tof_camera.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 //##################
19 //#### includes ####
20 
21 // standard includes
22 //--
23 
24 // ROS includes
25 #include <ros/ros.h>
27 #include <cv_bridge/CvBridge.h>
28 
29 // ROS message includes
30 #include <sensor_msgs/Image.h>
31 #include <sensor_msgs/CameraInfo.h>
32 #include <sensor_msgs/fill_image.h>
33 #include <sensor_msgs/SetCameraInfo.h>
34 #include <sensor_msgs/PointCloud.h>
35 #include <sensor_msgs/PointCloud2.h>
36 
37 #include <cob_camera_sensors/GetTOFImages.h>
38 
39 // external includes
44 
45 #include <boost/thread/mutex.hpp>
46 
47 using namespace ipa_CameraSensors;
48 
50 {
51  enum t_Mode
52  {
53  MODE_TOPIC = 0,
54  MODE_SERVICE
55  };
56 
57 private:
59 
65 
66  sensor_msgs::CameraInfo camera_info_msg_;
67 
70 
72 
73  std::string config_directory_;
81 
82  cv::Mat xyz_image_32F3_;
83  cv::Mat grey_image_32F1_;
84 
86  boost::mutex service_mutex_;
87 
90 
91 public:
93  CobTofCameraNode(const ros::NodeHandle& node_handle)
94  : node_handle_(node_handle),
95  image_transport_(node_handle),
96  tof_camera_(AbstractRangeImagingSensorPtr()),
97  xyz_image_32F3_(cv::Mat()),
98  grey_image_32F1_(cv::Mat()),
99  publish_point_cloud_(false),
100  publish_point_cloud_2_(false)
101  {
103  }
104 
107  {
108  tof_camera_->Close();
109  }
110 
113  bool init()
114  {
115  if (loadParameters() == false)
116  {
117  ROS_ERROR("[color_camera] Could not read all parameters from launch file");
118  return false;
119  }
120 
121 
122  if (tof_camera_->Init(config_directory_, tof_camera_index_) & ipa_CameraSensors::RET_FAILED)
123  {
124 
125  std::stringstream ss;
126  ss << "Initialization of tof camera ";
127  ss << tof_camera_index_;
128  ss << " failed";
129  ROS_ERROR("[tof_camera] %s", ss.str().c_str());
130  tof_camera_ = AbstractRangeImagingSensorPtr();
131  return false;
132  }
133 
134  if (tof_camera_->Open() & ipa_CameraSensors::RET_FAILED)
135  {
136  std::stringstream ss;
137  ss << "Could not open tof camera ";
138  ss << tof_camera_index_;
139  ROS_ERROR("[tof_camera] %s", ss.str().c_str());
140  tof_camera_ = AbstractRangeImagingSensorPtr();
141  return false;
142  }
143 
147  tof_camera_->GetProperty(&cameraProperty);
148  int range_sensor_width = cameraProperty.cameraResolution.xResolution;
149  int range_sensor_height = cameraProperty.cameraResolution.yResolution;
150  cv::Size range_image_size(range_sensor_width, range_sensor_height);
151 
154  tof_sensor_toolbox->Init(config_directory_, tof_camera_->GetCameraType(), tof_camera_index_, range_image_size);
155 
156  cv::Mat intrinsic_mat = tof_sensor_toolbox->GetIntrinsicMatrix(tof_camera_type_, tof_camera_index_);
157  cv::Mat distortion_map_X = tof_sensor_toolbox->GetDistortionMapX(tof_camera_type_, tof_camera_index_);
158  cv::Mat distortion_map_Y = tof_sensor_toolbox->GetDistortionMapY(tof_camera_type_, tof_camera_index_);
159  tof_camera_->SetIntrinsics(intrinsic_mat, distortion_map_X, distortion_map_Y);
160 
162  camera_info_service_ = node_handle_.advertiseService("set_camera_info", &CobTofCameraNode::setCameraInfo, this);
163  image_service_ = node_handle_.advertiseService("get_images", &CobTofCameraNode::imageSrvCallback, this);
164  xyz_image_publisher_ = image_transport_.advertiseCamera("image_xyz", 1);
165  grey_image_publisher_ = image_transport_.advertiseCamera("image_grey", 1);
166  if(publish_point_cloud_2_) topicPub_pointCloud2_ = node_handle_.advertise<sensor_msgs::PointCloud2>("point_cloud2", 1);
167  if(publish_point_cloud_) topicPub_pointCloud_ = node_handle_.advertise<sensor_msgs::PointCloud>("point_cloud", 1);
168 
169  cv::Mat d = tof_sensor_toolbox->GetDistortionParameters(tof_camera_type_, tof_camera_index_);
170  camera_info_msg_.header.stamp = ros::Time::now();
171  camera_info_msg_.header.frame_id = "head_tof_link";
172  /*camera_info_msg_.D[0] = d.at<double>(0, 0);
173  camera_info_msg_.D[1] = d.at<double>(0, 1);
174  camera_info_msg_.D[2] = d.at<double>(0, 2);
175  camera_info_msg_.D[3] = d.at<double>(0, 3);
176  camera_info_msg_.D[4] = 0;*/
177 
178  cv::Mat k = tof_sensor_toolbox->GetIntrinsicMatrix(tof_camera_type_, tof_camera_index_);
179  /*camera_info_msg_.K[0] = k.at<double>(0, 0);
180  camera_info_msg_.K[1] = k.at<double>(0, 1);
181  camera_info_msg_.K[2] = k.at<double>(0, 2);
182  camera_info_msg_.K[3] = k.at<double>(1, 0);
183  camera_info_msg_.K[4] = k.at<double>(1, 1);
184  camera_info_msg_.K[5] = k.at<double>(1, 2);
185  camera_info_msg_.K[6] = k.at<double>(2, 0);
186  camera_info_msg_.K[7] = k.at<double>(2, 1);
187  camera_info_msg_.K[8] = k.at<double>(2, 2);*/
188 
189  camera_info_msg_.width = range_sensor_width;
190  camera_info_msg_.height = range_sensor_height;
191 
192  return true;
193  }
194 
199  bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req,
200  sensor_msgs::SetCameraInfo::Response& rsp)
201  {
203  camera_info_msg_ = req.camera_info;
204 
205  rsp.success = false;
206  rsp.status_message = "[tof_camera] Setting camera parameters through ROS not implemented";
207 
208  return true;
209  }
210 
212  bool spin()
213  {
214  boost::mutex::scoped_lock lock(service_mutex_);
215  sensor_msgs::Image::Ptr xyz_image_msg_ptr;
216  sensor_msgs::Image::Ptr grey_image_msg_ptr;
217  sensor_msgs::CameraInfo tof_image_info;
218 
219  if(tof_camera_->AcquireImages(0, &grey_image_32F1_, &xyz_image_32F3_, false, false, ipa_CameraSensors::INTENSITY_32F1) & ipa_Utils::RET_FAILED)
220  {
221  ROS_ERROR("[tof_camera] Tof image acquisition failed");
222  return false;
223  }
224 
226  //if(filter_xyz_tearoff_edges_ || filter_xyz_by_amplitude_)
227  // ROS_ERROR("[tof_camera] FUNCTION UNCOMMENT BY JSF");
228  if(filter_xyz_tearoff_edges_) ipa_Utils::FilterTearOffEdges(xyz_image_32F3_, 0, (float)tearoff_tear_half_fraction_);
229  if(filter_xyz_by_amplitude_) ipa_Utils::FilterByAmplitude(xyz_image_32F3_, grey_image_32F1_, 0, 0, lower_amplitude_threshold_, upper_amplitude_threshold_);
230 
231  try
232  {
233  IplImage img = xyz_image_32F3_;
234  xyz_image_msg_ptr = sensor_msgs::CvBridge::cvToImgMsg(&img, "passthrough");
235  }
236  catch (sensor_msgs::CvBridgeException error)
237  {
238  ROS_ERROR("[tof_camera] Could not convert 32bit xyz IplImage to ROS message");
239  return false;
240  }
241 
242  try
243  {
244  IplImage img = grey_image_32F1_;
245  grey_image_msg_ptr = sensor_msgs::CvBridge::cvToImgMsg(&img, "passthrough");
246  }
247  catch (sensor_msgs::CvBridgeException error)
248  {
249  ROS_ERROR("[tof_camera] Could not convert 32bit grey IplImage to ROS message");
250  return false;
251  }
252 
254  ros::Time now = ros::Time::now();
255  xyz_image_msg_ptr->header.stamp = now;
256  xyz_image_msg_ptr->header.frame_id = "head_tof_link";
257  grey_image_msg_ptr->header.stamp = now;
258  grey_image_msg_ptr->header.frame_id = "head_tof_link";
259 
260  tof_image_info = camera_info_msg_;
261  tof_image_info.width = grey_image_32F1_.cols;
262  tof_image_info.height = grey_image_32F1_.rows;
263  tof_image_info.header.stamp = now;
264  tof_image_info.header.frame_id = "head_tof_link";
265 
267  xyz_image_publisher_.publish(*xyz_image_msg_ptr, tof_image_info);
268  grey_image_publisher_.publish(*grey_image_msg_ptr, tof_image_info);
269 
270  if(publish_point_cloud_) publishPointCloud(now);
271  if(publish_point_cloud_2_) publishPointCloud2(now);
272 
273  return true;
274  }
275 
277  {
278  ROS_DEBUG("convert xyz_image to point_cloud");
279  sensor_msgs::PointCloud pc_msg;
280  // create point_cloud message
281  pc_msg.header.stamp = now;
282  pc_msg.header.frame_id = "head_tof_link";
283 
284  cv::Mat cpp_xyz_image_32F3 = xyz_image_32F3_;
285  cv::Mat cpp_grey_image_32F1 = grey_image_32F1_;
286 
287  float* f_ptr = 0;
288  for (int row = 0; row < cpp_xyz_image_32F3.rows; row++)
289  {
290  f_ptr = cpp_xyz_image_32F3.ptr<float>(row);
291  for (int col = 0; col < cpp_xyz_image_32F3.cols; col++)
292  {
293  geometry_msgs::Point32 pt;
294  pt.x = f_ptr[3*col + 0];
295  pt.y = f_ptr[3*col + 1];
296  pt.z = f_ptr[3*col + 2];
297  pc_msg.points.push_back(pt);
298  }
299  }
300  topicPub_pointCloud_.publish(pc_msg);
301  }
302 
304  {
305  cv::Mat cpp_xyz_image_32F3 = xyz_image_32F3_;
306  cv::Mat cpp_confidence_mask_32F1 = grey_image_32F1_;
307 
308  sensor_msgs::PointCloud2 pc_msg;
309  // create point_cloud message
310  pc_msg.header.stamp = now;
311  pc_msg.header.frame_id = "head_tof_link";
312  pc_msg.width = cpp_xyz_image_32F3.cols;
313  pc_msg.height = cpp_xyz_image_32F3.rows;
314  pc_msg.fields.resize(4);
315  pc_msg.fields[0].name = "x";
316  pc_msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
317  pc_msg.fields[1].name = "y";
318  pc_msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
319  pc_msg.fields[2].name = "z";
320  pc_msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
321  pc_msg.fields[3].name = "confidence";
322  pc_msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
323  int offset = 0;
324  for (size_t d = 0; d < pc_msg.fields.size(); ++d, offset += 4)
325  {
326  pc_msg.fields[d].offset = offset;
327  }
328  pc_msg.point_step = 16;
329  pc_msg.row_step = pc_msg.point_step * pc_msg.width;
330  pc_msg.data.resize (pc_msg.width*pc_msg.height*pc_msg.point_step);
331  pc_msg.is_dense = true;
332  pc_msg.is_bigendian = false;
333 
334  float* f_ptr = 0;
335  float* g_ptr = 0;
336  int pc_msg_idx=0;
337  for (int row = 0; row < cpp_xyz_image_32F3.rows; row++)
338  {
339  f_ptr = cpp_xyz_image_32F3.ptr<float>(row);
340  g_ptr = cpp_confidence_mask_32F1.ptr<float>(row);
341  for (int col = 0; col < cpp_xyz_image_32F3.cols; col++, pc_msg_idx++)
342  {
343  memcpy(&pc_msg.data[pc_msg_idx * pc_msg.point_step], &f_ptr[3*col], 3*sizeof(float));
344  memcpy(&pc_msg.data[pc_msg_idx * pc_msg.point_step + pc_msg.fields[3].offset], &g_ptr[col], sizeof(float));
345  }
346  }
347  topicPub_pointCloud2_.publish(pc_msg);
348  }
349 
350  bool imageSrvCallback(cob_camera_sensors::GetTOFImages::Request &req,
351  cob_camera_sensors::GetTOFImages::Response &res)
352  {
353  boost::mutex::scoped_lock lock(service_mutex_);
354  // Convert openCV IplImages to ROS messages
355  try
356  {
357  IplImage grey_img = grey_image_32F1_;
358  IplImage xyz_img = xyz_image_32F3_;
359  res.greyImage = *(sensor_msgs::CvBridge::cvToImgMsg(&grey_img, "passthrough"));
360  res.xyzImage = *(sensor_msgs::CvBridge::cvToImgMsg(&xyz_img, "passthrough"));
361  }
362  catch (sensor_msgs::CvBridgeException error)
363  {
364  ROS_ERROR("[tof_camera_type_node] Could not convert IplImage to ROS message");
365  }
366 
367  // Set time stamp
368  ros::Time now = ros::Time::now();
369  res.greyImage.header.stamp = now;
370  res.greyImage.header.frame_id = "head_tof_link";
371  res.xyzImage.header.stamp = now;
372  res.xyzImage.header.frame_id = "head_tof_link";
373  return true;
374  }
375 
377  {
378  std::string tmp_string = "NULL";
379 
381  if (node_handle_.getParam("tof_camera/configuration_files", config_directory_) == false)
382  {
383  ROS_ERROR("[tof_camera] Path to xml configuration for tof camera not specified");
384  return false;
385  }
386 
387  ROS_INFO("Configuration directory: %s", config_directory_.c_str());
388 
390  if (node_handle_.getParam("tof_camera/tof_camera_index", tof_camera_index_) == false)
391  {
392  ROS_ERROR("[tof_camera] 'tof_camera_index' (0 or 1) not specified");
393  return false;
394  }
395 
397  if (node_handle_.getParam("tof_camera/tof_camera_type", tmp_string) == false)
398  {
399  ROS_ERROR("[tof_camera] 'tof_camera_type' not specified");
400  return false;
401  }
402  if (tmp_string == "CAM_SWISSRANGER")
403  {
405  tof_camera_type_ = ipa_CameraSensors::CAM_SWISSRANGER;
406  }
407  else if (tmp_string == "CAM_VIRTUAL")
408  {
410  tof_camera_type_ = ipa_CameraSensors::CAM_VIRTUALRANGE;
411  }
412  else
413  {
414  std::string str = "[tof_camera] Camera type '" + tmp_string + "' unknown, try 'CAM_SWISSRANGER'";
415  ROS_ERROR("%s", str.c_str());
416  return false;
417  }
418 
419  ROS_INFO("Camera type: %s_%d", tmp_string.c_str(), tof_camera_index_);
420 
422  if (node_handle_.getParam("tof_camera/filter_xyz_by_amplitude", filter_xyz_by_amplitude_) == false)
423  {
424  ROS_ERROR("[tof_camera] 'filter_xyz_by_amplitude not specified");
425  return false;
426  }
428  if (node_handle_.getParam("tof_camera/filter_xyz_tearoff_edges", filter_xyz_tearoff_edges_) == false)
429  {
430  ROS_ERROR("[tof_camera] 'filter_xyz_tearoff_edges_' not specified");
431  return false;
432  }
434  if (node_handle_.getParam("tof_camera/lower_amplitude_threshold", lower_amplitude_threshold_) == false)
435  {
436  ROS_ERROR("[tof_camera] 'lower_amplitude_threshold' not specified");
437  return false;
438  }
440  if (node_handle_.getParam("tof_camera/upper_amplitude_threshold", upper_amplitude_threshold_) == false)
441  {
442  ROS_ERROR("[tof_camera] 'upper_amplitude_threshold' not specified");
443  return false;
444  }
446  if (node_handle_.getParam("tof_camera/tearoff_pi_half_fraction", tearoff_tear_half_fraction_) == false)
447  {
448  ROS_ERROR("[tof_camera] 'tearoff_pi_half_fraction' not specified");
449  return false;
450  }
452  if (node_handle_.getParam("tof_camera/ros_node_mode", tmp_string) == false)
453  {
454  ROS_ERROR("[tof_camera] Mode for tof camera node not specified");
455  return false;
456  }
457  if (tmp_string == "MODE_SERVICE")
458  {
459  ros_node_mode_ = CobTofCameraNode::MODE_SERVICE;
460  }
461  else if (tmp_string == "MODE_TOPIC")
462  {
463  ros_node_mode_ = CobTofCameraNode::MODE_TOPIC;
464  }
465  else
466  {
467  std::string str = "[tof_camera] Mode '" + tmp_string + "' unknown, try 'MODE_SERVICE' or 'MODE_TOPIC'";
468  ROS_ERROR("%s", str.c_str());
469  return false;
470  }
471 
472  if(node_handle_.getParam("tof_camera/publish_point_cloud", publish_point_cloud_) == false)
473  {
474  ROS_WARN("[tof_camera] Flag for publishing PointCloud not set, falling back to default (false)");
475  }
476  if(node_handle_.getParam("tof_camera/publish_point_cloud_2", publish_point_cloud_2_) == false)
477  {
478  ROS_WARN("[tof_camera] Flag for publishing PointCloud2 not set, falling back to default (false)");
479  }
480 
481 
482  ROS_INFO("ROS node mode: %s", tmp_string.c_str());
483 
484  return true;
485  }
486 };
487 
488 
489 //#######################
490 //#### main programm ####
491 int main(int argc, char** argv)
492 {
494  ros::init(argc, argv, "tof_camera");
495 
497  ros::NodeHandle nh;
498 
500  CobTofCameraNode camera_node(nh);
501 
503  if (!camera_node.init()) return 0;
504 
505  //ros::spin();
506  ros::Rate rate(100);
507  while(nh.ok())
508  {
509  camera_node.spin();
510  ros::spinOnce();
511  rate.sleep();
512  }
513 
514  return 0;
515 }
ros::NodeHandle node_handle_
Node handle.
Definition: tof_camera.cpp:58
d
ros::Publisher topicPub_pointCloud2_
Definition: tof_camera.cpp:64
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
boost::mutex service_mutex_
Definition: tof_camera.cpp:86
void publishPointCloud(ros::Time now)
Definition: tof_camera.cpp:276
void publish(const boost::shared_ptr< M > &message) const
CobTofCameraNode(const ros::NodeHandle &node_handle)
Constructor.
Definition: tof_camera.cpp:93
bool filter_xyz_by_amplitude_
Definition: tof_camera.cpp:76
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
Definition: tof_camera.cpp:199
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
__DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam()
ipa_CameraSensors::t_cameraType tof_camera_type_
Type of tof camera.
Definition: tof_camera.cpp:75
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
__DLL_LIBCAMERASENSORS__ CameraSensorToolboxPtr CreateCameraSensorToolbox()
#define ROS_WARN(...)
int lower_amplitude_threshold_
Definition: tof_camera.cpp:78
int tof_camera_index_
Camera index of the color camera for IPA configuration file.
Definition: tof_camera.cpp:74
ros::Publisher topicPub_pointCloud_
Definition: tof_camera.cpp:63
double tearoff_tear_half_fraction_
Definition: tof_camera.cpp:80
bool publish_point_cloud_2_
Definition: tof_camera.cpp:89
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool publish_point_cloud_
Definition: tof_camera.cpp:88
#define ROS_INFO(...)
image_transport::CameraPublisher xyz_image_publisher_
Publishes xyz image data.
Definition: tof_camera.cpp:61
boost::shared_ptr< AbstractRangeImagingSensor > AbstractRangeImagingSensorPtr
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer camera_info_service_
Service to set/modify camera parameters.
Definition: tof_camera.cpp:68
cv::Mat grey_image_32F1_
OpenCV image holding the point cloud.
Definition: tof_camera.cpp:83
bool sleep()
bool imageSrvCallback(cob_camera_sensors::GetTOFImages::Request &req, cob_camera_sensors::GetTOFImages::Response &res)
Definition: tof_camera.cpp:350
bool filter_xyz_tearoff_edges_
Definition: tof_camera.cpp:77
bool getParam(const std::string &key, std::string &s) const
cv::Mat xyz_image_32F3_
Definition: tof_camera.cpp:82
static Time now()
unsigned long FilterTearOffEdges(cv::Mat &xyzImage, cv::Mat *mask, float piHalfFraction=6)
std::string config_directory_
Directory of related IPA configuration file.
Definition: tof_camera.cpp:73
__DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Swissranger()
Definition: Swissranger.cpp:31
bool ok() const
int upper_amplitude_threshold_
Definition: tof_camera.cpp:79
unsigned long FilterByAmplitude(cv::Mat &xyzImage, const cv::Mat &greyImage, cv::Mat *mask, cv::Mat *maskColor, float minMaskThresh, float maxMaskThresh)
ROSCPP_DECL void spinOnce()
bool spin()
Continuously advertises xyz and grey images.
Definition: tof_camera.cpp:212
sensor_msgs::CameraInfo camera_info_msg_
ROS camera information message (e.g. holding intrinsic parameters)
Definition: tof_camera.cpp:66
#define ROS_ERROR(...)
~CobTofCameraNode()
Destructor.
Definition: tof_camera.cpp:106
int main(int argc, char **argv)
Definition: tof_camera.cpp:491
image_transport::CameraPublisher grey_image_publisher_
Publishes grey image data.
Definition: tof_camera.cpp:62
image_transport::ImageTransport image_transport_
Image transport instance.
Definition: tof_camera.cpp:60
CobTofCameraNode::t_Mode ros_node_mode_
OpenCV image holding the amplitude values.
Definition: tof_camera.cpp:85
AbstractRangeImagingSensorPtr tof_camera_
Time-of-flight camera instance.
Definition: tof_camera.cpp:71
ros::ServiceServer image_service_
Definition: tof_camera.cpp:69
void publishPointCloud2(ros::Time now)
Definition: tof_camera.cpp:303
#define ROS_DEBUG(...)


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Thu Mar 19 2020 03:23:05