diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch index c40222e..e477f62 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch @@ -13,8 +13,8 @@ - - + + @@ -105,8 +105,8 @@ - - + + diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz b/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz index d378a1a..c43513f 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz @@ -82,11 +82,11 @@ Visualization Manager: Displays: - Class: rviz/Image Enabled: true - Image Topic: /mynteye/left/image_gray + Image Topic: /mynteye/left/image_mono Max Value: 1 Median window: 5 Min Value: 0 - Name: LeftGray + Name: LeftMono Normalize Range: true Queue Size: 2 Transport Hint: raw @@ -94,18 +94,18 @@ Visualization Manager: Value: true - Class: rviz/Image Enabled: true - Image Topic: /mynteye/right/image_gray + Image Topic: /mynteye/right/image_mono Max Value: 1 Median window: 5 Min Value: 0 - Name: RightGray + Name: RightMono Normalize Range: true Queue Size: 2 Transport Hint: raw Unreliable: false Value: true - Enabled: false - Name: Gray + Enabled: true + Name: Mono - Class: rviz/Group Displays: - Class: rviz/Image 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 d4b9c52..dd33f48 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 @@ -115,13 +115,13 @@ class ROSWrapperNodelet : public nodelet::Nodelet { private_nh_.getParam(it->second + "_topic", stream_topics[it->first]); } - std::map gray_names{{Stream::LEFT, "left_gray"}, - {Stream::RIGHT, "right_gray"}}; + std::map mono_names{{Stream::LEFT, "left_mono"}, + {Stream::RIGHT, "right_mono"}}; - std::map gray_topics{}; - for (auto &&it = gray_names.begin(); it != gray_names.end(); ++it) { - gray_topics[it->first] = it->second; - private_nh_.getParam(it->second + "_topic", gray_topics[it->first]); + std::map mono_topics{}; + for (auto &&it = mono_names.begin(); it != mono_names.end(); ++it) { + mono_topics[it->first] = it->second; + private_nh_.getParam(it->second + "_topic", mono_topics[it->first]); } std::string imu_topic = "imu"; @@ -188,10 +188,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet { NODELET_INFO_STREAM("Advertized on topic " << topic); } - for (auto &&it = gray_topics.begin(); it != gray_topics.end(); ++it) { - auto &&topic = gray_topics[it->first]; + for (auto &&it = mono_topics.begin(); it != mono_topics.end(); ++it) { + auto &&topic = mono_topics[it->first]; if (it->first == Stream::LEFT || it->first == Stream::RIGHT) { // camera - gray_publishers_[it->first] = it_mynteye.advertiseCamera(topic, 1); + mono_publishers_[it->first] = it_mynteye.advertiseCamera(topic, 1); } NODELET_INFO_STREAM("Advertized on topic " << topic); } @@ -291,7 +291,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { ++left_count_; publishCamera(Stream::LEFT, data, left_count_, stamp); - publishGray(Stream::LEFT, data, left_count_, stamp); + publishMono(Stream::LEFT, data, left_count_, stamp); NODELET_DEBUG_STREAM( Stream::LEFT << ", count: " << left_count_ << ", frame_id: " << data.img->frame_id @@ -305,7 +305,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { ++right_count_; publishCamera(Stream::RIGHT, data, right_count_, stamp); - publishGray(Stream::RIGHT, data, right_count_, stamp); + publishMono(Stream::RIGHT, data, right_count_, stamp); NODELET_DEBUG_STREAM( Stream::RIGHT << ", count: " << right_count_ << ", frame_id: " << data.img->frame_id @@ -419,21 +419,21 @@ class ROSWrapperNodelet : public nodelet::Nodelet { image_publishers_[stream].publish(msg); } - void publishGray( + void publishMono( const Stream &stream, const api::StreamData &data, std::uint32_t seq, ros::Time stamp) { - if (gray_publishers_[stream].getNumSubscribers() == 0) + if (mono_publishers_[stream].getNumSubscribers() == 0) return; std_msgs::Header header; header.seq = seq; header.stamp = stamp; header.frame_id = frame_ids_[stream]; - cv::Mat gray; - cv::cvtColor(data.frame, gray, CV_RGB2GRAY); - auto &&msg = cv_bridge::CvImage(header, enc::MONO8, gray).toImageMsg(); + cv::Mat mono; + cv::cvtColor(data.frame, mono, CV_RGB2GRAY); + auto &&msg = cv_bridge::CvImage(header, enc::MONO8, mono).toImageMsg(); auto &&info = getCameraInfo(stream); info->header.stamp = msg->header.stamp; - gray_publishers_[stream].publish(msg, info); + mono_publishers_[stream].publish(msg, info); } void publishPoints( @@ -878,8 +878,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet { std::map image_publishers_; std::map image_encodings_; - // gray: LEFT, RIGHT - std::map gray_publishers_; + // mono: LEFT, RIGHT + std::map mono_publishers_; // pointcloud: POINTS ros::Publisher points_publisher_;