basler_tof_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017, DFKI GmbH
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  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of DFKI GmbH nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author:
30  * Martin Günther <martin.guenther@dfki.de>
31  */
32 
33 #include <ConsumerImplHelper/ToFCamera.h>
34 #include <GenTL/PFNC.h>
35 #include <string>
36 #include <iostream>
37 #include <fstream>
38 #include <iomanip>
39 
40 #include <ros/ros.h>
42 #include <sensor_msgs/Image.h>
43 #include <sensor_msgs/CameraInfo.h>
45 #include <cv_bridge/cv_bridge.h>
46 #include <opencv2/opencv.hpp>
47 #include <pcl_ros/point_cloud.h>
49 
50 #include <dynamic_reconfigure/server.h>
51 #include <basler_tof/BaslerToFConfig.h>
52 
53 using namespace GenTLConsumerImplHelper;
54 using namespace GenApi;
55 using namespace std;
56 
64 std::string frame_id_;
65 std::string device_id_;
66 std::string camera_name_;
67 CToFCamera camera_;
68 
70 
74 
75 
76 bool publish(const BufferParts& parts, ros::Time acquisition_time)
77 {
78  if (parts.size() != 3)
79  {
80  ROS_ERROR("Expected 3 parts, got %zu!", parts.size());
81  return false;
82  }
83 
84  // If the point cloud is enabled, the first part always contains the point cloud data.
85  if (parts[0].dataFormat != PFNC_Coord3D_ABC32f)
86  {
87  ROS_ERROR("Unexpected data format for the first image part. Coord3D_ABC32f is expected.");
88  return false;
89  }
90 
91  if (parts[1].dataFormat != PFNC_Mono16)
92  {
93  ROS_ERROR("Unexpected data format for the second image part. Mono16 is expected.");
94  return false;
95  }
96 
97  // ----- publish point cloud
98  const size_t nPixel = parts[0].width * parts[0].height;
99 
100  pcl::PointCloud<pcl::PointXYZI>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZI>());
101  cloud->header.frame_id = frame_id_;
102  cloud->header.stamp = pcl_conversions::toPCL(acquisition_time);
103  cloud->width = parts[0].width;
104  cloud->height = parts[0].height;
105  cloud->is_dense = false;
106  cloud->points.resize(nPixel);
107 
108  CToFCamera::Coord3D *pPoint = static_cast<CToFCamera::Coord3D*>(parts[0].pData);
109  uint16_t *pIntensity = static_cast<uint16_t*>(parts[1].pData);
110 
111  for (size_t i = 0; i < nPixel; ++i)
112  {
113  pcl::PointXYZI &p = cloud->points[i];
114  if (pPoint->IsValid())
115  {
116  p.x = 0.001f * pPoint->x;
117  p.y = 0.001f * pPoint->y;
118  p.z = 0.001f * pPoint->z;
119  p.intensity = *pIntensity;
120  }
121  else
122  {
123  p.x = std::numeric_limits<float>::quiet_NaN();
124  p.y = std::numeric_limits<float>::quiet_NaN();
125  p.z = std::numeric_limits<float>::quiet_NaN();
126  }
127  pPoint++;
128  pIntensity++;
129  }
130 
131  cloud_pub_.publish(cloud);
132 
133  // ----- publish intensity image
134  pIntensity = static_cast<uint16_t*>(parts[1].pData);
135 
136  cv_bridge::CvImage intensity_cvimg;
138  intensity_cvimg.header.frame_id = frame_id_;
139  intensity_cvimg.header.stamp = acquisition_time;
140  intensity_cvimg.image = cv::Mat(parts[1].height, parts[1].width, CV_16UC1);
141  intensity_cvimg.image.setTo(0);
142 
143  for (size_t i = 0; i < parts[1].height; i++)
144  {
145  for (size_t j = 0; j < parts[1].width; j++)
146  {
147  intensity_cvimg.image.at<unsigned short>(i, j) = static_cast<unsigned short>(*pIntensity);
148  pIntensity++;
149  }
150  }
151  // uncomment these two lines for cameracalibrator.py
152  // intensity_cvimg.image.convertTo(intensity_cvimg.image, CV_8U, 1.0 / 256.0);
153  // intensity_cvimg.encoding = sensor_msgs::image_encodings::MONO8;
154 
155  intensity_pub_.publish(intensity_cvimg.toImageMsg());
156 
157  sensor_msgs::CameraInfoPtr intensity_info_msg(new sensor_msgs::CameraInfo(intensity_info_manager_->getCameraInfo()));
158  intensity_info_msg->header.stamp = acquisition_time;
159  intensity_info_msg->header.frame_id = frame_id_;
160  intensity_ci_pub_.publish(intensity_info_msg);
161 
162  // ----- publish confidence image
163  uint16_t *pConfidence = static_cast<uint16_t*>(parts[2].pData);
164 
165  cv_bridge::CvImage confidence_cvimg;
167  confidence_cvimg.header.frame_id = frame_id_;
168  confidence_cvimg.header.stamp = acquisition_time;
169  confidence_cvimg.image = cv::Mat(parts[2].height, parts[2].width, CV_16UC1);
170  confidence_cvimg.image.setTo(0);
171 
172  for (size_t i = 0; i < parts[2].height; i++)
173  {
174  for (size_t j = 0; j < parts[2].width; j++)
175  {
176  confidence_cvimg.image.at<unsigned short>(i, j) = static_cast<unsigned short>(*pConfidence);
177  pConfidence++;
178  }
179  }
180 
181  confidence_pub_.publish(confidence_cvimg.toImageMsg());
182 
183  sensor_msgs::CameraInfoPtr confidence_info_msg(new sensor_msgs::CameraInfo(confidence_info_manager_->getCameraInfo()));
184  confidence_info_msg->header.stamp = acquisition_time;
185  confidence_info_msg->header.frame_id = frame_id_;
186  confidence_ci_pub_.publish(confidence_info_msg);
187 
188  // ----- publish depth image
189  pPoint = static_cast<CToFCamera::Coord3D*>(parts[0].pData);
190 
191  cv_bridge::CvImage depth_cvimg;
193  depth_cvimg.header.frame_id = frame_id_;
194  depth_cvimg.header.stamp = acquisition_time;
195  depth_cvimg.image = cv::Mat(parts[0].height, parts[0].width, CV_16UC1);
196  depth_cvimg.image.setTo(0);
197 
198  for (size_t i = 0; i < parts[0].height; i++)
199  {
200  for (size_t j = 0; j < parts[0].width; j++)
201  {
202  depth_cvimg.image.at<uint16_t>(i, j) = static_cast<uint16_t>(pPoint->z); // can be NaN; should be in mm
203  pPoint++;
204  }
205  }
206 
207  depth_pub_.publish(depth_cvimg.toImageMsg());
208 
209  sensor_msgs::CameraInfoPtr depth_info_msg(new sensor_msgs::CameraInfo(depth_info_manager_->getCameraInfo()));
210  depth_info_msg->header.stamp = acquisition_time;
211  depth_info_msg->header.frame_id = frame_id_;
212  depth_ci_pub_.publish(depth_info_msg);
213 
214  return true;
215 }
216 
217 void round_to_increment_int(int &param, int increment)
218 {
219  param = ((param + increment / 2) / increment) * increment;
220 }
221 
222 void round_to_increment_double(double &param, double increment)
223 {
224  param = (int)((param + increment / 2) / increment) * increment;
225 }
226 
227 void update_config(basler_tof::BaslerToFConfig &new_config, uint32_t level)
228 {
229  // round to increments
230  round_to_increment_int(new_config.exposure_time, 100);
231  round_to_increment_double(new_config.exposure_agility, 0.1);
232  round_to_increment_int(new_config.confidence_threshold, 16);
233  round_to_increment_int(new_config.temporal_strength, 5);
234  round_to_increment_int(new_config.outlier_tolerance, 16);
235 
236  CFloatPtr(camera_.GetParameter("AcquisitionFrameRate"))->SetValue(new_config.frame_rate);
237 
238  if (new_config.exposure_auto)
239  {
240  CEnumerationPtr(camera_.GetParameter("ExposureAuto"))->FromString("Continuous");
241 
242  // Agility and Delay are only valid when exposure_auto is "true"
243  CFloatPtr(camera_.GetParameter("Agility"))->SetValue(new_config.exposure_agility);
244  CIntegerPtr(camera_.GetParameter("Delay"))->SetValue(new_config.exposure_delay);
245  }
246  else
247  {
248  CEnumerationPtr(camera_.GetParameter("ExposureAuto"))->FromString("Off");
249 
250  // ExposureTime is only valid when exposure_auto is "false"
251  CFloatPtr(camera_.GetParameter("ExposureTime"))->SetValue(new_config.exposure_time);
252  }
253 
254  CIntegerPtr(camera_.GetParameter("ConfidenceThreshold"))->SetValue(new_config.confidence_threshold);
255  CBooleanPtr(camera_.GetParameter("FilterSpatial"))->SetValue(new_config.spatial_filter);
256  CBooleanPtr(camera_.GetParameter("FilterTemporal"))->SetValue(new_config.temporal_filter);
257  CIntegerPtr(camera_.GetParameter("FilterStrength"))->SetValue(new_config.temporal_strength);
258  CIntegerPtr(camera_.GetParameter("OutlierTolerance"))->SetValue(new_config.outlier_tolerance);
259 }
260 
262 {
263  if (cloud_pub_.getNumSubscribers() > 0 ||
264  intensity_pub_.getNumSubscribers() > 0 ||
265  confidence_pub_.getNumSubscribers() > 0 ||
266  depth_pub_.getNumSubscribers() > 0 ||
267  intensity_ci_pub_.getNumSubscribers() > 0 ||
268  confidence_ci_pub_.getNumSubscribers() > 0 ||
269  depth_ci_pub_.getNumSubscribers() > 0)
270  {
272  {
273  ROS_INFO("Starting stream");
274  subscriber_connected_ = true;
275  }
276  }
277  else
278  {
280  {
281  ROS_INFO("Stopping stream");
282  camera_.StopGrab();
283  subscriber_connected_ = false;
284  }
285  }
286 }
287 
288 int main(int argc, char* argv[])
289 {
290  ros::init(argc, argv, "basler_tof_node");
291  ros::NodeHandle n;
292  ros::NodeHandle pn("~");
293  ros::NodeHandle intensity_nh("intensity");
294  ros::NodeHandle confidence_nh("confidence");
295  ros::NodeHandle depth_nh("depth");
296 
297  pn.param("frame_id", frame_id_, std::string("camera_optical_frame"));
298  if (!pn.getParam("device_id", device_id_))
299  {
300  ROS_WARN("~device_id is not set! Using first device.");
301  device_id_ = "#1";
302  }
303 
304  ros::SubscriberStatusCallback rsscb = boost::bind(&subscribeCallback);
305 
306  cloud_pub_ = n.advertise<pcl::PointCloud<pcl::PointXYZI> > ("points", 10, rsscb, rsscb);
307  intensity_pub_ = n.advertise<sensor_msgs::Image>("intensity/image_raw", 10, rsscb, rsscb);
308  confidence_pub_ = n.advertise<sensor_msgs::Image>("confidence/image_raw", 10, rsscb, rsscb);
309  depth_pub_ = n.advertise<sensor_msgs::Image>("depth/image_raw", 10, rsscb, rsscb);
310  intensity_ci_pub_ = n.advertise<sensor_msgs::CameraInfo>("intensity/camera_info", 10, rsscb, rsscb);
311  confidence_ci_pub_ = n.advertise<sensor_msgs::CameraInfo>("confidence/camera_info", 10, rsscb, rsscb);
312  depth_ci_pub_ = n.advertise<sensor_msgs::CameraInfo>("depth/camera_info", 10, rsscb, rsscb);
313 
314  intensity_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(intensity_nh);
315  confidence_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(confidence_nh);
316  depth_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(depth_nh);
317 
318  int exitCode = EXIT_FAILURE;
319 
320  try
321  {
322  CToFCamera::InitProducer();
323 
324  if (device_id_ == "#1")
325  {
326  ROS_INFO("Opening first camera.");
327  camera_.OpenFirstCamera();
328  }
329  else
330  {
331  CameraList cameraList = camera_.EnumerateCameras();
332  bool found = false;
333  for (CameraList::const_iterator it = cameraList.begin(); it != cameraList.end(); ++it)
334  {
335  ROS_INFO("Found camera device with serial: %s", it->strSerialNumber.c_str());
336  if (it->strSerialNumber == device_id_)
337  {
338  ROS_INFO("Serial matches device_id, opening camera.");
339  found = true;
340  camera_.Open(*it);
341  break;
342  }
343  }
344  if (!found)
345  {
346  ROS_FATAL("No camera with device_id '%s' found, exiting!", device_id_.c_str());
347  return EXIT_FAILURE;
348  }
349  }
350 
351  std::string camera_name_ = camera_.GetCameraInfo().strModelName
352  + "_" + camera_.GetCameraInfo().strSerialNumber;
353  if (!intensity_info_manager_->setCameraName(camera_name_) ||
354  !confidence_info_manager_->setCameraName(camera_name_) ||
355  !depth_info_manager_->setCameraName(camera_name_))
356  {
357  ROS_WARN_STREAM("[" << camera_name_
358  << "] name not valid"
359  << " for camera_info_manager");
360  }
361 
362  std::string camera_info_url;
363  if (pn.getParam("camera_info_url", camera_info_url))
364  {
365  if (!intensity_info_manager_->validateURL(camera_info_url) ||
366  !confidence_info_manager_->validateURL(camera_info_url) ||
367  !depth_info_manager_->validateURL(camera_info_url))
368  {
369  ROS_WARN("camera_info_url invalid: %s", camera_info_url.c_str());
370  }
371  else
372  {
373  intensity_info_manager_->loadCameraInfo(camera_info_url);
374  confidence_info_manager_->loadCameraInfo(camera_info_url);
375  depth_info_manager_->loadCameraInfo(camera_info_url);
376  }
377  }
378 
379  int device_channel;
380  pn.getParam("device_channel", device_channel);
381 
382  CIntegerPtr(camera_.GetDeviceNodeMap()->GetNode("DeviceChannel"))->SetValue(int64_t(device_channel));
383 
384  ROS_INFO_STREAM("[" << camera_name_ << "] opened.");
385 
386  ROS_INFO_STREAM("DeviceVendorName: " << CStringPtr(camera_.GetParameter("DeviceVendorName"))->GetValue());
387  ROS_INFO_STREAM("DeviceModelName: " << CStringPtr(camera_.GetParameter("DeviceModelName"))->GetValue());
388  ROS_INFO_STREAM("DeviceVersion: " << CStringPtr(camera_.GetParameter("DeviceVersion"))->GetValue());
389  ROS_INFO_STREAM("DeviceFirmwareVersion: " << CStringPtr(camera_.GetParameter("DeviceFirmwareVersion"))->GetValue());
390  ROS_INFO_STREAM("DeviceDriverVersion: " << CStringPtr(camera_.GetParameter("DeviceDriverVersion"))->GetValue());
391  ROS_INFO_STREAM("DeviceSerialNumber: " << CStringPtr(camera_.GetParameter("DeviceSerialNumber"))->GetValue());
392  ROS_INFO_STREAM("DeviceChannel: " << CIntegerPtr(camera_.GetDeviceNodeMap()->GetNode("DeviceChannel"))->GetValue());
393 
394  ROS_INFO_STREAM("DeviceCalibVersion: " << CIntegerPtr(camera_.GetParameter("DeviceCalibVersion"))->GetValue());
395  ROS_INFO_STREAM("DeviceCalibState: " << CEnumerationPtr(camera_.GetParameter("DeviceCalibState"))->ToString());
396  ROS_INFO_STREAM("DeviceCalibOffset: " << CIntegerPtr(camera_.GetParameter("DeviceCalibOffset"))->GetValue());
397 
398  ROS_INFO_STREAM("DeviceTemperature: " << CFloatPtr(camera_.GetParameter("DeviceTemperature"))->GetValue() << " degrees C");
399 
400 
401  // Parameterize the camera to send 3D coordinates and intensity data
402  CEnumerationPtr ptrImageComponentSelector = camera_.GetParameter("ImageComponentSelector");
403  CBooleanPtr ptrImageComponentEnable = camera_.GetParameter("ImageComponentEnable");
404  CEnumerationPtr ptrPixelFormat = camera_.GetParameter("PixelFormat");
405 
406  ptrImageComponentSelector->FromString("Range");
407  ptrImageComponentEnable->SetValue(true);
408  ptrPixelFormat->FromString("Coord3D_ABC32f");
409 
410  ptrImageComponentSelector->FromString("Intensity");
411  ptrImageComponentEnable->SetValue(true);
412  ptrPixelFormat->FromString("Mono16");
413 
414  ptrImageComponentSelector->FromString("Confidence");
415  ptrImageComponentEnable->SetValue(true);
416  ptrPixelFormat->FromString("Confidence16");
417 
418  dynamic_reconfigure::Server<basler_tof::BaslerToFConfig> dynamic_reconfigure_server;
419  dynamic_reconfigure::Server<basler_tof::BaslerToFConfig>::CallbackType f;
420  f = boost::bind(&update_config, _1, _2);
421  dynamic_reconfigure_server.setCallback(f);
422 
423  //check once if subscribers are already connected
425  while (ros::ok())
426  {
427  ros::spinOnce();
428 
430  {
431  // Acquire one single image
432  BufferParts parts;
433  GrabResultPtr ptrGrabResult = camera_.GrabSingleImage(1000, &parts);
434 
435  // Save 3D data
436  if (ptrGrabResult->status == GrabResult::Ok)
437  {
438  publish(parts, ros::Time::now());
439  }
440  else
441  {
442  ROS_ERROR("Failed to grab an image.");
443  }
444  }
445  }
446 
447  camera_.Close();
448  exitCode = EXIT_SUCCESS;
449  }
450  catch (GenICam::GenericException& e)
451  {
452  ROS_ERROR_STREAM("Exception occurred: " << endl << e.GetDescription());
453  }
454 
455  if (CToFCamera::IsProducerInitialized())
456  CToFCamera::TerminateProducer(); // Won't throw any exceptions
457 
458  return exitCode;
459 }
460 
std::string device_id_
#define ROS_FATAL(...)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void publish(const boost::shared_ptr< M > &message) const
f
boost::shared_ptr< camera_info_manager::CameraInfoManager > depth_info_manager_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string camera_name_
std::string encoding
bool subscriber_connected_
ros::Publisher confidence_pub_
void round_to_increment_double(double &param, double increment)
boost::shared_ptr< camera_info_manager::CameraInfoManager > intensity_info_manager_
CToFCamera camera_
int main(int argc, char *argv[])
#define ROS_WARN(...)
ros::Publisher depth_pub_
ros::Publisher depth_ci_pub_
void round_to_increment_int(int &param, int increment)
#define ROS_INFO(...)
ros::Publisher intensity_ci_pub_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string frame_id_
ROSCPP_DECL bool ok()
const std::string TYPE_16UC1
void subscribeCallback()
ros::Publisher cloud_pub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const std::string MONO16
#define ROS_WARN_STREAM(args)
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
bool publish(const BufferParts &parts, ros::Time acquisition_time)
bool getParam(const std::string &key, std::string &s) const
ros::Publisher intensity_pub_
ros::Publisher confidence_ci_pub_
static Time now()
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header header
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
boost::shared_ptr< camera_info_manager::CameraInfoManager > confidence_info_manager_
void update_config(basler_tof::BaslerToFConfig &new_config, uint32_t level)


basler_tof
Author(s): Martin Guenther
autogenerated on Wed Nov 18 2020 03:55:33