diff --git a/samples/tutorials/CMakeLists.txt b/samples/tutorials/CMakeLists.txt index 992c157..8e1eefa 100644 --- a/samples/tutorials/CMakeLists.txt +++ b/samples/tutorials/CMakeLists.txt @@ -127,10 +127,6 @@ make_executable2(ctrl_manual_exposure WITH_OPENCV ) -# intermediate level - -make_executable2(get_all_device_info SRCS intermediate/get_all_device_info.cc WITH_OPENCV) - if(PCL_FOUND) if(OpenCV_VERSION VERSION_LESS 4.0) diff --git a/samples/tutorials/intermediate/get_all_device_info.cc b/samples/tutorials/intermediate/get_all_device_info.cc deleted file mode 100644 index 1c335f7..0000000 --- a/samples/tutorials/intermediate/get_all_device_info.cc +++ /dev/null @@ -1,50 +0,0 @@ -// Copyright 2018 Slightech Co., Ltd. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -#include "mynteye/logger.h" -#include "mynteye/device/context.h" -#include "mynteye/device/device.h" - -MYNTEYE_USE_NAMESPACE - -int main(int argc, char *argv[]) { - glog_init _(argc, argv); - - LOG(INFO) << "Detecting MYNT EYE devices"; - Context context; - auto &&devices = context.devices(); - - size_t n = devices.size(); - if (n <= 0) { - LOG(ERROR) << "No MYNT EYE devices :("; - return 1; - } - - for (size_t i = 0; i < n; i++) { - auto &&device = devices[i]; - LOG(INFO) << "MYNT EYE device index: " << i; - LOG(INFO) << " Device name: " << device->GetInfo(Info::DEVICE_NAME); - LOG(INFO) << " Serial number: " << device->GetInfo(Info::SERIAL_NUMBER); - LOG(INFO) << " Firmware version: " - << device->GetInfo(Info::FIRMWARE_VERSION); - LOG(INFO) << " Hardware version: " - << device->GetInfo(Info::HARDWARE_VERSION); - LOG(INFO) << " Spec version: " << device->GetInfo(Info::SPEC_VERSION); - LOG(INFO) << " Lens type: " << device->GetInfo(Info::LENS_TYPE); - LOG(INFO) << " IMU type: " << device->GetInfo(Info::IMU_TYPE); - LOG(INFO) << " Nominal baseline: " - << device->GetInfo(Info::NOMINAL_BASELINE); - } - - return 0; -} diff --git a/tools/analytics/stamp_analytics.py b/tools/analytics/stamp_analytics.py index 2aa93d0..b36d3fb 100644 --- a/tools/analytics/stamp_analytics.py +++ b/tools/analytics/stamp_analytics.py @@ -15,7 +15,6 @@ # limitations under the License. # pylint: disable=missing-docstring - from __future__ import print_function import os @@ -27,7 +26,6 @@ sys.path.append(os.path.join(TOOLBOX_DIR, 'internal')) # pylint: disable=import-error,wrong-import-position from data import ROSBag, MYNTEYE, What - ANGLE_DEGREES = 'd' ANGLE_RADIANS = 'r' ANGLE_UNITS = (ANGLE_DEGREES, ANGLE_RADIANS) @@ -38,6 +36,11 @@ BIN_IMU_NAME = 'stamp_analytics_imu.bin' RESULT_FIGURE = 'stamp_analytics.png' +IMU_ALL = 0 +IMU_ACCEL = 1 +IMU_GYRO = 2 + + class BinDataset(object): def __init__(self, path, dataset_creator): @@ -147,9 +150,9 @@ class BinDataset(object): imgs_t_diff = np.diff(imgs['t']) # imus_t_diff = np.diff(imus['t']) - accel = imus[imus['flag'] == 1] + accel = imus[(imus['flag'] == IMU_ALL) | (imus['flag'] == IMU_ACCEL)] accel_t_diff = np.diff(accel['t']) - gyro = imus[imus['flag'] == 2] + gyro = imus[(imus['flag'] == IMU_ALL) | (imus['flag'] == IMU_GYRO)] gyro_t_diff = np.diff(gyro['t']) print('\ncount') diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index b9d7102..9eae936 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -72,14 +72,20 @@ class ROSWrapperNodelet : public nodelet::Nodelet { << (right_count_ / compute_time(time_end, right_time_beg_)); } if (imu_time_beg_ != -1) { - if (publish_imu_by_sync_) { - LOG(INFO) << "imu_sync_count: " << imu_sync_count_ << ", hz: " - << (imu_sync_count_ / - compute_time(time_end, imu_time_beg_)); - } else { - LOG(INFO) << "Imu count: " << imu_count_ << ", hz: " - << (imu_count_ / - compute_time(time_end, imu_time_beg_)); + if (model_ == Model::STANDARD) { + LOG(INFO) << "Imu count: " << imu_count_ << ", hz: " + << (imu_count_ / + compute_time(time_end, imu_time_beg_)); + } else { + if (publish_imu_by_sync_) { + LOG(INFO) << "imu_sync_count: " << imu_sync_count_ << ", hz: " + << (imu_sync_count_ / + compute_time(time_end, imu_time_beg_)); + } else { + LOG(INFO) << "Imu count: " << imu_count_ << ", hz: " + << (imu_count_ / + compute_time(time_end, imu_time_beg_)); + } } } @@ -1327,7 +1333,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { std::size_t imu_sync_count_ = 0; std::shared_ptr imu_accel_; std::shared_ptr imu_gyro_; - bool publish_imu_by_sync_ = false; + bool publish_imu_by_sync_ = true; std::map is_published_; bool is_motion_published_; bool is_started_;