Compare commits
10 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
0c5a4f7014 | ||
|
|
f0d2950701 | ||
|
|
4fcdb6fc7b | ||
|
|
0fc1196b52 | ||
|
|
ee19a8c857 | ||
|
|
6d39773439 | ||
|
|
677c10925f | ||
|
|
5e8bc7c05b | ||
|
|
ae8cc4cae2 | ||
|
|
9ef4820226 |
10
Makefile
10
Makefile
@@ -24,7 +24,7 @@ MKFILE_DIR := $(patsubst %/,%,$(dir $(MKFILE_PATH)))
|
||||
|
||||
SUDO ?= sudo
|
||||
|
||||
.DEFAULT_GOAL := help
|
||||
.DEFAULT_GOAL := all
|
||||
|
||||
help:
|
||||
@echo "Usage:"
|
||||
@@ -44,7 +44,7 @@ help:
|
||||
|
||||
.PHONY: help
|
||||
|
||||
all: test samples tools
|
||||
all: init samples tools ros
|
||||
|
||||
.PHONY: all
|
||||
|
||||
@@ -78,7 +78,7 @@ submodules:
|
||||
|
||||
# init
|
||||
|
||||
init: submodules
|
||||
init:
|
||||
@$(call echo,Make $@)
|
||||
@$(SH) ./scripts/init.sh $(INIT_OPTIONS)
|
||||
|
||||
@@ -86,7 +86,7 @@ init: submodules
|
||||
|
||||
# build
|
||||
|
||||
build: submodules
|
||||
build:
|
||||
@$(call echo,Make $@)
|
||||
ifeq ($(HOST_OS),Win)
|
||||
@$(call cmake_build,./_build,..,-DCMAKE_INSTALL_PREFIX=$(MKFILE_DIR)/_install)
|
||||
@@ -98,7 +98,7 @@ endif
|
||||
|
||||
# test
|
||||
|
||||
test: install
|
||||
test: submodules install
|
||||
@$(call echo,Make $@)
|
||||
@$(call echo,Make gtest,33)
|
||||
ifeq ($(HOST_OS),Win)
|
||||
|
||||
12
README.md
12
README.md
@@ -1,6 +1,6 @@
|
||||
# MYNT® EYE S SDK
|
||||
|
||||
[](https://github.com/slightech/MYNT-EYE-S-SDK)
|
||||
[](https://github.com/slightech/MYNT-EYE-S-SDK)
|
||||
|
||||
## Overview
|
||||
|
||||
@@ -17,11 +17,11 @@ Please follow the guide doc to install the SDK on different platforms.
|
||||
## Documentations
|
||||
|
||||
* [API Doc](https://github.com/slightech/MYNT-EYE-S-SDK/releases): API reference, some guides and data spec.
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2501756/mynt-eye-sdk-apidoc-2.2.1-rc-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2501763/mynt-eye-sdk-apidoc-2.2.1-rc-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2501770/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2501782/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans.zip) [](http://doc.myntai.com/resource/api/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans/mynt-eye-sdk-apidoc-2.2.1-rc-zh-Hans/index.html)
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2612865/mynt-eye-s-sdk-apidoc-2.2.2-rc1-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2612866/mynt-eye-s-sdk-apidoc-2.2.2-rc1-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2612867/mynt-eye-s-sdk-apidoc-2.2.2-rc1-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK/files/2612868/mynt-eye-s-sdk-apidoc-2.2.2-rc1-zh-Hans.zip) [](http://doc.myntai.com/resource/api/mynt-eye-s-sdk-apidoc-2.2.2-rc1-zh-Hans/mynt-eye-s-sdk-apidoc-2.2.2-rc1-zh-Hans/index.html)
|
||||
* [Guide Doc](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/releases): How to install and start using the SDK.
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2501821/mynt-eye-sdk-guide-2.2.1-rc-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2501822/mynt-eye-sdk-guide-2.2.1-rc-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2501823/mynt-eye-sdk-guide-2.2.1-rc-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2501827/mynt-eye-sdk-guide-2.2.1-rc-zh-Hans.zip) [](http://doc.myntai.com/resource/sdk/mynt-eye-sdk-guide-2.2.1-rc-zh-Hans/mynt-eye-sdk-guide-2.2.1-rc-zh-Hans/index.html)
|
||||
* en: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2612872/mynt-eye-s-sdk-guide-2.2.2-rc1-en.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2612873/mynt-eye-s-sdk-guide-2.2.2-rc1-en.zip) [](https://slightech.github.io/MYNT-EYE-S-SDK-Guide/)
|
||||
* zh-Hans: [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2612874/mynt-eye-s-sdk-guide-2.2.2-rc1-zh-Hans.pdf) [](https://github.com/slightech/MYNT-EYE-S-SDK-Guide/files/2612875/mynt-eye-s-sdk-guide-2.2.2-rc1-zh-Hans.zip) [](http://doc.myntai.com/resource/sdk/mynt-eye-s-sdk-guide-2.2.2-rc1-zh-Hans/mynt-eye-s-sdk-guide-2.2.2-rc1-zh-Hans/index.html)
|
||||
|
||||
> Supported languages: `en`, `zh-Hans`.
|
||||
|
||||
@@ -29,7 +29,7 @@ Please follow the guide doc to install the SDK on different platforms.
|
||||
|
||||
[MYNTEYE_BOX]: http://doc.myntai.com/mynteye/s/download
|
||||
|
||||
Get firmwares from our online disks: [MYNTEYE_BOX][]. The latest version is `2.2.1`.
|
||||
Get firmwares from our online disks: [MYNTEYE_BOX][]. The latest version is `2.2.2`.
|
||||
|
||||
## Usage
|
||||
|
||||
|
||||
@@ -38,13 +38,13 @@ PROJECT_NAME = "MYNT EYE S SDK"
|
||||
# could be handy for archiving the generated documentation or if some version
|
||||
# control system is used.
|
||||
|
||||
PROJECT_NUMBER = 2.2.2-rc0
|
||||
PROJECT_NUMBER = 2.2.2-rc1
|
||||
|
||||
# Using the PROJECT_BRIEF tag one can provide an optional one line description
|
||||
# for a project that appears at the top of each page and should give viewer a
|
||||
# quick idea about the purpose of the project. Keep the description short.
|
||||
|
||||
PROJECT_BRIEF = http://www.myntai.com/camera
|
||||
PROJECT_BRIEF = http://www.myntai.com/mynteye/standard
|
||||
|
||||
# With the PROJECT_LOGO tag one can specify a logo or an icon that is included
|
||||
# in the documentation. The maximum height of the logo should not exceed 55
|
||||
|
||||
@@ -38,13 +38,13 @@ PROJECT_NAME = "MYNT EYE S SDK"
|
||||
# could be handy for archiving the generated documentation or if some version
|
||||
# control system is used.
|
||||
|
||||
PROJECT_NUMBER = 2.2.2-rc0
|
||||
PROJECT_NUMBER = 2.2.2-rc1
|
||||
|
||||
# Using the PROJECT_BRIEF tag one can provide an optional one line description
|
||||
# for a project that appears at the top of each page and should give viewer a
|
||||
# quick idea about the purpose of the project. Keep the description short.
|
||||
|
||||
PROJECT_BRIEF = http://www.myntai.com/camera
|
||||
PROJECT_BRIEF = http://www.myntai.com/mynteye/standard
|
||||
|
||||
# With the PROJECT_LOGO tag one can specify a logo or an icon that is included
|
||||
# in the documentation. The maximum height of the logo should not exceed 55
|
||||
|
||||
@@ -26,3 +26,5 @@
|
||||
| HDR 模式 | hdr_mode | 1 | 0 | 0 | 1 | √ | 0x1F | XU_CAM_CTRL | 0:10-bit;1:12-bit |
|
||||
| 零漂标定 | zero_drift_calibration | | - | - | - | × | - | XU_HALF_DUPLEX | |
|
||||
| 擦除芯片 | erase_chip | | - | - | - | × | - | XU_HALF_DUPLEX | |
|
||||
| 加速度计量程 | accelerometer_range | 2 | 12 | 6 | 48 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
| 陀螺仪量程 | gyroscope_range | 2 | 1000 | 250 | 4000 | √ | - | XU_CAM_CTRL | 0x0100 | |
|
||||
|
||||
@@ -195,6 +195,18 @@ enum class Option : std::uint8_t {
|
||||
ZERO_DRIFT_CALIBRATION,
|
||||
/** Erase chip */
|
||||
ERASE_CHIP,
|
||||
/**
|
||||
* The range of accelerometer
|
||||
*
|
||||
* values: {4,8,16,32}, default: 8
|
||||
*/
|
||||
ACCELEROMETER_RANGE,
|
||||
/**
|
||||
* The range of gyroscope
|
||||
*
|
||||
* values: {500,1000,2000,4000}, default: 1000
|
||||
*/
|
||||
GYROSCOPE_RANGE,
|
||||
/** Last guard */
|
||||
LAST
|
||||
};
|
||||
|
||||
@@ -114,6 +114,7 @@ make_executable2(get_with_plugin SRCS data/get_with_plugin.cc WITH_OPENCV)
|
||||
## control
|
||||
|
||||
make_executable2(ctrl_framerate SRCS control/framerate.cc WITH_OPENCV)
|
||||
make_executable2(ctrl_imu_range SRCS control/imu_range.cc WITH_OPENCV)
|
||||
make_executable2(ctrl_auto_exposure
|
||||
SRCS control/auto_exposure.cc util/cv_painter.cc
|
||||
WITH_OPENCV
|
||||
|
||||
89
samples/tutorials/control/imu_range.cc
Normal file
89
samples/tutorials/control/imu_range.cc
Normal file
@@ -0,0 +1,89 @@
|
||||
// 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 <atomic>
|
||||
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
|
||||
#include "mynteye/logger.h"
|
||||
#include "mynteye/api/api.h"
|
||||
#include "mynteye/util/times.h"
|
||||
|
||||
MYNTEYE_USE_NAMESPACE
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
auto &&api = API::Create(argc, argv);
|
||||
if (!api)
|
||||
return 1;
|
||||
|
||||
// ACCELEROMETER_RANGE values: 4, 8, 16, 32
|
||||
api->SetOptionValue(Option::ACCELEROMETER_RANGE, 8);
|
||||
// GYROSCOPE_RANGE values: 500, 1000, 2000, 4000
|
||||
api->SetOptionValue(Option::GYROSCOPE_RANGE, 1000);
|
||||
|
||||
LOG(INFO) << "Set ACCELEROMETER_RANGE to "
|
||||
<< api->GetOptionValue(Option::ACCELEROMETER_RANGE);
|
||||
LOG(INFO) << "Set GYROSCOPE_RANGE to "
|
||||
<< api->GetOptionValue(Option::GYROSCOPE_RANGE);
|
||||
|
||||
// Count img
|
||||
std::atomic_uint img_count(0);
|
||||
api->SetStreamCallback(
|
||||
Stream::LEFT, [&img_count](const api::StreamData &data) {
|
||||
CHECK_NOTNULL(data.img);
|
||||
++img_count;
|
||||
});
|
||||
|
||||
// Count imu
|
||||
std::atomic_uint imu_count(0);
|
||||
api->SetMotionCallback([&imu_count](const api::MotionData &data) {
|
||||
CHECK_NOTNULL(data.imu);
|
||||
++imu_count;
|
||||
});
|
||||
|
||||
api->Start(Source::ALL);
|
||||
|
||||
cv::namedWindow("frame");
|
||||
|
||||
auto &&time_beg = times::now();
|
||||
while (true) {
|
||||
api->WaitForStreams();
|
||||
|
||||
auto &&left_data = api->GetStreamData(Stream::LEFT);
|
||||
auto &&right_data = api->GetStreamData(Stream::RIGHT);
|
||||
|
||||
cv::Mat img;
|
||||
cv::hconcat(left_data.frame, right_data.frame, img);
|
||||
cv::imshow("frame", img);
|
||||
|
||||
char key = static_cast<char>(cv::waitKey(1));
|
||||
if (key == 27 || key == 'q' || key == 'Q') { // ESC/Q
|
||||
break;
|
||||
}
|
||||
}
|
||||
auto &&time_end = times::now();
|
||||
|
||||
api->Stop(Source::ALL);
|
||||
|
||||
// Calculate img fps and imu hz
|
||||
float elapsed_ms =
|
||||
times::count<times::microseconds>(time_end - time_beg) * 0.001f;
|
||||
LOG(INFO) << "Time beg: " << times::to_local_string(time_beg)
|
||||
<< ", end: " << times::to_local_string(time_end)
|
||||
<< ", cost: " << elapsed_ms << "ms";
|
||||
LOG(INFO) << "Img count: " << img_count
|
||||
<< ", fps: " << (1000.f * img_count / elapsed_ms);
|
||||
LOG(INFO) << "Imu count: " << imu_count
|
||||
<< ", hz: " << (1000.f * imu_count / elapsed_ms);
|
||||
return 0;
|
||||
}
|
||||
@@ -63,6 +63,12 @@ int XuCamCtrlId(Option option) {
|
||||
case Option::FRAME_RATE:
|
||||
return 7;
|
||||
break;
|
||||
case Option::ACCELEROMETER_RANGE:
|
||||
return 9;
|
||||
break;
|
||||
case Option::GYROSCOPE_RANGE:
|
||||
return 10;
|
||||
break;
|
||||
default:
|
||||
LOG(FATAL) << "No cam ctrl id for " << option;
|
||||
}
|
||||
@@ -135,7 +141,8 @@ void Channels::UpdateControlInfos() {
|
||||
for (auto &&option : std::vector<Option>{
|
||||
Option::FRAME_RATE, Option::IMU_FREQUENCY, Option::EXPOSURE_MODE,
|
||||
Option::MAX_GAIN, Option::MAX_EXPOSURE_TIME,
|
||||
Option::DESIRED_BRIGHTNESS, Option::IR_CONTROL, Option::HDR_MODE}) {
|
||||
Option::DESIRED_BRIGHTNESS, Option::IR_CONTROL, Option::HDR_MODE,
|
||||
Option::ACCELEROMETER_RANGE, Option::GYROSCOPE_RANGE}) {
|
||||
control_infos_[option] = XuControlInfo(option);
|
||||
}
|
||||
|
||||
@@ -177,6 +184,8 @@ std::int32_t Channels::GetControlValue(const Option &option) const {
|
||||
case Option::DESIRED_BRIGHTNESS:
|
||||
case Option::IR_CONTROL:
|
||||
case Option::HDR_MODE:
|
||||
case Option::ACCELEROMETER_RANGE:
|
||||
case Option::GYROSCOPE_RANGE:
|
||||
return XuCamCtrlGet(option);
|
||||
case Option::ZERO_DRIFT_CALIBRATION:
|
||||
case Option::ERASE_CHIP:
|
||||
@@ -232,6 +241,16 @@ void Channels::SetControlValue(const Option &option, std::int32_t value) {
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
case Option::ACCELEROMETER_RANGE: {
|
||||
if (!in_range() || !in_values({4, 8, 16, 32}))
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
case Option::GYROSCOPE_RANGE: {
|
||||
if (!in_range() || !in_values({500, 1000, 2000, 4000}))
|
||||
break;
|
||||
XuCamCtrlSet(option, value);
|
||||
} break;
|
||||
case Option::EXPOSURE_MODE:
|
||||
case Option::MAX_GAIN:
|
||||
case Option::MAX_EXPOSURE_TIME:
|
||||
@@ -268,6 +287,8 @@ bool Channels::RunControlAction(const Option &option) const {
|
||||
case Option::DESIRED_BRIGHTNESS:
|
||||
case Option::IR_CONTROL:
|
||||
case Option::HDR_MODE:
|
||||
case Option::ACCELEROMETER_RANGE:
|
||||
case Option::GYROSCOPE_RANGE:
|
||||
LOG(WARNING) << option << " run action useless";
|
||||
return false;
|
||||
default:
|
||||
|
||||
@@ -26,7 +26,8 @@ const std::map<Model, OptionSupports> option_supports_map = {
|
||||
{Option::GAIN, Option::BRIGHTNESS, Option::CONTRAST, Option::FRAME_RATE,
|
||||
Option::IMU_FREQUENCY, Option::EXPOSURE_MODE, Option::MAX_GAIN,
|
||||
Option::MAX_EXPOSURE_TIME, Option::DESIRED_BRIGHTNESS, Option::IR_CONTROL,
|
||||
Option::HDR_MODE, Option::ZERO_DRIFT_CALIBRATION, Option::ERASE_CHIP}}};
|
||||
Option::HDR_MODE, Option::ZERO_DRIFT_CALIBRATION, Option::ERASE_CHIP,
|
||||
Option::ACCELEROMETER_RANGE, Option::GYROSCOPE_RANGE}}};
|
||||
|
||||
const std::map<Model, std::map<Capabilities, StreamRequests>>
|
||||
stream_requests_map = {
|
||||
|
||||
@@ -34,6 +34,14 @@ Motions::~Motions() {
|
||||
void Motions::SetMotionCallback(motion_callback_t callback) {
|
||||
motion_callback_ = callback;
|
||||
if (motion_callback_) {
|
||||
accel_range = channels_->GetControlValue(Option::ACCELEROMETER_RANGE);
|
||||
if (accel_range == -1)
|
||||
accel_range = 8;
|
||||
|
||||
gyro_range = channels_->GetControlValue(Option::GYROSCOPE_RANGE);
|
||||
if (gyro_range == -1)
|
||||
gyro_range = 1000;
|
||||
|
||||
channels_->SetImuCallback([this](const ImuPacket &packet) {
|
||||
if (!motion_callback_ && !motion_datas_enabled_) {
|
||||
return;
|
||||
@@ -46,12 +54,12 @@ void Motions::SetMotionCallback(motion_callback_t callback) {
|
||||
// LOG(WARNING) << "Imu timestamp offset is incorrect";
|
||||
// }
|
||||
imu->timestamp = packet.timestamp + seg.offset;
|
||||
imu->accel[0] = seg.accel[0] * 8.f / 0x10000;
|
||||
imu->accel[1] = seg.accel[1] * 8.f / 0x10000;
|
||||
imu->accel[2] = seg.accel[2] * 8.f / 0x10000;
|
||||
imu->gyro[0] = seg.gyro[0] * 1000.f / 0x10000;
|
||||
imu->gyro[1] = seg.gyro[1] * 1000.f / 0x10000;
|
||||
imu->gyro[2] = seg.gyro[2] * 1000.f / 0x10000;
|
||||
imu->accel[0] = seg.accel[0] * 1.f * accel_range / 0x10000;
|
||||
imu->accel[1] = seg.accel[1] * 1.f * accel_range / 0x10000;
|
||||
imu->accel[2] = seg.accel[2] * 1.f * accel_range / 0x10000;
|
||||
imu->gyro[0] = seg.gyro[0] * 1.f * gyro_range / 0x10000;
|
||||
imu->gyro[1] = seg.gyro[1] * 1.f * gyro_range / 0x10000;
|
||||
imu->gyro[2] = seg.gyro[2] * 1.f * gyro_range / 0x10000;
|
||||
imu->temperature = seg.temperature / 326.8f + 25;
|
||||
|
||||
std::lock_guard<std::mutex> _(mtx_datas_);
|
||||
|
||||
@@ -57,6 +57,9 @@ class Motions {
|
||||
bool is_imu_tracking;
|
||||
|
||||
std::mutex mtx_datas_;
|
||||
|
||||
int accel_range = 8;
|
||||
int gyro_range = 1000;
|
||||
};
|
||||
|
||||
MYNTEYE_END_NAMESPACE
|
||||
|
||||
@@ -114,6 +114,8 @@ const char *to_string(const Option &value) {
|
||||
CASE(HDR_MODE)
|
||||
CASE(ZERO_DRIFT_CALIBRATION)
|
||||
CASE(ERASE_CHIP)
|
||||
CASE(ACCELEROMETER_RANGE)
|
||||
CASE(GYROSCOPE_RANGE)
|
||||
default:
|
||||
CHECK(is_valid(value));
|
||||
return "Option::UNKNOWN";
|
||||
|
||||
@@ -86,6 +86,14 @@
|
||||
<arg name="hdr_mode" default="-1" />
|
||||
<!-- <arg name="hdr_mode" default="0" /> -->
|
||||
|
||||
<!-- accel_range range: {4,8,16,32} -->
|
||||
<arg name="accel_range" default="-1" />
|
||||
<!-- <arg name="accel_range" default="8" /> -->
|
||||
|
||||
<!-- gyro_range range: {500,1000,2000,4000} -->
|
||||
<arg name="gyro_range" default="-1" />
|
||||
<!-- <arg name="gyro_range" default="1000" /> -->
|
||||
|
||||
<!-- Push down all topics/nodelets into "mynteye" namespace -->
|
||||
<group ns="$(arg mynteye)">
|
||||
|
||||
@@ -143,6 +151,8 @@
|
||||
<param name="desired_brightness" value="$(arg desired_brightness)" />
|
||||
<param name="ir_control" value="$(arg ir_control)" />
|
||||
<param name="hdr_mode" value="$(arg hdr_mode)" />
|
||||
<param name="accel_range" value="$(arg accel_range)" />
|
||||
<param name="gyro_range" value="$(arg gyro_range)" />
|
||||
|
||||
</node>
|
||||
|
||||
|
||||
@@ -160,6 +160,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
{Option::DESIRED_BRIGHTNESS, "desired_brightness"},
|
||||
{Option::IR_CONTROL, "ir_control"},
|
||||
{Option::HDR_MODE, "hdr_mode"},
|
||||
{Option::ACCELEROMETER_RANGE, "accel_range"},
|
||||
{Option::GYROSCOPE_RANGE, "gyro_range"}
|
||||
};
|
||||
for (auto &&it = option_names.begin(); it != option_names.end(); ++it) {
|
||||
if (!api_->Supports(it->first))
|
||||
@@ -196,10 +198,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||
{Stream::DISPARITY_NORMALIZED, enc::MONO8},
|
||||
{Stream::DEPTH, enc::MONO16}};
|
||||
|
||||
pub_imu_ = nh_.advertise<sensor_msgs::Imu>(imu_topic, 1);
|
||||
pub_imu_ = nh_.advertise<sensor_msgs::Imu>(imu_topic, 100);
|
||||
NODELET_INFO_STREAM("Advertized on topic " << imu_topic);
|
||||
|
||||
pub_temp_ = nh_.advertise<mynt_eye_ros_wrapper::Temp>(temp_topic, 1);
|
||||
pub_temp_ = nh_.advertise<mynt_eye_ros_wrapper::Temp>(temp_topic, 100);
|
||||
NODELET_INFO_STREAM("Advertized on topic " << temp_topic);
|
||||
|
||||
// stream toggles
|
||||
|
||||
Reference in New Issue
Block a user