astra_driver.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * Copyright (c) 2016, Orbbec Ltd.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  *
30  * Author: Tim Liu (liuhua@orbbec.com)
31  */
32 
36 
37 #include <unistd.h>
38 #include <stdlib.h>
39 #include <stdio.h>
40 #include <sys/shm.h>
43 
44 #include <boost/date_time/posix_time/posix_time.hpp>
45 #include <boost/thread/thread.hpp>
46 
47 #define MULTI_ASTRA 1
48 namespace astra_wrapper
49 {
50 
52  nh_(n),
53  pnh_(pnh),
54  device_manager_(AstraDeviceManager::getSingelton()),
55  config_init_(false),
56  data_skip_ir_counter_(0),
57  data_skip_color_counter_(0),
58  data_skip_depth_counter_ (0),
59  ir_subscribers_(false),
60  color_subscribers_(false),
61  depth_subscribers_(false),
62  depth_raw_subscribers_(false),
63  uvc_flip_(0)
64 {
65 
67 
69 
70 #if MULTI_ASTRA
71  int bootOrder, devnums;
72  if (!pnh.getParam("bootorder", bootOrder))
73  {
74  bootOrder = 0;
75  }
76 
77  if (!pnh.getParam("devnums", devnums))
78  {
79  devnums = 1;
80  }
81 
82  if( devnums>1 )
83  {
84  int shmid;
85  char *shm = NULL;
86  char *tmp;
87 
88  if( bootOrder==1 )
89  {
90  if( (shmid = shmget((key_t)0401, 1, 0666|IPC_CREAT)) == -1 )
91  {
92  ROS_ERROR("Create Share Memory Error:%s", strerror(errno));
93  }
94  shm = (char *)shmat(shmid, 0, 0);
95  *shm = 1;
96  initDevice();
97  ROS_INFO("*********** device_id %s already open device************************ ", device_id_.c_str());
98  *shm = 2;
99  }
100  else
101  {
102  if( (shmid = shmget((key_t)0401, 1, 0666|IPC_CREAT)) == -1 )
103  {
104  ROS_ERROR("Create Share Memory Error:%s", strerror(errno));
105  }
106  shm = (char *)shmat(shmid, 0, 0);
107  while( *shm!=bootOrder)
108  {
109  boost::this_thread::sleep(boost::posix_time::milliseconds(10));
110  }
111 
112  initDevice();
113  ROS_INFO("*********** device_id %s already open device************************ ", device_id_.c_str());
114  *shm = (bootOrder+1);
115  }
116  if( bootOrder==devnums )
117  {
118  if(shmdt(shm) == -1)
119  {
120  ROS_ERROR("shmdt failed\n");
121  }
122  if(shmctl(shmid, IPC_RMID, 0) == -1)
123  {
124  ROS_ERROR("shmctl(IPC_RMID) failed\n");
125  }
126  }
127  else
128  {
129  if(shmdt(shm) == -1)
130  {
131  ROS_ERROR("shmdt failed\n");
132  }
133  }
134  }
135  else
136  {
137  initDevice();
138  }
139 #else
140  initDevice();
141 
142 #endif
143  // Initialize dynamic reconfigure
145  reconfigure_server_->setCallback(boost::bind(&AstraDriver::configCb, this, _1, _2));
146 
147  while (!config_init_)
148  {
149  ROS_DEBUG("Waiting for dynamic reconfigure configuration.");
150  boost::this_thread::sleep(boost::posix_time::milliseconds(100));
151  }
152  ROS_DEBUG("Dynamic reconfigure configuration received.");
153 
155 }
156 
158  device_->stopAllStreams();
159 }
160 
162 {
163 
164  // Allow remapping namespaces rgb, ir, depth, depth_registered
165  ros::NodeHandle color_nh(nh_, "rgb");
166  image_transport::ImageTransport color_it(color_nh);
167  ros::NodeHandle ir_nh(nh_, "ir");
168  image_transport::ImageTransport ir_it(ir_nh);
169  ros::NodeHandle depth_nh(nh_, "depth");
170  image_transport::ImageTransport depth_it(depth_nh);
171  ros::NodeHandle depth_raw_nh(nh_, "depth");
172  image_transport::ImageTransport depth_raw_it(depth_raw_nh);
173  ros::NodeHandle projector_nh(nh_, "projector");
174  // Advertise all published topics
175 
176  // Prevent connection callbacks from executing until we've set all the publishers. Otherwise
177  // connectCb() can fire while we're advertising (say) "depth/image_raw", but before we actually
178  // assign to pub_depth_raw_. Then pub_depth_raw_.getNumSubscribers() returns 0, and we fail to start
179  // the depth generator.
180  boost::lock_guard<boost::mutex> lock(connect_mutex_);
181 
182  // Asus Xtion PRO does not have an RGB camera
183  //ROS_WARN("-------------has color sensor is %d----------- ", device_->hasColorSensor());
184  if (device_->hasColorSensor())
185  {
188  pub_color_ = color_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
189  }
190 
191  if (device_->hasIRSensor())
192  {
195  pub_ir_ = ir_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
196  }
197 
198  if (device_->hasDepthSensor())
199  {
202  pub_depth_raw_ = depth_it.advertiseCamera("image_raw", 1, itssc, itssc, rssc, rssc);
203  pub_depth_ = depth_raw_it.advertiseCamera("image", 1, itssc, itssc, rssc, rssc);
204  pub_projector_info_ = projector_nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, rssc, rssc);
205  }
206 
208 
209  // Pixel offset between depth and IR images.
210  // By default assume offset of (5,4) from 9x7 correlation window.
211  // NOTE: These are now (temporarily?) dynamically reconfigurable, to allow tweaking.
212  //param_nh.param("depth_ir_offset_x", depth_ir_offset_x_, 5.0);
213  //param_nh.param("depth_ir_offset_y", depth_ir_offset_y_, 4.0);
214 
215  // The camera names are set to [rgb|depth]_[serial#], e.g. depth_B00367707227042B.
216  // camera_info_manager substitutes this for ${NAME} in the URL.
217  std::string serial_number = device_->getStringID();
218  std::string color_name, ir_name;
219 
220  color_name = "rgb_" + serial_number;
221  ir_name = "depth_" + serial_number;
222 
223  // Load the saved calibrations, if they exist
224  color_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(color_nh, color_name, color_info_url_);
225  ir_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh, ir_name, ir_info_url_);
226 
239  if (device_->getDeviceTypeNo() == OB_STEREO_S_NO || device_->getDeviceTypeNo() == OB_STEREO_S_U3_NO)
240  {
242  }
243 }
244 
245 bool AstraDriver::getSerialCb(astra_camera::GetSerialRequest& req, astra_camera::GetSerialResponse& res)
246 {
247  res.serial = device_manager_->getSerial(device_->getUri());
248  return true;
249 }
250 
251 bool AstraDriver::getDeviceTypeCb(astra_camera::GetDeviceTypeRequest& req, astra_camera::GetDeviceTypeResponse& res)
252 {
253  res.device_type = std::string(device_->getDeviceType());
254  return true;
255 }
256 
257 bool AstraDriver::getIRGainCb(astra_camera::GetIRGainRequest& req, astra_camera::GetIRGainResponse& res)
258 {
259  res.gain = device_->getIRGain();
260  return true;
261 }
262 
263 bool AstraDriver::setIRGainCb(astra_camera::SetIRGainRequest& req, astra_camera::SetIRGainResponse& res)
264 {
265  device_->setIRGain(req.gain);
266  return true;
267 }
268 
269 bool AstraDriver::getIRExposureCb(astra_camera::GetIRExposureRequest& req, astra_camera::GetIRExposureResponse& res)
270 {
271  res.exposure = device_->getIRExposure();
272  return true;
273 }
274 
275 bool AstraDriver::setIRExposureCb(astra_camera::SetIRExposureRequest& req, astra_camera::SetIRExposureResponse& res)
276 {
277  device_->setIRExposure(req.exposure);
278  return true;
279 }
280 
281 bool AstraDriver::setLaserCb(astra_camera::SetLaserRequest& req, astra_camera::SetLaserResponse& res)
282 {
283  device_->setLaser(req.enable);
284  return true;
285 }
286 
287 bool AstraDriver::setLDPCb(astra_camera::SetLDPRequest& req, astra_camera::SetLDPResponse& res)
288 {
289  device_->setLDP(req.enable);
290  return true;
291 }
292 
293 bool AstraDriver::resetIRGainCb(astra_camera::ResetIRGainRequest& req, astra_camera::ResetIRGainResponse& res)
294 {
295  device_->setIRGain(0x8);
296  return true;
297 }
298 
299 bool AstraDriver::resetIRExposureCb(astra_camera::ResetIRExposureRequest& req, astra_camera::ResetIRExposureResponse& res)
300 {
301  device_->setIRExposure(0x419);
302  return true;
303 }
304 
305 bool AstraDriver::getCameraInfoCb(astra_camera::GetCameraInfoRequest& req, astra_camera::GetCameraInfoResponse& res)
306 {
307  res.info = convertAstraCameraInfo(device_->getCameraParams(), ros::Time::now());
308  return true;
309 }
310 
311 bool AstraDriver::setIRFloodCb(astra_camera::SetIRFloodRequest& req, astra_camera::SetIRFloodResponse& res)
312 {
313  device_->setIRFlood(req.enable);
314  return true;
315 }
316 
317 bool AstraDriver::switchIRCameraCb(astra_camera::SwitchIRCameraRequest& req, astra_camera::SwitchIRCameraResponse& res)
318 {
319  if (req.camera == "left")
320  device_->switchIRCamera(0);
321  else if (req.camera == "right")
322  device_->switchIRCamera(1);
323  else
324  ROS_ERROR("Only support left/right");
325  return true;
326 }
327 
329 {
330  if (device_->getDeviceTypeNo() == OB_STEREO_S_NO)
331  {
332  if (config.depth_mode != 13 && config.depth_mode != 14)
333  {
334  config.depth_mode = 13;
335  }
336  if (config.ir_mode != 13 && config.ir_mode != 14 && config.ir_mode != 16)
337  {
338  config.ir_mode = 13;
339  }
340  device_->switchIRCamera(0);
341  }
342  else if (device_->getDeviceTypeNo() == OB_EMBEDDED_S_NO)
343  {
344  if (config.depth_mode != 13 && config.depth_mode != 17)
345  {
346  config.depth_mode = 13;
347  }
348  if (config.ir_mode != 13 && config.ir_mode != 17)
349  {
350  config.ir_mode = 13;
351  }
352  uvc_flip_ = 1;
353  }
354  else if (device_->getDeviceTypeNo() == OB_STEREO_S_U3_NO)
355  {
356  if (config.depth_mode != 13 && config.depth_mode != 14)
357  {
358  config.depth_mode = 13;
359  }
360  if (config.ir_mode != 13 && config.ir_mode != 14)
361  {
362  config.ir_mode = 13;
363  }
364  device_->switchIRCamera(0);
365  }
366  bool stream_reset = false;
367 
368  rgb_preferred_ = config.rgb_preferred;
369 
370  if (config_init_ && old_config_.rgb_preferred != config.rgb_preferred)
371  imageConnectCb();
372 
373  depth_ir_offset_x_ = config.depth_ir_offset_x;
374  depth_ir_offset_y_ = config.depth_ir_offset_y;
375  z_offset_mm_ = config.z_offset_mm;
376  z_scaling_ = config.z_scaling;
377 
378  ir_time_offset_ = ros::Duration(config.ir_time_offset);
379  color_time_offset_ = ros::Duration(config.color_time_offset);
380  depth_time_offset_ = ros::Duration(config.depth_time_offset);
381 
382  if (lookupVideoModeFromDynConfig(config.ir_mode, ir_video_mode_)<0)
383  {
384  ROS_ERROR("Undefined IR video mode received from dynamic reconfigure");
385  exit(-1);
386  }
387 
388  if (lookupVideoModeFromDynConfig(config.color_mode, color_video_mode_)<0)
389  {
390  ROS_ERROR("Undefined color video mode received from dynamic reconfigure");
391  exit(-1);
392  }
393 
394  if (lookupVideoModeFromDynConfig(config.depth_mode, depth_video_mode_)<0)
395  {
396  ROS_ERROR("Undefined depth video mode received from dynamic reconfigure");
397  exit(-1);
398  }
399 
400  // assign pixel format
401 
405 
406  color_depth_synchronization_ = config.color_depth_synchronization;
407  depth_registration_ = config.depth_registration;
408 
409  auto_exposure_ = config.auto_exposure;
410  auto_white_balance_ = config.auto_white_balance;
411 
412  use_device_time_ = config.use_device_time;
413 
414  data_skip_ = config.data_skip+1;
415 
417 
418  config_init_ = true;
419 
420  old_config_ = config;
421 }
422 
423 void AstraDriver::setIRVideoMode(const AstraVideoMode& ir_video_mode)
424 {
425  if (device_->isIRVideoModeSupported(ir_video_mode))
426  {
427  if (ir_video_mode != device_->getIRVideoMode())
428  {
429  device_->setIRVideoMode(ir_video_mode);
430  }
431 
432  }
433  else
434  {
435  ROS_ERROR_STREAM("Unsupported IR video mode - " << ir_video_mode);
436  }
437 }
438 void AstraDriver::setColorVideoMode(const AstraVideoMode& color_video_mode)
439 {
440  if (device_->isColorVideoModeSupported(color_video_mode))
441  {
442  if (color_video_mode != device_->getColorVideoMode())
443  {
444  device_->setColorVideoMode(color_video_mode);
445  }
446  }
447  else
448  {
449  ROS_ERROR_STREAM("Unsupported color video mode - " << color_video_mode);
450  }
451 }
452 void AstraDriver::setDepthVideoMode(const AstraVideoMode& depth_video_mode)
453 {
454  if (device_->isDepthVideoModeSupported(depth_video_mode))
455  {
456  if (depth_video_mode != device_->getDepthVideoMode())
457  {
458  device_->setDepthVideoMode(depth_video_mode);
459  }
460  }
461  else
462  {
463  ROS_ERROR_STREAM("Unsupported depth video mode - " << depth_video_mode);
464  }
465 }
466 
468 {
469 
473 
475  if (device_->hasColorSensor())
476  {
478  }
480 
481  if (device_->isImageRegistrationModeSupported())
482  {
483  try
484  {
485  if (!config_init_ || (old_config_.depth_registration != depth_registration_))
486  device_->setImageRegistrationMode(depth_registration_);
487  }
488  catch (const AstraException& exception)
489  {
490  ROS_ERROR("Could not set image registration. Reason: %s", exception.what());
491  }
492  }
493 
494  try
495  {
496  if (!config_init_ || (old_config_.color_depth_synchronization != color_depth_synchronization_))
497  device_->setDepthColorSync(color_depth_synchronization_);
498  }
499  catch (const AstraException& exception)
500  {
501  ROS_ERROR("Could not set color depth synchronization. Reason: %s", exception.what());
502  }
503 
504  try
505  {
506  if (!config_init_ || (old_config_.auto_exposure != auto_exposure_))
507  device_->setAutoExposure(auto_exposure_);
508  }
509  catch (const AstraException& exception)
510  {
511  ROS_ERROR("Could not set auto exposure. Reason: %s", exception.what());
512  }
513 
514  try
515  {
516  if (!config_init_ || (old_config_.auto_white_balance != auto_white_balance_))
517  device_->setAutoWhiteBalance(auto_white_balance_);
518  }
519  catch (const AstraException& exception)
520  {
521  ROS_ERROR("Could not set auto white balance. Reason: %s", exception.what());
522  }
523 
524  device_->setUseDeviceTimer(use_device_time_);
525 
526 }
527 
529 {
530  boost::lock_guard<boost::mutex> lock(connect_mutex_);
531 
532  bool ir_started = device_->isIRStreamStarted();
533  bool color_started = device_->isColorStreamStarted();
534 
537 
539  {
540  if (ir_subscribers_)
541  ROS_ERROR("Cannot stream RGB and IR at the same time. Streaming RGB only.");
542 
543  if (ir_started)
544  {
545  ROS_INFO("Stopping IR stream.");
546  device_->stopIRStream();
547  }
548 
549  if (!color_started)
550  {
551  device_->setColorFrameCallback(boost::bind(&AstraDriver::newColorFrameCallback, this, _1));
552 
553  ROS_INFO("Starting color stream.");
554  device_->startColorStream();
555  }
556  }
558  {
559 
560  if (color_subscribers_)
561  ROS_ERROR("Cannot stream RGB and IR at the same time. Streaming IR only.");
562 
563  if (color_started)
564  {
565  ROS_INFO("Stopping color stream.");
566  device_->stopColorStream();
567  }
568 
569  if (!ir_started)
570  {
571  device_->setIRFrameCallback(boost::bind(&AstraDriver::newIRFrameCallback, this, _1));
572 
573  ROS_INFO("Starting IR stream.");
574  device_->startIRStream();
575  }
576  }
577  else
578  {
579  if (color_started)
580  {
581  ROS_INFO("Stopping color stream.");
582  device_->stopColorStream();
583  }
584  if (ir_started)
585  {
586  ROS_INFO("Stopping IR stream.");
587  device_->stopIRStream();
588  }
589  }
590 }
591 
593 {
594  boost::lock_guard<boost::mutex> lock(connect_mutex_);
595 
599 
600  bool need_depth = depth_subscribers_ || depth_raw_subscribers_;
601 
602  if (need_depth && !device_->isDepthStreamStarted())
603  {
604  device_->setDepthFrameCallback(boost::bind(&AstraDriver::newDepthFrameCallback, this, _1));
605 
606  ROS_INFO("Starting depth stream.");
607  device_->startDepthStream();
608  }
609  else if (!need_depth && device_->isDepthStreamStarted())
610  {
611  ROS_INFO("Stopping depth stream.");
612  device_->stopDepthStream();
613  }
614 }
615 
616 void AstraDriver::newIRFrameCallback(sensor_msgs::ImagePtr image)
617 {
619  {
621 
622  if (ir_subscribers_)
623  {
624  image->header.frame_id = ir_frame_id_;
625  image->header.stamp = image->header.stamp + ir_time_offset_;
626 
627  pub_ir_.publish(image, getIRCameraInfo(image->width, image->height, image->header.stamp));
628  }
629  }
630 }
631 
632 void AstraDriver::newColorFrameCallback(sensor_msgs::ImagePtr image)
633 {
635  {
637 
638  if (color_subscribers_)
639  {
640  image->header.frame_id = color_frame_id_;
641  image->header.stamp = image->header.stamp + color_time_offset_;
642 
643  pub_color_.publish(image, getColorCameraInfo(image->width, image->height, image->header.stamp));
644  }
645  }
646 }
647 
648 void AstraDriver::newDepthFrameCallback(sensor_msgs::ImagePtr image)
649 {
651  {
652 
654 
656  {
657  image->header.stamp = image->header.stamp + depth_time_offset_;
658 
659  if (z_offset_mm_ != 0)
660  {
661  uint16_t* data = reinterpret_cast<uint16_t*>(&image->data[0]);
662  for (unsigned int i = 0; i < image->width * image->height; ++i)
663  if (data[i] != 0)
664  data[i] += z_offset_mm_;
665  }
666 
667  if (fabs(z_scaling_ - 1.0) > 1e-6)
668  {
669  uint16_t* data = reinterpret_cast<uint16_t*>(&image->data[0]);
670  for (unsigned int i = 0; i < image->width * image->height; ++i)
671  if (data[i] != 0)
672  data[i] = static_cast<uint16_t>(data[i] * z_scaling_);
673  }
674 
675  sensor_msgs::CameraInfoPtr cam_info;
676 
678  {
679  image->header.frame_id = color_frame_id_;
680  } else
681  {
682  image->header.frame_id = depth_frame_id_;
683  }
684  cam_info = getDepthCameraInfo(image->width, image->height, image->header.stamp);
685 
687  {
688  pub_depth_raw_.publish(image, cam_info);
689  }
690 
691  if (depth_subscribers_ )
692  {
693  sensor_msgs::ImageConstPtr floating_point_image = rawToFloatingPointConversion(image);
694  pub_depth_.publish(floating_point_image, cam_info);
695  }
696 
697  // Projector "info" probably only useful for working with disparity images
699  {
700  pub_projector_info_.publish(getProjectorCameraInfo(image->width, image->height, image->header.stamp));
701  }
702  }
703  }
704 }
705 
706 sensor_msgs::CameraInfo AstraDriver::convertAstraCameraInfo(OBCameraParams p, ros::Time time) const
707 {
708  sensor_msgs::CameraInfo info;
709  // info.width = width;
710  // info.height = height;
711  info.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
712  info.D.resize(5, 0.0);
713  info.D[0] = p.r_k[0];
714  info.D[1] = p.r_k[1];
715  info.D[2] = p.r_k[3];
716  info.D[3] = p.r_k[4];
717  info.D[4] = p.r_k[2];
718 
719  info.K.assign(0.0);
720  info.K[0] = p.r_intr_p[0];
721  info.K[2] = p.r_intr_p[2];
722  info.K[4] = p.r_intr_p[1];
723  info.K[5] = p.r_intr_p[3];
724  info.K[8] = 1.0;
725 
726  info.R.assign(0.0);
727  for (int i = 0; i < 9; i++)
728  {
729  info.R[i] = p.r2l_r[i];
730  }
731 
732  info.P.assign(0.0);
733  info.P[0] = info.K[0];
734  info.P[2] = info.K[2];
735  info.P[3] = p.r2l_t[0];
736  info.P[5] = info.K[4];
737  info.P[6] = info.K[5];
738  info.P[7] = p.r2l_t[1];
739  info.P[10] = 1.0;
740  info.P[11] = p.r2l_t[2];
741  // Fill in header
742  info.header.stamp = time;
743  info.header.frame_id = color_frame_id_;
744  return info;
745 }
746 
747 // Methods to get calibration parameters for the various cameras
748 sensor_msgs::CameraInfoPtr AstraDriver::getDefaultCameraInfo(int width, int height, double f) const
749 {
750  sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
751 
752  info->width = width;
753  info->height = height;
754 
755  // No distortion
756  info->D.resize(5, 0.0);
757  info->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
758 
759  // Simple camera matrix: square pixels (fx = fy), principal point at center
760  info->K.assign(0.0);
761  info->K[0] = info->K[4] = f;
762  info->K[2] = (width / 2) - 0.5;
763  // Aspect ratio for the camera center on Astra (and other devices?) is 4/3
764  // This formula keeps the principal point the same in VGA and SXGA modes
765  info->K[5] = (width * (3./8.)) - 0.5;
766  info->K[8] = 1.0;
767 
768  // No separate rectified image plane, so R = I
769  info->R.assign(0.0);
770  info->R[0] = info->R[4] = info->R[8] = 1.0;
771 
772  // Then P=K(I|0) = (K|0)
773  info->P.assign(0.0);
774  info->P[0] = info->P[5] = f; // fx, fy
775  info->P[2] = info->K[2]; // cx
776  info->P[6] = info->K[5]; // cy
777  info->P[10] = 1.0;
778 
779  return info;
780 }
781 
783 sensor_msgs::CameraInfoPtr AstraDriver::getColorCameraInfo(int width, int height, ros::Time time) const
784 {
785  sensor_msgs::CameraInfoPtr info;
786 
787  if (color_info_manager_->isCalibrated())
788  {
789  info = boost::make_shared<sensor_msgs::CameraInfo>(color_info_manager_->getCameraInfo());
790  if ( info->width != width )
791  {
792  // Use uncalibrated values
793  ROS_WARN_ONCE("Image resolution doesn't match calibration of the RGB camera. Using default parameters.");
794  info = getDefaultCameraInfo(width, height, device_->getColorFocalLength(height));
795  }
796  }
797  else
798  {
799  // If uncalibrated, fill in default values
800  if (device_->isCameraParamsValid())
801  {
802  sensor_msgs::CameraInfo cinfo = convertAstraCameraInfo(device_->getCameraParams(), time);
803  info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
804  info->D.resize(5, 0.0);
805  info->K.assign(0.0);
806  info->R.assign(0.0);
807  info->P.assign(0.0);
808  info->distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
809  info->width = width;
810  info->height = height;
811 
812  for (int i = 0; i < 9; i++)
813  {
814  info->K[i] = cinfo.K[i];
815  info->R[i] = cinfo.R[i];
816  }
817 
818  for (int i = 0; i < 12; i++)
819  {
820  info->P[i] = cinfo.P[i];
821  }
822 /*02112020 color camera param change according to resolution */
823  double scaling = (double)width / 640;
824  info->K[0] *= scaling; // fx
825  info->K[2] *= scaling; // cx
826  info->K[4] *= scaling; // fy
827  info->K[5] *= scaling; // cy
828  info->P[0] *= scaling; // fx
829  info->P[2] *= scaling; // cx
830  info->P[5] *= scaling; // fy
831  info->P[6] *= scaling; // cy
832 /* 02112020 end*/
833 
834  }
835  else
836  {
837  info = getDefaultCameraInfo(width, height, device_->getColorFocalLength(height));
838  }
839  }
840 
841  // Fill in header
842  info->header.stamp = time;
843  info->header.frame_id = color_frame_id_;
844 
845  return info;
846 }
847 
848 
849 sensor_msgs::CameraInfoPtr AstraDriver::getIRCameraInfo(int width, int height, ros::Time time) const
850 {
851  sensor_msgs::CameraInfoPtr info;
852 
853  if (ir_info_manager_->isCalibrated())
854  {
855  info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
856  if ( info->width != width )
857  {
858  // Use uncalibrated values
859  ROS_WARN_ONCE("Image resolution doesn't match calibration of the IR camera. Using default parameters.");
860  info = getDefaultCameraInfo(width, height, device_->getIRFocalLength(height));
861  }
862  }
863  else
864  {
865  // If uncalibrated, fill in default values
866  info = getDefaultCameraInfo(width, height, device_->getDepthFocalLength(height));
867 
868  if (device_->isCameraParamsValid())
869  {
870  OBCameraParams p = device_->getCameraParams();
871  info->D.resize(5, 0.0);
872  // info->D[0] = p.l_k[0];
873  // info->D[1] = p.l_k[1];
874  // info->D[2] = p.l_k[3];
875  // info->D[3] = p.l_k[4];
876  // info->D[4] = p.l_k[2];
877 
878  info->K.assign(0.0);
879  info->K[0] = p.l_intr_p[0];
880  info->K[2] = p.l_intr_p[2];
881  info->K[4] = p.l_intr_p[1];
882  info->K[5] = p.l_intr_p[3];
883  info->K[8] = 1.0;
884 
885  info->R.assign(0.0);
886  info->R[0] = 1;
887  info->R[4] = 1;
888  info->R[8] = 1;
889 
890  info->P.assign(0.0);
891  info->P[0] = info->K[0];
892  info->P[2] = info->K[2];
893  info->P[5] = info->K[4];
894  info->P[6] = info->K[5];
895  info->P[10] = 1.0;
896 /* 02122020 Scale IR Params */
897  double scaling = (double)width / 640;
898  info->K[0] *= scaling; // fx
899  info->K[2] *= scaling; // cx
900  info->K[4] *= scaling; // fy
901  info->K[5] *= scaling; // cy
902  info->P[0] *= scaling; // fx
903  info->P[2] *= scaling; // cx
904  info->P[5] *= scaling; // fy
905  info->P[6] *= scaling; // cy
906 /* 02122020 end */
907 
908  }
909  }
910 
911  // Fill in header
912  info->header.stamp = time;
913  info->header.frame_id = depth_frame_id_;
914 
915  return info;
916 }
917 
918 sensor_msgs::CameraInfoPtr AstraDriver::getDepthCameraInfo(int width, int height, ros::Time time) const
919 {
920  // The depth image has essentially the same intrinsics as the IR image, BUT the
921  // principal point is offset by half the size of the hardware correlation window
922  // (probably 9x9 or 9x7 in 640x480 mode). See http://www.ros.org/wiki/kinect_calibration/technical
923  double scaling = (double)width / 640;
924  sensor_msgs::CameraInfoPtr info = getIRCameraInfo(width, height, time);
925  info->K[2] -= depth_ir_offset_x_ * scaling;
926  info->K[5] -= depth_ir_offset_y_ * scaling;
927  info->P[2] -= depth_ir_offset_x_ * scaling;
928  info->P[6] -= depth_ir_offset_y_ * scaling;
929 
931  return info;
932 }
933 
934 sensor_msgs::CameraInfoPtr AstraDriver::getProjectorCameraInfo(int width, int height, ros::Time time) const
935 {
936  // The projector info is simply the depth info with the baseline encoded in the P matrix.
937  // It's only purpose is to be the "right" camera info to the depth camera's "left" for
938  // processing disparity images.
939  sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(width, height, time);
940  // Tx = -baseline * fx
941  info->P[3] = -device_->getBaseline() * info->P[0];
942  return info;
943 }
944 
946 {
947  if (!pnh_.getParam("device_id", device_id_))
948  {
949  ROS_WARN ("~device_id is not set! Using first device.");
950  device_id_ = "#1";
951  }
952 
953  // Camera TF frames
954  pnh_.param("ir_frame_id", ir_frame_id_, std::string("/openni_ir_optical_frame"));
955  pnh_.param("rgb_frame_id", color_frame_id_, std::string("/openni_rgb_optical_frame"));
956  pnh_.param("depth_frame_id", depth_frame_id_, std::string("/openni_depth_optical_frame"));
957 
958  ROS_DEBUG("ir_frame_id = '%s' ", ir_frame_id_.c_str());
959  ROS_DEBUG("rgb_frame_id = '%s' ", color_frame_id_.c_str());
960  ROS_DEBUG("depth_frame_id = '%s' ", depth_frame_id_.c_str());
961 
962  pnh_.param("rgb_camera_info_url", color_info_url_, std::string());
963  pnh_.param("depth_camera_info_url", ir_info_url_, std::string());
964 
965 }
966 
967 std::string AstraDriver::resolveDeviceURI(const std::string& device_id)
968 {
969  // retrieve available device URIs, they look like this: "1d27/0601@1/5"
970  // which is <vendor ID>/<product ID>@<bus number>/<device number>
971  boost::shared_ptr<std::vector<std::string> > available_device_URIs =
972  device_manager_->getConnectedDeviceURIs();
973 
974  //for tes
975  #if 0
976  for (size_t i = 0; i < available_device_URIs->size(); ++i)
977  {
978  std::string s = (*available_device_URIs)[i];
979  ROS_WARN("------------id %d, available_device_uri is %s-----------", i, s.c_str());
980  }
981  #endif
982  //end
983  // look for '#<number>' format
984  if (device_id.size() > 1 && device_id[0] == '#')
985  {
986  std::istringstream device_number_str(device_id.substr(1));
987  int device_number;
988  device_number_str >> device_number;
989  int device_index = device_number - 1; // #1 refers to first device
990  if (device_index >= available_device_URIs->size() || device_index < 0)
991  {
993  "Invalid device number %i, there are %zu devices connected.",
994  device_number, available_device_URIs->size());
995  }
996  else
997  {
998  return available_device_URIs->at(device_index);
999  }
1000  }
1001  // look for '<bus>@<number>' format
1002  // <bus> is usb bus id, typically start at 1
1003  // <number> is the device number, for consistency with astra_camera, these start at 1
1004  // although 0 specifies "any device on this bus"
1005  else if (device_id.size() > 1 && device_id.find('@') != std::string::npos && device_id.find('/') == std::string::npos)
1006  {
1007  // get index of @ character
1008  size_t index = device_id.find('@');
1009  if (index <= 0)
1010  {
1012  "%s is not a valid device URI, you must give the bus number before the @.",
1013  device_id.c_str());
1014  }
1015  if (index >= device_id.size() - 1)
1016  {
1018  "%s is not a valid device URI, you must give a number after the @, specify 0 for first device",
1019  device_id.c_str());
1020  }
1021 
1022  // pull out device number on bus
1023  std::istringstream device_number_str(device_id.substr(index+1));
1024  int device_number;
1025  device_number_str >> device_number;
1026 
1027  // reorder to @<bus>
1028  std::string bus = device_id.substr(0, index);
1029  bus.insert(0, "@");
1030 
1031  for (size_t i = 0; i < available_device_URIs->size(); ++i)
1032  {
1033  std::string s = (*available_device_URIs)[i];
1034  if (s.find(bus) != std::string::npos)
1035  {
1036  // this matches our bus, check device number
1037  --device_number;
1038  if (device_number <= 0)
1039  return s;
1040  }
1041  }
1042 
1043  THROW_OPENNI_EXCEPTION("Device not found %s", device_id.c_str());
1044  }
1045  else
1046  {
1047  // check if the device id given matches a serial number of a connected device
1048  for(std::vector<std::string>::const_iterator it = available_device_URIs->begin();
1049  it != available_device_URIs->end(); ++it)
1050  {
1051  #if 0
1052  try
1053  {
1054  std::string serial = device_manager_->getSerial(*it);
1055  if (serial.size() > 0 && device_id == serial)
1056  return *it;
1057  }
1058  #else
1059  try
1060  {
1061  std::set<std::string>::iterator iter;
1062  if((iter = alreadyOpen.find(*it)) == alreadyOpen.end())
1063  {
1064  // ROS_WARN("------------seraial num it is %s, device_id is %s -----------", (*it).c_str(), device_id_.c_str());
1065  std::string serial = device_manager_->getSerial(*it);
1066  if (serial.size() > 0 && device_id == serial)
1067  {
1068  alreadyOpen.insert(*it);
1069  return *it;
1070  }
1071  }
1072  }
1073  #endif
1074  catch (const AstraException& exception)
1075  {
1076  ROS_WARN("Could not query serial number of device \"%s\":", exception.what());
1077  }
1078  }
1079 
1080  // everything else is treated as part of the device_URI
1081  bool match_found = false;
1082  std::string matched_uri;
1083  for (size_t i = 0; i < available_device_URIs->size(); ++i)
1084  {
1085  std::string s = (*available_device_URIs)[i];
1086  if (s.find(device_id) != std::string::npos)
1087  {
1088  if (!match_found)
1089  {
1090  matched_uri = s;
1091  match_found = true;
1092  }
1093  else
1094  {
1095  // more than one match
1096  THROW_OPENNI_EXCEPTION("Two devices match the given device id '%s': %s and %s.", device_id.c_str(), matched_uri.c_str(), s.c_str());
1097  }
1098  }
1099  }
1100  return matched_uri;
1101  }
1102 
1103  return "INVALID";
1104 }
1105 
1107 {
1108  while (ros::ok() && !device_)
1109  {
1110  try
1111  {
1112  std::string device_URI = resolveDeviceURI(device_id_);
1113  #if 0
1114  if( device_URI == "" )
1115  {
1116  boost::this_thread::sleep(boost::posix_time::milliseconds(500));
1117  continue;
1118  }
1119  #endif
1120  device_ = device_manager_->getDevice(device_URI);
1121  }
1122  catch (const AstraException& exception)
1123  {
1124  if (!device_)
1125  {
1126  ROS_INFO("No matching device found.... waiting for devices. Reason: %s", exception.what());
1127  boost::this_thread::sleep(boost::posix_time::seconds(3));
1128  continue;
1129  }
1130  else
1131  {
1132  ROS_ERROR("Could not retrieve device. Reason: %s", exception.what());
1133  exit(-1);
1134  }
1135  }
1136  }
1137 
1138  while (ros::ok() && !device_->isValid())
1139  {
1140  ROS_DEBUG("Waiting for device initialization..");
1141  boost::this_thread::sleep(boost::posix_time::milliseconds(100));
1142  }
1143 
1144 }
1145 
1147 {
1148  /*
1149  * # Video modes defined by dynamic reconfigure:
1150 output_mode_enum = gen.enum([ gen.const( "SXGA_30Hz", int_t, 1, "1280x1024@30Hz"),
1151  gen.const( "SXGA_15Hz", int_t, 2, "1280x1024@15Hz"),
1152  gen.const( "XGA_30Hz", int_t, 3, "1280x720@30Hz"),
1153  gen.const( "XGA_15Hz", int_t, 4, "1280x720@15Hz"),
1154  gen.const( "VGA_30Hz", int_t, 5, "640x480@30Hz"),
1155  gen.const( "VGA_25Hz", int_t, 6, "640x480@25Hz"),
1156  gen.const( "QVGA_25Hz", int_t, 7, "320x240@25Hz"),
1157  gen.const( "QVGA_30Hz", int_t, 8, "320x240@30Hz"),
1158  gen.const( "QVGA_60Hz", int_t, 9, "320x240@60Hz"),
1159  gen.const( "QQVGA_25Hz", int_t, 10, "160x120@25Hz"),
1160  gen.const( "QQVGA_30Hz", int_t, 11, "160x120@30Hz"),
1161  gen.const( "QQVGA_60Hz", int_t, 12, "160x120@60Hz"),
1162  gen.const("640400_30Hz", int_t, 13, "640x400@30Hz"),
1163  gen.const("320200_30Hz", int_t, 14, "320x200@30Hz"),
1164  gen.const("1280800_7Hz", int_t, 15, "1280x800@7Hz"),
1165  gen.const("1280800_30Hz", int_t, 16, "1280x800@30Hz"),
1166  gen.const("640400_60Hz", int_t, 17, "640x400@60Hz")],
1167  "output mode")
1168  */
1169 
1170  video_modes_lookup_.clear();
1171 
1172  AstraVideoMode video_mode;
1173 
1174  // SXGA_30Hz
1175  video_mode.x_resolution_ = 1280;
1176  video_mode.y_resolution_ = 1024;
1177  video_mode.frame_rate_ = 30;
1178 
1179  video_modes_lookup_[1] = video_mode;
1180 
1181  // SXGA_15Hz
1182  video_mode.x_resolution_ = 1280;
1183  video_mode.y_resolution_ = 1024;
1184  video_mode.frame_rate_ = 15;
1185 
1186  video_modes_lookup_[2] = video_mode;
1187 
1188  // XGA_30Hz
1189  video_mode.x_resolution_ = 1280;
1190  video_mode.y_resolution_ = 720;
1191  video_mode.frame_rate_ = 30;
1192 
1193  video_modes_lookup_[3] = video_mode;
1194 
1195  // XGA_15Hz
1196  video_mode.x_resolution_ = 1280;
1197  video_mode.y_resolution_ = 720;
1198  video_mode.frame_rate_ = 15;
1199 
1200  video_modes_lookup_[4] = video_mode;
1201 
1202  // VGA_30Hz
1203  video_mode.x_resolution_ = 640;
1204  video_mode.y_resolution_ = 480;
1205  video_mode.frame_rate_ = 30;
1206 
1207  video_modes_lookup_[5] = video_mode;
1208 
1209  // VGA_25Hz
1210  video_mode.x_resolution_ = 640;
1211  video_mode.y_resolution_ = 480;
1212  video_mode.frame_rate_ = 25;
1213 
1214  video_modes_lookup_[6] = video_mode;
1215 
1216  // QVGA_25Hz
1217  video_mode.x_resolution_ = 320;
1218  video_mode.y_resolution_ = 240;
1219  video_mode.frame_rate_ = 25;
1220 
1221  video_modes_lookup_[7] = video_mode;
1222 
1223  // QVGA_30Hz
1224  video_mode.x_resolution_ = 320;
1225  video_mode.y_resolution_ = 240;
1226  video_mode.frame_rate_ = 30;
1227 
1228  video_modes_lookup_[8] = video_mode;
1229 
1230  // QVGA_60Hz
1231  video_mode.x_resolution_ = 320;
1232  video_mode.y_resolution_ = 240;
1233  video_mode.frame_rate_ = 60;
1234 
1235  video_modes_lookup_[9] = video_mode;
1236 
1237  // QQVGA_25Hz
1238  video_mode.x_resolution_ = 160;
1239  video_mode.y_resolution_ = 120;
1240  video_mode.frame_rate_ = 25;
1241 
1242  video_modes_lookup_[10] = video_mode;
1243 
1244  // QQVGA_30Hz
1245  video_mode.x_resolution_ = 160;
1246  video_mode.y_resolution_ = 120;
1247  video_mode.frame_rate_ = 30;
1248 
1249  video_modes_lookup_[11] = video_mode;
1250 
1251  // QQVGA_60Hz
1252  video_mode.x_resolution_ = 160;
1253  video_mode.y_resolution_ = 120;
1254  video_mode.frame_rate_ = 60;
1255 
1256  video_modes_lookup_[12] = video_mode;
1257 
1258  // 640*400_30Hz
1259  video_mode.x_resolution_ = 640;
1260  video_mode.y_resolution_ = 400;
1261  video_mode.frame_rate_ = 30;
1262 
1263  video_modes_lookup_[13] = video_mode;
1264 
1265  // 320*200_30Hz
1266  video_mode.x_resolution_ = 320;
1267  video_mode.y_resolution_ = 200;
1268  video_mode.frame_rate_ = 30;
1269 
1270  video_modes_lookup_[14] = video_mode;
1271 
1272  // 1280*800_7Hz
1273  video_mode.x_resolution_ = 1280;
1274  video_mode.y_resolution_ = 800;
1275  video_mode.frame_rate_ = 7;
1276 
1277  video_modes_lookup_[15] = video_mode;
1278 
1279  // 1280*800_30Hz
1280  video_mode.x_resolution_ = 1280;
1281  video_mode.y_resolution_ = 800;
1282  video_mode.frame_rate_ = 30;
1283 
1284  video_modes_lookup_[16] = video_mode;
1285 
1286  // 640*400_60Hz
1287  video_mode.x_resolution_ = 640;
1288  video_mode.y_resolution_ = 400;
1289  video_mode.frame_rate_ = 60;
1290 
1291  video_modes_lookup_[17] = video_mode;
1292 }
1293 
1295 {
1296  int ret = -1;
1297 
1298  std::map<int, AstraVideoMode>::const_iterator it;
1299 
1300  it = video_modes_lookup_.find(mode_nr);
1301 
1302  if (it!=video_modes_lookup_.end())
1303  {
1304  video_mode = it->second;
1305  ret = 0;
1306  }
1307 
1308  return ret;
1309 }
1310 
1311 sensor_msgs::ImageConstPtr AstraDriver::rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
1312 {
1313  static const float bad_point = std::numeric_limits<float>::quiet_NaN ();
1314 
1315  sensor_msgs::ImagePtr new_image = boost::make_shared<sensor_msgs::Image>();
1316 
1317  new_image->header = raw_image->header;
1318  new_image->width = raw_image->width;
1319  new_image->height = raw_image->height;
1320  new_image->is_bigendian = 0;
1321  new_image->encoding = sensor_msgs::image_encodings::TYPE_32FC1;
1322  new_image->step = sizeof(float)*raw_image->width;
1323 
1324  std::size_t data_size = new_image->width*new_image->height;
1325  new_image->data.resize(data_size*sizeof(float));
1326 
1327  const unsigned short* in_ptr = reinterpret_cast<const unsigned short*>(&raw_image->data[0]);
1328  float* out_ptr = reinterpret_cast<float*>(&new_image->data[0]);
1329 
1330  for (std::size_t i = 0; i<data_size; ++i, ++in_ptr, ++out_ptr)
1331  {
1332  if (*in_ptr==0 || *in_ptr==0x7FF)
1333  {
1334  *out_ptr = bad_point;
1335  } else
1336  {
1337  *out_ptr = static_cast<float>(*in_ptr)/1000.0f;
1338  }
1339  }
1340 
1341  return new_image;
1342 }
1343 
1344 }
ros::ServiceServer set_ir_exposure_server
Definition: astra_driver.h:150
void setDepthVideoMode(const AstraVideoMode &depth_video_mode)
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
std::string resolveDeviceURI(const std::string &device_id)
ros::ServiceServer get_camera_info
get_serial server
Definition: astra_driver.h:144
bool getIRGainCb(astra_camera::GetIRGainRequest &req, astra_camera::GetIRGainResponse &res)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
General exception class.
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
Definition: astra_driver.h:159
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle & nh_
Definition: astra_driver.h:135
float r2l_r[9]
Definition: OniCTypes.h:89
bool setIRExposureCb(astra_camera::SetIRExposureRequest &req, astra_camera::SetIRExposureResponse &res)
image_transport::CameraPublisher pub_depth_raw_
Definition: astra_driver.h:167
image_transport::CameraPublisher pub_depth_
Definition: astra_driver.h:166
ros::ServiceServer set_laser_server
Definition: astra_driver.h:152
unsigned short uint16_t
image_transport::CameraPublisher pub_color_
Definition: astra_driver.h:165
float l_intr_p[4]
Definition: OniCTypes.h:87
uint32_t getNumSubscribers() const
XmlRpcServer s
ros::ServiceServer reset_ir_gain_server
Definition: astra_driver.h:154
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
ros::Duration ir_time_offset_
Definition: astra_driver.h:195
AstraVideoMode color_video_mode_
Definition: astra_driver.h:175
virtual const char * what() const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
ros::NodeHandle & pnh_
Definition: astra_driver.h:136
#define THROW_OPENNI_EXCEPTION(format,...)
ros::ServiceServer get_serial_server
Definition: astra_driver.h:145
#define ROS_WARN(...)
ros::Duration depth_time_offset_
Definition: astra_driver.h:197
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
ros::Publisher pub_projector_info_
Definition: astra_driver.h:169
bool getDeviceTypeCb(astra_camera::GetDeviceTypeRequest &req, astra_camera::GetDeviceTypeResponse &res)
bool getCameraInfoCb(astra_camera::GetCameraInfoRequest &req, astra_camera::GetCameraInfoResponse &res)
int lookupVideoModeFromDynConfig(int mode_nr, AstraVideoMode &video_mode)
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
Definition: astra_driver.h:172
boost::shared_ptr< AstraDevice > device_
Definition: astra_driver.h:139
bool getIRExposureCb(astra_camera::GetIRExposureRequest &req, astra_camera::GetIRExposureResponse &res)
bool setIRGainCb(astra_camera::SetIRGainRequest &req, astra_camera::SetIRGainResponse &res)
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
void newColorFrameCallback(sensor_msgs::ImagePtr image)
#define ROS_WARN_ONCE(...)
AstraVideoMode depth_video_mode_
Definition: astra_driver.h:176
sensor_msgs::CameraInfo convertAstraCameraInfo(OBCameraParams p, ros::Time time) const
#define ROS_INFO(...)
float r_k[5]
Definition: OniCTypes.h:92
bool param(const std::string &param_name, T &param_val, const T &default_val) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
Definition: astra_driver.h:172
const std::string TYPE_32FC1
void newIRFrameCallback(sensor_msgs::ImagePtr image)
float r2l_t[3]
Definition: OniCTypes.h:90
ros::Duration color_time_offset_
Definition: astra_driver.h:196
ROSCPP_DECL bool ok()
ros::ServiceServer set_ir_gain_server
Definition: astra_driver.h:148
float r_intr_p[4]
Definition: OniCTypes.h:88
void configCb(Config &config, uint32_t level)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: astra_driver.h:83
void setColorVideoMode(const AstraVideoMode &color_video_mode)
ros::ServiceServer set_ir_flood_server
Definition: astra_driver.h:151
ros::ServiceServer get_device_type_server
Definition: astra_driver.h:146
void setIRVideoMode(const AstraVideoMode &ir_video_mode)
ros::ServiceServer get_ir_exposure_server
Definition: astra_driver.h:149
std::set< std::string > alreadyOpen
Definition: astra_driver.h:162
uint32_t getNumSubscribers() const
std::map< int, AstraVideoMode > video_modes_lookup_
Definition: astra_driver.h:187
bool getParam(const std::string &key, std::string &s) const
ros::ServiceServer switch_ir_camera
Definition: astra_driver.h:156
astra_camera::AstraConfig Config
Definition: astra_driver.h:82
ros::ServiceServer set_ldp_server
Definition: astra_driver.h:153
ros::ServiceServer get_ir_gain_server
Definition: astra_driver.h:147
unsigned int uint32_t
bool setLDPCb(astra_camera::SetLDPRequest &req, astra_camera::SetLDPResponse &res)
AstraDriver(ros::NodeHandle &n, ros::NodeHandle &pnh)
bool setIRFloodCb(astra_camera::SetIRFloodRequest &req, astra_camera::SetIRFloodResponse &res)
static Time now()
bool resetIRGainCb(astra_camera::ResetIRGainRequest &req, astra_camera::ResetIRGainResponse &res)
bool getSerialCb(astra_camera::GetSerialRequest &req, astra_camera::GetSerialResponse &res)
image_transport::CameraPublisher pub_ir_
Definition: astra_driver.h:168
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
bool setLaserCb(astra_camera::SetLaserRequest &req, astra_camera::SetLaserResponse &res)
#define ROS_ERROR_STREAM(args)
bool resetIRExposureCb(astra_camera::ResetIRExposureRequest &req, astra_camera::ResetIRExposureResponse &res)
ros::ServiceServer reset_ir_exposure_server
Definition: astra_driver.h:155
#define ROS_ERROR(...)
AstraVideoMode ir_video_mode_
Definition: astra_driver.h:174
boost::shared_ptr< AstraDeviceManager > device_manager_
Definition: astra_driver.h:138
bool switchIRCameraCb(astra_camera::SwitchIRCameraRequest &req, astra_camera::SwitchIRCameraResponse &res)
#define ROS_DEBUG(...)


astra_camera
Author(s): Tim Liu
autogenerated on Wed Dec 16 2020 03:54:34