Merge branch 'develop' of http://gitlab.mynt.com/mynteye/mynt-eye-sdk-2 into develop
This commit is contained in:
commit
effa0ba2ad
|
@ -127,10 +127,6 @@ make_executable2(ctrl_manual_exposure
|
||||||
WITH_OPENCV
|
WITH_OPENCV
|
||||||
)
|
)
|
||||||
|
|
||||||
# intermediate level
|
|
||||||
|
|
||||||
make_executable2(get_all_device_info SRCS intermediate/get_all_device_info.cc WITH_OPENCV)
|
|
||||||
|
|
||||||
if(PCL_FOUND)
|
if(PCL_FOUND)
|
||||||
|
|
||||||
if(OpenCV_VERSION VERSION_LESS 4.0)
|
if(OpenCV_VERSION VERSION_LESS 4.0)
|
||||||
|
|
|
@ -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;
|
|
||||||
}
|
|
|
@ -15,7 +15,6 @@
|
||||||
# limitations under the License.
|
# limitations under the License.
|
||||||
|
|
||||||
# pylint: disable=missing-docstring
|
# pylint: disable=missing-docstring
|
||||||
|
|
||||||
from __future__ import print_function
|
from __future__ import print_function
|
||||||
|
|
||||||
import os
|
import os
|
||||||
|
@ -27,7 +26,6 @@ sys.path.append(os.path.join(TOOLBOX_DIR, 'internal'))
|
||||||
# pylint: disable=import-error,wrong-import-position
|
# pylint: disable=import-error,wrong-import-position
|
||||||
from data import ROSBag, MYNTEYE, What
|
from data import ROSBag, MYNTEYE, What
|
||||||
|
|
||||||
|
|
||||||
ANGLE_DEGREES = 'd'
|
ANGLE_DEGREES = 'd'
|
||||||
ANGLE_RADIANS = 'r'
|
ANGLE_RADIANS = 'r'
|
||||||
ANGLE_UNITS = (ANGLE_DEGREES, ANGLE_RADIANS)
|
ANGLE_UNITS = (ANGLE_DEGREES, ANGLE_RADIANS)
|
||||||
|
@ -38,6 +36,11 @@ BIN_IMU_NAME = 'stamp_analytics_imu.bin'
|
||||||
RESULT_FIGURE = 'stamp_analytics.png'
|
RESULT_FIGURE = 'stamp_analytics.png'
|
||||||
|
|
||||||
|
|
||||||
|
IMU_ALL = 0
|
||||||
|
IMU_ACCEL = 1
|
||||||
|
IMU_GYRO = 2
|
||||||
|
|
||||||
|
|
||||||
class BinDataset(object):
|
class BinDataset(object):
|
||||||
|
|
||||||
def __init__(self, path, dataset_creator):
|
def __init__(self, path, dataset_creator):
|
||||||
|
@ -147,9 +150,9 @@ class BinDataset(object):
|
||||||
imgs_t_diff = np.diff(imgs['t'])
|
imgs_t_diff = np.diff(imgs['t'])
|
||||||
# imus_t_diff = np.diff(imus['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'])
|
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'])
|
gyro_t_diff = np.diff(gyro['t'])
|
||||||
|
|
||||||
print('\ncount')
|
print('\ncount')
|
||||||
|
|
|
@ -72,6 +72,11 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
<< (right_count_ / compute_time(time_end, right_time_beg_));
|
<< (right_count_ / compute_time(time_end, right_time_beg_));
|
||||||
}
|
}
|
||||||
if (imu_time_beg_ != -1) {
|
if (imu_time_beg_ != -1) {
|
||||||
|
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_) {
|
if (publish_imu_by_sync_) {
|
||||||
LOG(INFO) << "imu_sync_count: " << imu_sync_count_ << ", hz: "
|
LOG(INFO) << "imu_sync_count: " << imu_sync_count_ << ", hz: "
|
||||||
<< (imu_sync_count_ /
|
<< (imu_sync_count_ /
|
||||||
|
@ -82,6 +87,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
compute_time(time_end, imu_time_beg_));
|
compute_time(time_end, imu_time_beg_));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// ROS messages could not be reliably printed here, using glog instead :(
|
// ROS messages could not be reliably printed here, using glog instead :(
|
||||||
// ros::Duration(1).sleep(); // 1s
|
// ros::Duration(1).sleep(); // 1s
|
||||||
|
@ -1327,7 +1333,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
std::size_t imu_sync_count_ = 0;
|
std::size_t imu_sync_count_ = 0;
|
||||||
std::shared_ptr<ImuData> imu_accel_;
|
std::shared_ptr<ImuData> imu_accel_;
|
||||||
std::shared_ptr<ImuData> imu_gyro_;
|
std::shared_ptr<ImuData> imu_gyro_;
|
||||||
bool publish_imu_by_sync_ = false;
|
bool publish_imu_by_sync_ = true;
|
||||||
std::map<Stream, bool> is_published_;
|
std::map<Stream, bool> is_published_;
|
||||||
bool is_motion_published_;
|
bool is_motion_published_;
|
||||||
bool is_started_;
|
bool is_started_;
|
||||||
|
|
Loading…
Reference in New Issue
Block a user