sync_nodelet.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  Copyright (c) 2017, Intel Corporation
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without
6  modification, are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software without
17  specific prior written permission.
18 
19  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23  FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27  OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  *******************************************************************************/
30 
32 
34 
35 namespace realsense_camera
36 {
37  SyncNodelet::~SyncNodelet()
38  {
39  topic_thread_->join();
40  }
41 
42  /*
43  * Initialize the nodelet.
44  */
45  void SyncNodelet::onInit()
46  {
47  BaseNodelet::onInit();
48 
49  // start thread to publish topics
50  topic_thread_ =
51  boost::shared_ptr <boost::thread>(new boost::thread (boost::bind(&SyncNodelet::publishSyncTopics, this)));
52  }
53 
54  void SyncNodelet::publishSyncTopics() try
55  {
56  while (ros::ok())
57  {
58  if (start_stop_srv_called_ == true)
59  {
60  if (start_camera_ == true)
61  {
62  ROS_INFO_STREAM(nodelet_name_ << " - " << startCamera());
63  }
64  else
65  {
66  ROS_INFO_STREAM(nodelet_name_ << " - " << stopCamera());
67  }
68 
69  start_stop_srv_called_ = false;
70  }
71 
72  if (enable_[RS_STREAM_DEPTH] != rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0))
73  {
74  stopCamera();
75  setStreams();
76  startCamera();
77  }
78 
79  if (rs_is_device_streaming(rs_device_, 0) == 1)
80  {
81  rs_wait_for_frames(rs_device_, &rs_error_);
82  checkError();
83  topic_ts_ = ros::Time::now();
84  duplicate_depth_color_ = false;
85 
86  for (int stream=0; stream < STREAM_COUNT; stream++)
87  {
88  if (enable_[stream] == true)
89  {
90  publishTopic(static_cast<rs_stream>(stream));
91  }
92  }
93 
94  if (pointcloud_publisher_.getNumSubscribers() > 0 &&
95  rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1 && enable_pointcloud_ == true &&
96  (duplicate_depth_color_ == false)) // Skip publishing PointCloud if Depth or Color frame was duplicate
97  {
98  if (camera_publisher_[RS_STREAM_DEPTH].getNumSubscribers() <= 0)
99  {
100  setImageData(RS_STREAM_DEPTH);
101  }
102 
103  if (camera_publisher_[RS_STREAM_COLOR].getNumSubscribers() <= 0)
104  {
105  setImageData(RS_STREAM_COLOR);
106  }
107 
108  publishPCTopic();
109  }
110  }
111  }
112  }
113  catch(const rs::error & e)
114  {
115  ROS_ERROR_STREAM(nodelet_name_ << " - " << "RealSense error calling "
116  << e.get_failed_function() << "(" << e.get_failed_args() << "):\n "
117  << e.what());
118  ros::shutdown();
119  }
120  catch(const std::exception & e)
121  {
122  ROS_ERROR_STREAM(nodelet_name_ << " - " << e.what());
123  ros::shutdown();
124  }
125  catch(...)
126  {
127  ROS_ERROR_STREAM(nodelet_name_ << " - Caught unknown expection...shutting down!");
128  ros::shutdown();
129  }
130 
131  /*
132  * Publish topic.
133  */
134  void SyncNodelet::publishTopic(rs_stream stream_index)
135  {
136  // Publish stream only if there is at least one subscriber.
137  if (camera_publisher_[stream_index].getNumSubscribers() > 0 &&
138  rs_is_stream_enabled(rs_device_, (rs_stream) stream_index, 0) == 1)
139  {
140  double frame_ts = rs_get_frame_timestamp(rs_device_, (rs_stream) stream_index, 0);
141  if (ts_[stream_index] != frame_ts) // Publish frames only if its not duplicate
142  {
143  setImageData(stream_index);
144 
145  sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(),
146  encoding_[stream_index],
147  image_[stream_index]).toImageMsg();
148 
149  msg->header.frame_id = optical_frame_id_[stream_index];
150  msg->header.stamp = topic_ts_; // Publish timestamp to synchronize frames.
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];
155 
156  camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp;
157  camera_publisher_[stream_index].publish(msg, camera_info_ptr_[stream_index]);
158  }
159  else
160  {
161  if ((stream_index == RS_STREAM_DEPTH) || (stream_index == RS_STREAM_COLOR))
162  {
163  duplicate_depth_color_ = true; // Set this flag to true if Depth and/or Color frame is duplicate
164  }
165  }
166 
167  ts_[stream_index] = frame_ts;
168  }
169  }
170 
171  void SyncNodelet::setImageData(rs_stream stream_index)
172  {
173  if (stream_index == RS_STREAM_DEPTH)
174  {
175  // fill depth buffer
176  image_depth16_ = reinterpret_cast<const uint16_t *>(rs_get_frame_data(rs_device_, stream_index, 0));
177  float depth_scale_meters = rs_get_device_depth_scale(rs_device_, &rs_error_);
178  if (depth_scale_meters == MILLIMETER_METERS)
179  {
180  image_[stream_index].data = (unsigned char *) image_depth16_;
181  }
182  else
183  {
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));
189  }
190  }
191  else if (stream_index == RS_STREAM_COLOR)
192  {
193  image_[stream_index].data = (unsigned char *) (rs_get_frame_data(rs_device_, RS_STREAM_RECTIFIED_COLOR, 0));
194  }
195  else
196  {
197  image_[stream_index].data = (unsigned char *) (rs_get_frame_data(rs_device_, stream_index, 0));
198  }
199  }
200 } // namespace realsense_camera
const std::string & get_failed_args() const
rs_error * e
const float MILLIMETER_METERS
Definition: constants.h:85
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
rs_error * rs_error_
stream
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)
ROSCPP_DECL bool ok()
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)
const int STREAM_COUNT
Definition: constants.h:43
#define ROS_INFO_STREAM(args)
rs_stream
GLsizeiptr size
static Time now()
ROSCPP_DECL void shutdown()
int rs_is_device_streaming(const rs_device *device, rs_error **error)
#define ROS_ERROR_STREAM(args)
RS_STREAM_DEPTH
const std::string & get_failed_function() const
sensor_msgs::ImagePtr toImageMsg() const
RS_STREAM_COLOR


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Mon Jun 10 2019 14:40:37