From ceec4f492a26bf56bb4898d3b691e81aa1fcbe52 Mon Sep 17 00:00:00 2001 From: TinyOh Date: Sat, 29 Dec 2018 09:53:25 +0800 Subject: [PATCH] fix(ros): include publishOther and reduce the range --- .../ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) 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 d03ed32..56284d6 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 @@ -439,9 +439,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { // img_time_prev = data.img->timestamp; ++left_count_; - pthread_mutex_lock(&mutex_data); publishCamera(Stream::LEFT, data, left_count_, stamp); - pthread_mutex_unlock(&mutex_data); NODELET_DEBUG_STREAM( Stream::LEFT << ", count: " << left_count_ << ", frame_id: " << data.img->frame_id @@ -461,9 +459,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet { data.img->timestamp, Stream::RIGHT); ++right_count_; - pthread_mutex_lock(&mutex_data); publishCamera(Stream::RIGHT, data, right_count_, stamp); - pthread_mutex_unlock(&mutex_data); NODELET_DEBUG_STREAM( Stream::RIGHT << ", count: " << right_count_ << ", frame_id: " @@ -538,12 +534,14 @@ class ROSWrapperNodelet : public nodelet::Nodelet { header.seq = seq; header.stamp = stamp; header.frame_id = frame_ids_[stream]; + pthread_mutex_lock(&mutex_data); cv::Mat img = data.frame; if (stream == Stream::DISPARITY) { // 32FC1 > 8UC1 = MONO8 img.convertTo(img, CV_8UC1); } auto &&msg = cv_bridge::CvImage(header, camera_encodings_[stream], img).toImageMsg(); + pthread_mutex_unlock(&mutex_data); auto &&info = getCameraInfo(stream); info->header.stamp = msg->header.stamp; camera_publishers_[stream].publish(msg, info);