node.cpp
Go to the documentation of this file.
1 
42 #include <ros/ros.h>
45 #include <sensor_msgs/PointCloud2.h>
46 #include <cv_bridge/cv_bridge.h>
47 #include <boost/thread.hpp>
48 #include <sensor_msgs/CameraInfo.h>
49 #include <std_msgs/ByteMultiArray.h>
50 
52 const bool SUPPRESS_INVALID_POINTS = true;
53 
55 const uint16_t NARE_DISTANCE_VALUE = 0xffffU;
59 std::string g_frame_id;
61 bool g_publish_all = false;
62 
63 boost::mutex g_mtx_data;
65 
66 void publish_frame(const Driver_3DCS::Data &data);
67 
69  g_mtx_data.lock();
70  publish_frame(*g_data);
71  g_mtx_data.unlock();
72 }
73 
75  //update data in queue and
76  //detach publishing data from network thread
77 
78  if(g_publish_all || g_mtx_data.try_lock()) {
79  if(g_publish_all)
80  g_mtx_data.lock();
81  g_data = data;
82  g_mtx_data.unlock();
83 
84  boost::thread thr(thr_publish_frame);
85  }
86  else
87  ROS_WARN("skipping frame");
88 }
89 
90 void publish_frame(const Driver_3DCS::Data &data) {
91  bool published_anything = false;
92 
93  sensor_msgs::ImagePtr msg;
94  std_msgs::Header header;
95  header.stamp = ros::Time::now();
96  header.frame_id = g_frame_id;
97 
98  if(g_pub_camera_info.getNumSubscribers()>0) {
99  published_anything = true;
100 
101  sensor_msgs::CameraInfo ci;
102  ci.header = header;
103 
104  ci.height = data.getCameraParameters().height;
105  ci.width = data.getCameraParameters().width;
106 
107  ci.D.clear();
108  ci.D.resize(5,0);
109  ci.D[0] = data.getCameraParameters().k1;
110  ci.D[1] = data.getCameraParameters().k2;
111 
112  for(int i=0; i<9; i++) ci.K[i]=0;
113  ci.K[0] = data.getCameraParameters().fx;
114  ci.K[4] = data.getCameraParameters().fy;
115  ci.K[2] = data.getCameraParameters().cx;
116  ci.K[5] = data.getCameraParameters().cy;
117 
118  for(int i=0; i<12; i++)
119  ci.P[i] = 0;//data.getCameraParameters().cam2worldMatrix[i];
120  //TODO:....
121  ci.P[0] = data.getCameraParameters().fx;
122  ci.P[5] = data.getCameraParameters().fy;
123  ci.P[10] = 1;
124  ci.P[2] = data.getCameraParameters().cx;
125  ci.P[6] = data.getCameraParameters().cy;
126 
127  g_pub_camera_info.publish(ci);
128  }
129 
130  if(g_pub_depth.getNumSubscribers()>0) {
131  published_anything = true;
132 
133  msg = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::TYPE_16UC1, data.get_distance()).toImageMsg();
134  msg->header = header;
135  g_pub_depth.publish(msg);
136  }
137  if(g_pub_confidence.getNumSubscribers()>0) {
138  published_anything = true;
139 
140  msg = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::TYPE_16UC1, data.get_confidence()).toImageMsg();
141  msg->header = header;
142  g_pub_confidence.publish(msg);
143  }
144  if(g_pub_intensity.getNumSubscribers()>0) {
145  published_anything = true;
146 
147  msg = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::TYPE_16UC1, data.get_intensity()).toImageMsg();
148  msg->header = header;
149  g_pub_intensity.publish(msg);
150  }
151  if(g_pub_points.getNumSubscribers()>0) {
152  published_anything = true;
153 
154  typedef sensor_msgs::PointCloud2 PointCloud;
155 
156  // Allocate new point cloud message
157  PointCloud::Ptr cloud_msg (new PointCloud);
158  cloud_msg->header = header; // Use depth image time stamp
159  cloud_msg->height = data.get_distance().rows;
160  cloud_msg->width = data.get_distance().cols;
161  cloud_msg->is_dense = false;
162  cloud_msg->is_bigendian = false;
163 
164  cloud_msg->fields.resize (5);
165  cloud_msg->fields[0].name = "x"; cloud_msg->fields[1].name = "y"; cloud_msg->fields[2].name = "z";
166  cloud_msg->fields[3].name = "confidence"; cloud_msg->fields[4].name = "intensity";
167  int offset = 0;
168  // All offsets are *4, as all field data types are float32
169  for (size_t d = 0; d < cloud_msg->fields.size (); ++d, offset += 4)
170  {
171  cloud_msg->fields[d].offset = offset;
172  cloud_msg->fields[d].datatype = (d<3) ? int(sensor_msgs::PointField::FLOAT32) : int(sensor_msgs::PointField::UINT16);
173  cloud_msg->fields[d].count = 1;
174  }
175  cloud_msg->point_step = offset;
176  cloud_msg->row_step = cloud_msg->point_step * cloud_msg->width;
177  cloud_msg->data.resize (cloud_msg->height * cloud_msg->width * cloud_msg->point_step);
178 
179  const float f2rc = data.getCameraParameters().f2rc / 1000.f; // since f2rc is given in [mm], but the pcl message wants [m]
180 
181  uint16_t *pDepth, *pConf, *pInt;
182  int cp=0;
183  for(int i = 0; i < data.get_distance().rows; ++i)
184  {
185  pDepth = (uint16_t*)(data.get_distance() .data + (data.get_distance() .step*i) );
186  pConf = (uint16_t*)(data.get_confidence().data + (data.get_confidence().step*i) );
187  pInt = (uint16_t*)(data.get_intensity() .data + (data.get_intensity() .step*i) );
188 
189  for (int j = 0; j < data.get_distance().cols; ++j, ++cp)
190  {
191  if(pDepth[j]==0 || pDepth[j]==NARE_DISTANCE_VALUE) {
192  const float bad_point = std::numeric_limits<float>::quiet_NaN();
193  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[0].offset], &bad_point, sizeof (float));
194  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[1].offset], &bad_point, sizeof (float));
195  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[2].offset], &bad_point, sizeof (float));
196  }
197  else {
198  float xp = (data.getCameraParameters().cx - j) / data.getCameraParameters().fx;
199  float yp = (data.getCameraParameters().cy - i) / data.getCameraParameters().fy;
200 
201  // Correction of the lens distortion
202  float r2 = (xp * xp + yp * yp);
203  float r4 = r2 * r2;
204  float k = 1 + data.getCameraParameters().k1 * r2 + data.getCameraParameters().k2 * r4;
205  xp = xp * k;
206  yp = yp * k;
207 
208  // Calculation of the distances
209  float s0 = std::sqrt(xp*xp + yp*yp + 1.f) * 1000.f;
210 
211  // Calculation of the Cartesian coordinates
212  const float ox = xp * pDepth[j] / s0;
213  const float oy = yp * pDepth[j] / s0;
214  const float oz = pDepth[j] / s0 - f2rc;
215 
216  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[0].offset], &ox, sizeof (float));
217  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[1].offset], &oy, sizeof (float));
218  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[2].offset], &oz, sizeof (float));
219  }
220 
221  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[3].offset], &pConf[j], sizeof (uint16_t));
222  memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[4].offset], &pInt [j], sizeof (uint16_t));
223  }
224  }
225 
226  g_pub_points.publish(cloud_msg);
227  }
228 
229  if(!published_anything) {
230  if(g_control) g_control->stopStream();
231  }
232 }
233 
235  ROS_DEBUG("Got new subscriber");
236 
237  if(!g_control) return;
238 
239  bool r=g_control->startStream(); // tell the device to start streaming data
240  ROS_ASSERT(r);
241 }
242 
245 }
246 
249 }
250 
251 int main(int argc, char **argv) {
253  ros::init(argc, argv, "driver_3DCS");
254  ros::NodeHandle nh("~");
255 
256  bool r;
257  boost::asio::io_service io_service;
258 
259  //default parameters
260  std::string remote_device_ip="192.168.1.10";
261  g_frame_id = "camera";
262 
263  ros::param::get("~remote_device_ip", remote_device_ip);
264  ros::param::get("~frame_id", g_frame_id);
265  ros::param::get("~prevent_frame_skipping", g_publish_all);
266 
267  Driver_3DCS::Control control(io_service, remote_device_ip);
268  r=control.open();
269  ROS_ASSERT(r);
270  r=control.initStream();
271  ROS_ASSERT(r);
272 
273  boost::thread thr(boost::bind(&boost::asio::io_service::run, &io_service));
274 
275  Driver_3DCS::Streaming device(io_service, remote_device_ip);
276  device.getSignal().connect( boost::bind(&on_frame, _1) );
277  r=device.openStream();
278  ROS_ASSERT(r);
279 
280  g_control = &control;
281 
282  //make me public (after init.)
283 
286  g_pub_points = nh.advertise<sensor_msgs::PointCloud2>("points", 2, (ros::SubscriberStatusCallback)on_new_subscriber_ros, ros::SubscriberStatusCallback());
287  g_pub_confidence = it.advertise("confidence", 1, (image_transport::SubscriberStatusCallback)on_new_subscriber_it, image_transport::SubscriberStatusCallback());
288  g_pub_intensity = it.advertise("intensity", 1, (image_transport::SubscriberStatusCallback)on_new_subscriber_it, image_transport::SubscriberStatusCallback());
289  g_pub_camera_info = nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, (ros::SubscriberStatusCallback)on_new_subscriber_ros, ros::SubscriberStatusCallback());
290  g_pub_ios = nh.advertise<std_msgs::ByteMultiArray>("ios", 1, (ros::SubscriberStatusCallback)on_new_subscriber_ros, ros::SubscriberStatusCallback());
291 
292  //wait til end of exec.
293  ros::spin();
294 
295  io_service.stop();
296  device.closeStream();
297  control.close();
298 
299  g_pub_depth.shutdown();
300  g_pub_confidence.shutdown();
301  g_pub_intensity.shutdown();
302  g_pub_camera_info.shutdown();
303  g_pub_points.shutdown();
304  g_pub_ios.shutdown();
305 
306  return 0;
307 }
d
void thr_publish_frame()
Definition: node.cpp:68
boost::mutex g_mtx_data
Definition: node.cpp:63
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
image_transport::Publisher g_pub_intensity
Definition: node.cpp:56
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< Driver_3DCS::Data > g_data
Definition: node.cpp:64
f
void on_frame(const boost::shared_ptr< Driver_3DCS::Data > &data)
Definition: node.cpp:74
void publish_frame(const Driver_3DCS::Data &data)
Definition: node.cpp:90
ros::Publisher g_pub_ios
Definition: node.cpp:57
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void _on_new_subscriber()
Definition: node.cpp:234
ros::Publisher g_pub_camera_info
Definition: node.cpp:57
#define ROS_WARN(...)
std::string g_frame_id
Definition: node.cpp:59
uint32_t getNumSubscribers() const
void on_new_subscriber_it(const image_transport::SingleSubscriberPublisher &pub)
Definition: node.cpp:247
ROSCPP_DECL void spin(Spinner &spinner)
const cv::Mat & get_confidence() const
Definition: driver.h:100
const CameraParameters & getCameraParameters() const
Definition: driver.h:103
ros::Publisher g_pub_points
Definition: node.cpp:57
void publish(const sensor_msgs::Image &message) const
SIG_ON_FRAME & getSignal()
Definition: driver.h:179
ROSCPP_DECL bool get(const std::string &key, std::string &s)
image_transport::Publisher g_pub_depth
Definition: node.cpp:56
const cv::Mat & get_intensity() const
Definition: driver.h:99
const std::string TYPE_16UC1
bool startStream()
Definition: driver.h:123
image_transport::Publisher g_pub_confidence
Definition: node.cpp:56
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const bool SUPPRESS_INVALID_POINTS
Flag whether invalid points are to be replaced by NaN.
Definition: node.cpp:52
void on_new_subscriber_ros(const ros::SingleSubscriberPublisher &pub)
Definition: node.cpp:243
Driver_3DCS::Control * g_control
Definition: node.cpp:58
uint32_t getNumSubscribers() const
const uint16_t NARE_DISTANCE_VALUE
Distance code for data outside the TOF range.
Definition: node.cpp:55
bool g_publish_all
If true: prevents skipping of frames and publish everything, otherwise use newest data to publish to ...
Definition: node.cpp:61
int main(int argc, char **argv)
Definition: node.cpp:251
static Time now()
const cv::Mat & get_distance() const
Definition: driver.h:98
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
#define ROS_ASSERT(cond)
#define ROSCONSOLE_DEFAULT_NAME
#define ROS_DEBUG(...)
virtual void close()
Definition: network.h:128


sick_visionary_t_driver
Author(s): Joshua Hampp
autogenerated on Mon Jun 10 2019 15:09:27