nerian_stereo_node_base.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * Copyright (c) 2021 Nerian Vision GmbH
3  *
4  * Permission is hereby granted, free of charge, to any person obtaining a copy
5  * of this software and associated documentation files (the "Software"), to deal
6  * in the Software without restriction, including without limitation the rights
7  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8  * copies of the Software, and to permit persons to whom the Software is
9  * furnished to do so, subject to the following conditions:
10  *
11  * The above copyright notice and this permission notice shall be included in
12  * all copies or substantial portions of the Software.
13  *******************************************************************************/
14 
16 
17 namespace nerian_stereo {
18 
19 void StereoNodeBase::dynamicReconfigureCallback(nerian_stereo::NerianStereoConfig &config, uint32_t level) {
21  ROS_INFO("Received a new configuration via dynamic_reconfigure");
22  // Unfortunately, we have to check for each potential change (no configuration deltas provided).
23  // This is done in the autogenerated external code.
25  } else {
26  initialConfigReceived = true;
27  }
28  lastKnownConfig = config;
29 }
30 
31 void StereoNodeBase::updateParameterServerFromDevice(std::map<std::string, ParameterInfo>& cfg) {
32  // Publish the current config to the parameter server
34  // Publish reboot flag to definitely be set to false in the parameter server
35  getNH().setParam("/nerian_stereo/reboot", false);
36 }
37 
38 void StereoNodeBase::updateDynamicReconfigureFromDevice(std::map<std::string, ParameterInfo>& cfg) {
40 }
41 /*
42  * \brief Initialize and publish configuration with a dynamic_reconfigure server
43  */
45  std::map<std::string, ParameterInfo> ssParams;
46  // Connect to parameter server on device
47  ROS_INFO("Connecting to %s for parameter service", remoteHost.c_str());
48  try {
49  deviceParameters.reset(new DeviceParameters(remoteHost.c_str()));
50  } catch(visiontransfer::ParameterException& e) {
51  ROS_ERROR("ParameterException while connecting to parameter service: %s", e.what());
52  throw;
53  }
54  try {
55  ssParams = deviceParameters->getAllParameters();
56  } catch(visiontransfer::TransferException& e) {
57  ROS_ERROR("TransferException while obtaining parameter enumeration: %s", e.what());
58  throw;
59  } catch(visiontransfer::ParameterException& e) {
60  ROS_ERROR("ParameterException while obtaining parameter enumeration: %s", e.what());
61  throw;
62  }
63  // First make sure that the parameter server gets all *current* values
65  // Initialize (and publish) initial configuration from compile-time generated header
66  dynReconfServer.reset(new dynamic_reconfigure::Server<nerian_stereo::NerianStereoConfig>());
67  // Obtain and publish the default, min, and max values from the device to dyn_reconf
69  // Callback for future changes requested from the ROS side
70  dynReconfServer->setCallback(boost::bind(&StereoNodeBase::dynamicReconfigureCallback, this, _1, _2));
71 }
72 
77  ros::NodeHandle& privateNh = getPrivateNH();
78 
79  // Read all ROS parameters
80  std::string intensityChannel = "mono8";
81  privateNh.getParam("point_cloud_intensity_channel", intensityChannel);
82  if(intensityChannel == "none") {
84  } else if(intensityChannel == "rgb8") {
86  } else if(intensityChannel == "rgb32f") {
88  } else {
90  }
91 
92  if (!privateNh.getParam("color_code_disparity_map", colorCodeDispMap)) {
93  colorCodeDispMap = "";
94  }
95 
96  if (!privateNh.getParam("color_code_legend", colorCodeLegend)) {
97  colorCodeLegend = false;
98  }
99 
100  if (!privateNh.getParam("top_level_frame", frame)) {
101  if (!privateNh.getParam("frame", frame)) {
102  frame = "world";
103  }
104  }
105 
106  if (!privateNh.getParam("internal_frame", internalFrame)) {
107  internalFrame = "nerian_stereo";
108  }
109 
110  if (!privateNh.getParam("remote_port", remotePort)) {
111  remotePort = "7681";
112  }
113 
114  if (!privateNh.getParam("remote_host", remoteHost)) {
115  remoteHost = "0.0.0.0";
116  }
117 
118  if (!privateNh.getParam("use_tcp", useTcp)) {
119  useTcp = false;
120  }
121 
122  if (!privateNh.getParam("ros_coordinate_system", rosCoordinateSystem)) {
123  rosCoordinateSystem = true;
124  }
125 
126  if (!privateNh.getParam("ros_timestamps", rosTimestamps)) {
127  rosTimestamps = true;
128  }
129 
130  if (!privateNh.getParam("calibration_file", calibFile)) {
131  calibFile = "";
132  }
133 
134  if (!privateNh.getParam("delay_execution", execDelay)) {
135  execDelay = 0;
136  }
137 
138  if (!privateNh.getParam("max_depth", maxDepth)) {
139  maxDepth = -1;
140  }
141 
142  if (!privateNh.getParam("q_from_calib_file", useQFromCalibFile)) {
143  useQFromCalibFile = false;
144  }
145 
146  // Apply an initial delay if configured
148 
149  // Create publishers
150  disparityPublisher.reset(new ros::Publisher(getNH().advertise<sensor_msgs::Image>(
151  "/nerian_stereo/disparity_map", 5)));
152  leftImagePublisher.reset(new ros::Publisher(getNH().advertise<sensor_msgs::Image>(
153  "/nerian_stereo/left_image", 5)));
154  rightImagePublisher.reset(new ros::Publisher(getNH().advertise<sensor_msgs::Image>(
155  "/nerian_stereo/right_image", 5)));
156 
158 
159  cameraInfoPublisher.reset(new ros::Publisher(getNH().advertise<nerian_stereo::StereoCameraInfo>(
160  "/nerian_stereo/stereo_camera_info", 1)));
161  cloudPublisher.reset(new ros::Publisher(getNH().advertise<sensor_msgs::PointCloud2>(
162  "/nerian_stereo/point_cloud", 5)));
163 
165  currentTransform.header.stamp = ros::Time::now();
166  currentTransform.header.frame_id = frame;
167  currentTransform.child_frame_id = internalFrame;
168  currentTransform.transform.translation.x = 0.0;
169  currentTransform.transform.translation.y = 0.0;
170  currentTransform.transform.translation.z = 0.0;
171  currentTransform.transform.rotation.x = 0.0;
172  currentTransform.transform.rotation.y = 0.0;
173  currentTransform.transform.rotation.z = 0.0;
174  currentTransform.transform.rotation.w = 1.0;
175 
176 }
177 
179  dataChannelService.reset(new DataChannelService(remoteHost.c_str()));
180 }
181 
183  ROS_INFO("Connecting to %s:%s for data transfer", remoteHost.c_str(), remotePort.c_str());
184  asyncTransfer.reset(new AsyncTransfer(remoteHost.c_str(), remotePort.c_str(),
185  useTcp ? ImageProtocol::PROTOCOL_TCP : ImageProtocol::PROTOCOL_UDP));
186 }
187 
189  // Receive image data
190  ImageSet imageSet;
191  if(asyncTransfer->collectReceivedImageSet(imageSet, 0.005)) {
192 
193  // Get time stamp
194  ros::Time stamp;
195  if(rosTimestamps) {
196  stamp = ros::Time::now();
197  } else {
198  int secs = 0, microsecs = 0;
199  imageSet.getTimestamp(secs, microsecs);
200  stamp = ros::Time(secs, microsecs*1000);
201  }
202 
203  // Publish image data messages for all images included in the set
204  if (imageSet.hasImageType(ImageSet::IMAGE_LEFT)) {
205  publishImageMsg(imageSet, imageSet.getIndexOf(ImageSet::IMAGE_LEFT), stamp, false, leftImagePublisher.get());
206  }
207  if (imageSet.hasImageType(ImageSet::IMAGE_DISPARITY)) {
208  publishImageMsg(imageSet, imageSet.getIndexOf(ImageSet::IMAGE_DISPARITY), stamp, true, disparityPublisher.get());
209  }
210  if (imageSet.hasImageType(ImageSet::IMAGE_RIGHT)) {
211  publishImageMsg(imageSet, imageSet.getIndexOf(ImageSet::IMAGE_RIGHT), stamp, false, rightImagePublisher.get());
212  }
213 
214  if(cloudPublisher->getNumSubscribers() > 0) {
215  if(recon3d == nullptr) {
216  // First initialize
217  initPointCloud();
218  }
219 
220  publishPointCloudMsg(imageSet, stamp);
221  }
222 
223  if(cameraInfoPublisher != NULL && cameraInfoPublisher->getNumSubscribers() > 0) {
224  publishCameraInfo(stamp, imageSet);
225  }
226 
227  // Display some simple statistics
228  frameNum++;
229  if(stamp.sec != lastLogTime.sec) {
230  if(lastLogTime != ros::Time()) {
231  double dt = (stamp - lastLogTime).toSec();
232  double fps = (frameNum - lastLogFrames) / dt;
233  ROS_INFO("%.1f fps", fps);
234  }
236  lastLogTime = stamp;
237  }
238  }
239 }
240 
242  if(calibFile == "" ) {
243  ROS_WARN("No camera calibration file configured. Cannot publish detailed camera information!");
244  } else {
245  bool success = false;
246  try {
247  if (calibStorage.open(calibFile, cv::FileStorage::READ)) {
248  success = true;
249  }
250  } catch(...) {
251  }
252 
253  if(!success) {
254  ROS_WARN("Error reading calibration file: %s\n"
255  "Cannot publish detailed camera information!", calibFile.c_str());
256  }
257  }
258 }
259 
260 void StereoNodeBase::publishImageMsg(const ImageSet& imageSet, int imageIndex, ros::Time stamp, bool allowColorCode,
261  ros::Publisher* publisher) {
262 
263  if(publisher->getNumSubscribers() <= 0) {
264  return; //No subscribers
265  }
266 
267  cv_bridge::CvImage cvImg;
268  cvImg.header.frame_id = internalFrame;
269  cvImg.header.stamp = stamp;
270  cvImg.header.seq = imageSet.getSequenceNumber(); // Actually ROS will overwrite this
271 
272  bool format12Bit = (imageSet.getPixelFormat(imageIndex) == ImageSet::FORMAT_12_BIT_MONO);
273  string encoding = "";
274  bool ok = true;
275 
276  if(colorCodeDispMap == "" || colorCodeDispMap == "none" || !allowColorCode || !format12Bit) {
277  switch (imageSet.getPixelFormat(imageIndex)) {
278  case ImageSet::FORMAT_8_BIT_RGB: {
279  cv::Mat rgbImg(imageSet.getHeight(), imageSet.getWidth(),
280  CV_8UC3,
281  imageSet.getPixelData(imageIndex), imageSet.getRowStride(imageIndex));
282  cvImg.image = rgbImg;
283  encoding = "rgb8";
284  break;
285  }
286  case ImageSet::FORMAT_8_BIT_MONO:
287  case ImageSet::FORMAT_12_BIT_MONO: {
288  cv::Mat monoImg(imageSet.getHeight(), imageSet.getWidth(),
289  format12Bit ? CV_16UC1 : CV_8UC1,
290  imageSet.getPixelData(imageIndex), imageSet.getRowStride(imageIndex));
291  cvImg.image = monoImg;
292  encoding = (format12Bit ? "mono16": "mono8");
293  break;
294  }
295  default: {
296  ROS_WARN("Omitting an image with unhandled pixel format");
297  ok = false;
298  }
299  }
300  } else {
301  cv::Mat monoImg(imageSet.getHeight(), imageSet.getWidth(),
302  format12Bit ? CV_16UC1 : CV_8UC1,
303  imageSet.getPixelData(imageIndex), imageSet.getRowStride(imageIndex));
304 
305  if(colCoder == NULL) {
306  int dispMin = 0, dispMax = 0;
307  imageSet.getDisparityRange(dispMin, dispMax);
308 
309  colCoder.reset(new ColorCoder(
310  colorCodeDispMap == "rainbow" ? ColorCoder::COLOR_RAINBOW_BGR : ColorCoder::COLOR_RED_BLUE_BGR,
311  dispMin*16, dispMax*16, true, true));
312  if(colorCodeLegend) {
313  // Create the legend
314  colDispMap = colCoder->createLegendBorder(monoImg.cols, monoImg.rows, 1.0/16.0);
315  } else {
316  colDispMap = cv::Mat_<cv::Vec3b>(monoImg.rows, monoImg.cols);
317  }
318  }
319 
320  cv::Mat_<cv::Vec3b> dispSection = colDispMap(cv::Rect(0, 0, monoImg.cols, monoImg.rows));
321 
322  colCoder->codeImage(cv::Mat_<unsigned short>(monoImg), dispSection);
323  cvImg.image = colDispMap;
324  encoding = "bgr8";
325  }
326 
327  if (ok) {
328  sensor_msgs::ImagePtr msg = cvImg.toImageMsg();
329  msg->encoding = encoding;
330  publisher->publish(msg);
331  }
332 }
333 
334 void StereoNodeBase::qMatrixToRosCoords(const float* src, float* dst) {
335  dst[0] = src[8]; dst[1] = src[9];
336  dst[2] = src[10]; dst[3] = src[11];
337 
338  dst[4] = -src[0]; dst[5] = -src[1];
339  dst[6] = -src[2]; dst[7] = -src[3];
340 
341  dst[8] = -src[4]; dst[9] = -src[5];
342  dst[10] = -src[6]; dst[11] = -src[7];
343 
344  dst[12] = src[12]; dst[13] = src[13];
345  dst[14] = src[14]; dst[15] = src[15];
346 }
347 
348 void StereoNodeBase::publishPointCloudMsg(ImageSet& imageSet, ros::Time stamp) {
349  if ((!imageSet.hasImageType(ImageSet::IMAGE_DISPARITY))
350  || (imageSet.getPixelFormat(ImageSet::IMAGE_DISPARITY) != ImageSet::FORMAT_12_BIT_MONO)) {
351  return; // This is not a disparity map
352  }
353 
354  // Set static q matrix if desired
355  if(useQFromCalibFile) {
356  static std::vector<float> q;
357  calibStorage["Q"] >> q;
358  imageSet.setQMatrix(&q[0]);
359  }
360 
361  // Transform Q-matrix if desired
362  float qRos[16];
363  if(rosCoordinateSystem) {
364  qMatrixToRosCoords(imageSet.getQMatrix(), qRos);
365  imageSet.setQMatrix(qRos);
366  }
367 
368  // Get 3D points
369  float* pointMap = nullptr;
370  try {
371  pointMap = recon3d->createPointMap(imageSet, 0);
372  } catch(std::exception& ex) {
373  cerr << "Error creating point cloud: " << ex.what() << endl;
374  return;
375  }
376 
377  // Create message object and set header
378  pointCloudMsg->header.stamp = stamp;
379  pointCloudMsg->header.frame_id = internalFrame;
380  pointCloudMsg->header.seq = imageSet.getSequenceNumber(); // Actually ROS will overwrite this
381 
382  // Copy 3D points
383  if(pointCloudMsg->data.size() != imageSet.getWidth()*imageSet.getHeight()*4*sizeof(float)) {
384  // Allocate buffer
385  pointCloudMsg->data.resize(imageSet.getWidth()*imageSet.getHeight()*4*sizeof(float));
386 
387  // Set basic data
388  pointCloudMsg->width = imageSet.getWidth();
389  pointCloudMsg->height = imageSet.getHeight();
390  pointCloudMsg->is_bigendian = false;
391  pointCloudMsg->point_step = 4*sizeof(float);
392  pointCloudMsg->row_step = imageSet.getWidth() * pointCloudMsg->point_step;
393  pointCloudMsg->is_dense = false;
394  }
395 
396  if(maxDepth < 0) {
397  // Just copy everything
398  memcpy(&pointCloudMsg->data[0], pointMap,
399  imageSet.getWidth()*imageSet.getHeight()*4*sizeof(float));
400  } else {
401  // Only copy points up to maximum depth
402  if(rosCoordinateSystem) {
403  copyPointCloudClamped<0>(pointMap, reinterpret_cast<float*>(&pointCloudMsg->data[0]),
404  imageSet.getWidth()*imageSet.getHeight());
405  } else {
406  copyPointCloudClamped<2>(pointMap, reinterpret_cast<float*>(&pointCloudMsg->data[0]),
407  imageSet.getWidth()*imageSet.getHeight());
408  }
409  }
410 
411  if (imageSet.hasImageType(ImageSet::IMAGE_LEFT)) {
412  // Copy intensity values as well (if we received any image data)
413  switch(pointCloudColorMode) {
414  case INTENSITY:
415  copyPointCloudIntensity<INTENSITY>(imageSet);
416  break;
417  case RGB_COMBINED:
418  copyPointCloudIntensity<RGB_COMBINED>(imageSet);
419  break;
420  case RGB_SEPARATE:
421  copyPointCloudIntensity<RGB_SEPARATE>(imageSet);
422  break;
423  case NONE:
424  break;
425  }
426  }
427 
428  cloudPublisher->publish(pointCloudMsg);
429 }
430 
431 template <StereoNodeBase::PointCloudColorMode colorMode> void StereoNodeBase::copyPointCloudIntensity(ImageSet& imageSet) {
432  // Get pointers to the beginning and end of the point cloud
433  unsigned char* cloudStart = &pointCloudMsg->data[0];
434  unsigned char* cloudEnd = &pointCloudMsg->data[0]
435  + imageSet.getWidth()*imageSet.getHeight()*4*sizeof(float);
436 
437  if(imageSet.getPixelFormat(ImageSet::IMAGE_LEFT) == ImageSet::FORMAT_8_BIT_MONO) {
438  // Get pointer to the current pixel and end of current row
439  unsigned char* imagePtr = imageSet.getPixelData(ImageSet::IMAGE_LEFT);
440  unsigned char* rowEndPtr = imagePtr + imageSet.getWidth();
441  int rowIncrement = imageSet.getRowStride(ImageSet::IMAGE_LEFT) - imageSet.getWidth();
442 
443  for(unsigned char* cloudPtr = cloudStart + 3*sizeof(float);
444  cloudPtr < cloudEnd; cloudPtr+= 4*sizeof(float)) {
445  if(colorMode == RGB_SEPARATE) {// RGB as float
446  *reinterpret_cast<float*>(cloudPtr) = static_cast<float>(*imagePtr) / 255.0F;
447  } else if(colorMode == RGB_COMBINED) {// RGB as integer
448  const unsigned char intensity = *imagePtr;
449  *reinterpret_cast<unsigned int*>(cloudPtr) = (intensity << 16) | (intensity << 8) | intensity;
450  } else {
451  *cloudPtr = *imagePtr;
452  }
453 
454  imagePtr++;
455  if(imagePtr == rowEndPtr) {
456  // Progress to next row
457  imagePtr += rowIncrement;
458  rowEndPtr = imagePtr + imageSet.getWidth();
459  }
460  }
461  } else if(imageSet.getPixelFormat(ImageSet::IMAGE_LEFT) == ImageSet::FORMAT_12_BIT_MONO) {
462  // Get pointer to the current pixel and end of current row
463  unsigned short* imagePtr = reinterpret_cast<unsigned short*>(imageSet.getPixelData(ImageSet::IMAGE_LEFT));
464  unsigned short* rowEndPtr = imagePtr + imageSet.getWidth();
465  int rowIncrement = imageSet.getRowStride(ImageSet::IMAGE_LEFT) - 2*imageSet.getWidth();
466 
467  for(unsigned char* cloudPtr = cloudStart + 3*sizeof(float);
468  cloudPtr < cloudEnd; cloudPtr+= 4*sizeof(float)) {
469 
470  if(colorMode == RGB_SEPARATE) {// RGB as float
471  *reinterpret_cast<float*>(cloudPtr) = static_cast<float>(*imagePtr) / 4095.0F;
472  } else if(colorMode == RGB_COMBINED) {// RGB as integer
473  const unsigned char intensity = *imagePtr/16;
474  *reinterpret_cast<unsigned int*>(cloudPtr) = (intensity << 16) | (intensity << 8) | intensity;
475  } else {
476  *cloudPtr = *imagePtr/16;
477  }
478 
479  imagePtr++;
480  if(imagePtr == rowEndPtr) {
481  // Progress to next row
482  imagePtr += rowIncrement;
483  rowEndPtr = imagePtr + imageSet.getWidth();
484  }
485  }
486  } else if(imageSet.getPixelFormat(ImageSet::IMAGE_LEFT) == ImageSet::FORMAT_8_BIT_RGB) {
487  // Get pointer to the current pixel and end of current row
488  unsigned char* imagePtr = imageSet.getPixelData(ImageSet::IMAGE_LEFT);
489  unsigned char* rowEndPtr = imagePtr + imageSet.getWidth();
490  int rowIncrement = imageSet.getRowStride(ImageSet::IMAGE_LEFT) - imageSet.getWidth();
491 
492  static bool warned = false;
493  if(colorMode == RGB_SEPARATE && !warned) {
494  warned = true;
495  ROS_WARN("RGBF32 is not supported for color images. Please use RGB8!");
496  }
497 
498  for(unsigned char* cloudPtr = cloudStart + 3*sizeof(float);
499  cloudPtr < cloudEnd; cloudPtr+= 4*sizeof(float)) {
500  if(colorMode == RGB_SEPARATE) {// RGB as float
501  *reinterpret_cast<float*>(cloudPtr) = static_cast<float>(imagePtr[2]) / 255.0F;
502  } else if(colorMode == RGB_COMBINED) {// RGB as integer
503  *reinterpret_cast<unsigned int*>(cloudPtr) = (imagePtr[0] << 16) | (imagePtr[1] << 8) | imagePtr[2];
504  } else {
505  *cloudPtr = (imagePtr[0] + imagePtr[1]*2 + imagePtr[2])/4;
506  }
507 
508  imagePtr+=3;
509  if(imagePtr == rowEndPtr) {
510  // Progress to next row
511  imagePtr += rowIncrement;
512  rowEndPtr = imagePtr + imageSet.getWidth();
513  }
514  }
515  } else {
516  throw std::runtime_error("Invalid pixel format!");
517  }
518 }
519 
520 template <int coord> void StereoNodeBase::copyPointCloudClamped(float* src, float* dst, int size) {
521  // Only copy points that are below the minimum depth
522  float* endPtr = src + 4*size;
523  for(float *srcPtr = src, *dstPtr = dst; srcPtr < endPtr; srcPtr+=4, dstPtr+=4) {
524  if(srcPtr[coord] > maxDepth) {
525  dstPtr[0] = std::numeric_limits<float>::quiet_NaN();
526  dstPtr[1] = std::numeric_limits<float>::quiet_NaN();
527  dstPtr[2] = std::numeric_limits<float>::quiet_NaN();
528  } else {
529  dstPtr[0] = srcPtr[0];
530  dstPtr[1] = srcPtr[1];
531  dstPtr[2] = srcPtr[2];
532  }
533  }
534 }
535 
537  //ros::NodeHandle privateNh("~"); // RYT TODO check
538 
539  // Initialize 3D reconstruction class
540  recon3d.reset(new Reconstruct3D);
541 
542  // Initialize message
543  pointCloudMsg.reset(new sensor_msgs::PointCloud2);
544 
545  // Set channel information.
546  sensor_msgs::PointField fieldX;
547  fieldX.name ="x";
548  fieldX.offset = 0;
549  fieldX.datatype = sensor_msgs::PointField::FLOAT32;
550  fieldX.count = 1;
551  pointCloudMsg->fields.push_back(fieldX);
552 
553  sensor_msgs::PointField fieldY;
554  fieldY.name ="y";
555  fieldY.offset = sizeof(float);
556  fieldY.datatype = sensor_msgs::PointField::FLOAT32;
557  fieldY.count = 1;
558  pointCloudMsg->fields.push_back(fieldY);
559 
560  sensor_msgs::PointField fieldZ;
561  fieldZ.name ="z";
562  fieldZ.offset = 2*sizeof(float);
563  fieldZ.datatype = sensor_msgs::PointField::FLOAT32;
564  fieldZ.count = 1;
565  pointCloudMsg->fields.push_back(fieldZ);
566 
568  sensor_msgs::PointField fieldI;
569  fieldI.name ="intensity";
570  fieldI.offset = 3*sizeof(float);
571  fieldI.datatype = sensor_msgs::PointField::UINT8;
572  fieldI.count = 1;
573  pointCloudMsg->fields.push_back(fieldI);
574  }
575  else if(pointCloudColorMode == RGB_SEPARATE) {
576  sensor_msgs::PointField fieldRed;
577  fieldRed.name ="r";
578  fieldRed.offset = 3*sizeof(float);
579  fieldRed.datatype = sensor_msgs::PointField::FLOAT32;
580  fieldRed.count = 1;
581  pointCloudMsg->fields.push_back(fieldRed);
582 
583  sensor_msgs::PointField fieldGreen;
584  fieldGreen.name ="g";
585  fieldGreen.offset = 3*sizeof(float);
586  fieldGreen.datatype = sensor_msgs::PointField::FLOAT32;
587  fieldGreen.count = 1;
588  pointCloudMsg->fields.push_back(fieldGreen);
589 
590  sensor_msgs::PointField fieldBlue;
591  fieldBlue.name ="b";
592  fieldBlue.offset = 3*sizeof(float);
593  fieldBlue.datatype = sensor_msgs::PointField::FLOAT32;
594  fieldBlue.count = 1;
595  pointCloudMsg->fields.push_back(fieldBlue);
596  } else if(pointCloudColorMode == RGB_COMBINED) {
597  sensor_msgs::PointField fieldRGB;
598  fieldRGB.name ="rgb";
599  fieldRGB.offset = 3*sizeof(float);
600  fieldRGB.datatype = sensor_msgs::PointField::UINT32;
601  fieldRGB.count = 1;
602  pointCloudMsg->fields.push_back(fieldRGB);
603  }
604 }
605 
606 void StereoNodeBase::publishCameraInfo(ros::Time stamp, const ImageSet& imageSet) {
607  if(camInfoMsg == NULL) {
608  // Initialize the camera info structure
609  camInfoMsg.reset(new nerian_stereo::StereoCameraInfo);
610 
611  camInfoMsg->header.frame_id = internalFrame;
612  camInfoMsg->header.seq = imageSet.getSequenceNumber(); // Actually ROS will overwrite this
613 
614  if(calibFile != "") {
615  std::vector<int> sizeVec;
616  calibStorage["size"] >> sizeVec;
617  if(sizeVec.size() != 2) {
618  std::runtime_error("Calibration file format error!");
619  }
620 
621  camInfoMsg->left_info.header = camInfoMsg->header;
622  camInfoMsg->left_info.width = sizeVec[0];
623  camInfoMsg->left_info.height = sizeVec[1];
624  camInfoMsg->left_info.distortion_model = "plumb_bob";
625  calibStorage["D1"] >> camInfoMsg->left_info.D;
626  readCalibrationArray("M1", camInfoMsg->left_info.K);
627  readCalibrationArray("R1", camInfoMsg->left_info.R);
628  readCalibrationArray("P1", camInfoMsg->left_info.P);
629  camInfoMsg->left_info.binning_x = 1;
630  camInfoMsg->left_info.binning_y = 1;
631  camInfoMsg->left_info.roi.do_rectify = false;
632  camInfoMsg->left_info.roi.height = 0;
633  camInfoMsg->left_info.roi.width = 0;
634  camInfoMsg->left_info.roi.x_offset = 0;
635  camInfoMsg->left_info.roi.y_offset = 0;
636 
637  camInfoMsg->right_info.header = camInfoMsg->header;
638  camInfoMsg->right_info.width = sizeVec[0];
639  camInfoMsg->right_info.height = sizeVec[1];
640  camInfoMsg->right_info.distortion_model = "plumb_bob";
641  calibStorage["D2"] >> camInfoMsg->right_info.D;
642  readCalibrationArray("M2", camInfoMsg->right_info.K);
643  readCalibrationArray("R2", camInfoMsg->right_info.R);
644  readCalibrationArray("P2", camInfoMsg->right_info.P);
645  camInfoMsg->right_info.binning_x = 1;
646  camInfoMsg->right_info.binning_y = 1;
647  camInfoMsg->right_info.roi.do_rectify = false;
648  camInfoMsg->right_info.roi.height = 0;
649  camInfoMsg->right_info.roi.width = 0;
650  camInfoMsg->right_info.roi.x_offset = 0;
651  camInfoMsg->right_info.roi.y_offset = 0;
652 
654  readCalibrationArray("T", camInfoMsg->T_left_right);
655  readCalibrationArray("R", camInfoMsg->R_left_right);
656  }
657  }
658 
659  double dt = (stamp - lastCamInfoPublish).toSec();
660  if(dt > 1.0) {
661  // Rather use the Q-matrix that we received over the network if it is valid
662  const float* qMatrix = imageSet.getQMatrix();
663  if(qMatrix[0] != 0.0) {
664  for(int i=0; i<16; i++) {
665  camInfoMsg->Q[i] = static_cast<double>(qMatrix[i]);
666  }
667  }
668 
669  // Publish once per second
670  camInfoMsg->header.stamp = stamp;
671  camInfoMsg->left_info.header.stamp = stamp;
672  camInfoMsg->right_info.header.stamp = stamp;
674 
675  lastCamInfoPublish = stamp;
676  }
677 }
678 
679 template<class T> void StereoNodeBase::readCalibrationArray(const char* key, T& dest) {
680  std::vector<double> doubleVec;
681  calibStorage[key] >> doubleVec;
682 
683  if(doubleVec.size() != dest.size()) {
684  std::runtime_error("Calibration file format error!");
685  }
686 
687  std::copy(doubleVec.begin(), doubleVec.end(), dest.begin());
688 }
689 
691  auto now = ros::Time::now();
692  if ((now - currentTransform.header.stamp).toSec() < 0.01) {
693  // Limit to 100 Hz transform update frequency
694  return;
695  }
696  if (dataChannelService->imuAvailable()) {
697  // Obtain and publish the most recent orientation
698  TimestampedQuaternion tsq = dataChannelService->imuGetRotationQuaternion();
699  currentTransform.header.stamp = now;
700  if(rosCoordinateSystem) {
701  currentTransform.transform.rotation.x = tsq.x();
702  currentTransform.transform.rotation.y = -tsq.z();
703  currentTransform.transform.rotation.z = tsq.y();
704  } else {
705  currentTransform.transform.rotation.x = tsq.x();
706  currentTransform.transform.rotation.y = tsq.y();
707  currentTransform.transform.rotation.z = tsq.z();
708  }
709  currentTransform.transform.rotation.w = tsq.w();
710 
711  /*
712  // DEBUG: Quaternion->Euler + debug output
713  double roll, pitch, yaw;
714  tf2::Quaternion q(tsq.x(), rosCoordinateSystem?(-tsq.z()):tsq.y(), rosCoordinateSystem?tsq.y():tsq.z(), tsq.w());
715  tf2::Matrix3x3 m(q);
716  m.getRPY(roll, pitch, yaw);
717  std::cout << "Orientation:" << std::setprecision(2) << std::fixed << " Roll " << (180.0*roll/M_PI) << " Pitch " << (180.0*pitch/M_PI) << " Yaw " << (180.0*yaw/M_PI) << std::endl;
718  */
719 
721  } else {
722  // We must periodically republish due to ROS interval constraints
723  /*
724  // DEBUG: Impart a (fake) periodic horizontal swaying motion
725  static double DEBUG_t = 0.0;
726  DEBUG_t += 0.1;
727  tf2::Quaternion q;
728  q.setRPY(0, 0, 0.3*sin(DEBUG_t));
729  currentTransform.header.stamp = ros::Time::now();
730  currentTransform.transform.rotation.x = q.x();
731  currentTransform.transform.rotation.y = q.y();
732  currentTransform.transform.rotation.z = q.z();
733  currentTransform.transform.rotation.w = q.w();
734  */
735  currentTransform.header.stamp = now;
737  }
738 }
739 
741  transformBroadcaster->sendTransform(currentTransform);
742 }
743 
744 } // namespace
virtual ros::NodeHandle & getPrivateNH()=0
void prepareAsyncTransfer()
Connects to the image service to request the stream of image sets.
sensor_msgs::PointCloud2Ptr pointCloudMsg
boost::scoped_ptr< dynamic_reconfigure::Server< nerian_stereo::NerianStereoConfig > > dynReconfServer
boost::scoped_ptr< ColorCoder > colCoder
boost::scoped_ptr< DataChannelService > dataChannelService
void publish(const boost::shared_ptr< M > &message) const
void copyPointCloudIntensity(ImageSet &imageSet)
Copies the intensity or RGB data to the point cloud.
virtual ros::NodeHandle & getNH()=0
void loadCameraCalibration()
Loads a camera calibration file if configured.
nerian_stereo::StereoCameraInfoPtr camInfoMsg
boost::scoped_ptr< ros::Publisher > rightImagePublisher
bool sleep() const
void autogen_updateParameterServerFromDevice(std::map< std::string, ParameterInfo > &cfg)
Auto-generated code to set initial parameters according to those obtained from the device...
void autogen_updateDynamicReconfigureFromDevice(std::map< std::string, ParameterInfo > &cfg)
Auto-generated code to override the dynamic_reconfigure limits and defaults for all parameters...
void dynamicReconfigureCallback(nerian_stereo::NerianStereoConfig &config, uint32_t level)
#define ROS_WARN(...)
geometry_msgs::TransformStamped currentTransform
void publishImageMsg(const ImageSet &imageSet, int imageIndex, ros::Time stamp, bool allowColorCode, ros::Publisher *publisher)
Publishes the disparity map as 16-bit grayscale image or color coded RGB image.
#define ROS_INFO(...)
void initPointCloud()
Performs all neccessary initializations for point cloud+ publishing.
void readCalibrationArray(const char *key, T &dest)
Reads a vector from the calibration file to a boost:array.
boost::scoped_ptr< Reconstruct3D > recon3d
boost::scoped_ptr< ros::Publisher > cloudPublisher
boost::scoped_ptr< ros::Publisher > disparityPublisher
boost::scoped_ptr< tf2_ros::TransformBroadcaster > transformBroadcaster
uint32_t getNumSubscribers() const
void publishPointCloudMsg(ImageSet &imageSet, ros::Time stamp)
Reconstructs the 3D locations form the disparity map and publishes them as point cloud.
bool getParam(const std::string &key, std::string &s) const
A driver node that receives data from Nerian stereo devices and forwards it to ROS.
boost::scoped_ptr< ros::Publisher > leftImagePublisher
void updateParameterServerFromDevice(std::map< std::string, ParameterInfo > &cfg)
void updateDynamicReconfigureFromDevice(std::map< std::string, ParameterInfo > &cfg)
static Time now()
boost::scoped_ptr< DeviceParameters > deviceParameters
void copyPointCloudClamped(float *src, float *dst, int size)
Copies all points in a point cloud that have a depth smaller than maxDepth. Other points are set to N...
void publishCameraInfo(ros::Time stamp, const ImageSet &imageSet)
Publishes the camera info once per second.
void qMatrixToRosCoords(const float *src, float *dst)
Transform Q matrix to match the ROS coordinate system: Swap y/z axis, then swap x/y axis...
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
sensor_msgs::ImagePtr toImageMsg() const
void init()
Performs general initializations.
void autogen_dynamicReconfigureCallback(nerian_stereo::NerianStereoConfig &config, uint32_t level)
Auto-generated code to check for parameter changes and forward them to the device.
std_msgs::Header header
boost::scoped_ptr< ros::Publisher > cameraInfoPublisher
nerian_stereo::NerianStereoConfig lastKnownConfig
boost::scoped_ptr< AsyncTransfer > asyncTransfer


nerian_stereo
Author(s): Nerian Vision Technologies
autogenerated on Fri Apr 16 2021 02:11:19