37 SyncNodelet::~SyncNodelet()
39 topic_thread_->join();
45 void SyncNodelet::onInit()
47 BaseNodelet::onInit();
54 void SyncNodelet::publishSyncTopics()
try 58 if (start_stop_srv_called_ ==
true)
60 if (start_camera_ ==
true)
69 start_stop_srv_called_ =
false;
84 duplicate_depth_color_ =
false;
88 if (enable_[
stream] ==
true)
90 publishTopic(static_cast<rs_stream>(
stream));
94 if (pointcloud_publisher_.getNumSubscribers() > 0 &&
96 (duplicate_depth_color_ ==
false))
120 catch(
const std::exception & e)
127 ROS_ERROR_STREAM(nodelet_name_ <<
" - Caught unknown expection...shutting down!");
137 if (camera_publisher_[stream_index].getNumSubscribers() > 0 &&
141 if (ts_[stream_index] != frame_ts)
143 setImageData(stream_index);
146 encoding_[stream_index],
149 msg->header.frame_id = optical_frame_id_[stream_index];
150 msg->header.stamp = topic_ts_;
151 msg->width = image_[stream_index].cols;
152 msg->height = image_[stream_index].rows;
153 msg->is_bigendian =
false;
154 msg->step = step_[stream_index];
156 camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp;
157 camera_publisher_[stream_index].publish(msg, camera_info_ptr_[stream_index]);
163 duplicate_depth_color_ =
true;
167 ts_[stream_index] = frame_ts;
176 image_depth16_ =
reinterpret_cast<const uint16_t *
>(
rs_get_frame_data(rs_device_, stream_index, 0));
180 image_[stream_index].data = (
unsigned char *) image_depth16_;
184 cvWrapper_ = cv::Mat(image_[stream_index].
size(), cv_type_[stream_index],
185 const_cast<void *>(reinterpret_cast<const void *>(image_depth16_)),
186 step_[stream_index]);
187 cvWrapper_.convertTo(image_[stream_index], cv_type_[stream_index],
188 static_cast<double>(depth_scale_meters) / static_cast<double>(
MILLIMETER_METERS));
197 image_[stream_index].data = (
unsigned char *) (
rs_get_frame_data(rs_device_, stream_index, 0));
const std::string & get_failed_args() const
const float MILLIMETER_METERS
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
float rs_get_device_depth_scale(const rs_device *device, rs_error **error)
double rs_get_frame_timestamp(const rs_device *device, rs_stream stream, rs_error **error)
int rs_is_stream_enabled(const rs_device *device, rs_stream stream, rs_error **error)
void rs_wait_for_frames(rs_device *device, rs_error **error)
RS_STREAM_RECTIFIED_COLOR
const void * rs_get_frame_data(const rs_device *device, rs_stream stream, rs_error **error)
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void shutdown()
int rs_is_device_streaming(const rs_device *device, rs_error **error)
#define ROS_ERROR_STREAM(args)
const std::string & get_failed_function() const
sensor_msgs::ImagePtr toImageMsg() const