reconfigure.cpp
Go to the documentation of this file.
1 
35 
36 using namespace crl::multisense;
37 
38 namespace multisense_ros {
39 
40 Reconfigure::Reconfigure(Channel* driver,
41  std::function<void (crl::multisense::image::Config)> resolutionChangeCallback,
42  std::function<void (BorderClip, double)> borderClipChangeCallback,
43  std::function<void (double)> maxPointCloudRangeCallback,
44  std::function<void (crl::multisense::system::ExternalCalibration)> extrinsicsCallback,
45  std::function<void (ground_surface_utilities::SplineDrawParameters)> groundSurfaceSplineDrawParametersCallback):
46  driver_(driver),
47  resolution_change_callback_(resolutionChangeCallback),
48  device_nh_(""),
49  imu_samples_per_message_(0),
50  lighting_supported_(false),
51  motor_supported_(false),
52  crop_mode_changed_(false),
53  ptp_supported_(false),
54  roi_supported_(false),
55  aux_supported_(false),
56  reconfigure_external_calibration_supported_(false),
57  border_clip_type_(BorderClip::NONE),
58  border_clip_value_(0.0),
59  border_clip_change_callback_(borderClipChangeCallback),
60  max_point_cloud_range_callback_(maxPointCloudRangeCallback),
61  extrinsics_callback_(extrinsicsCallback),
62  spline_draw_parameters_callback_(groundSurfaceSplineDrawParametersCallback)
63 {
64  system::DeviceInfo deviceInfo;
65  system::VersionInfo versionInfo;
66  std::vector<system::DeviceMode> deviceModes;
67 
68  //
69  // Query device and version information from sensor
70 
71  Status status = driver_->getVersionInfo(versionInfo);
72  if (Status_Ok != status) {
73  ROS_ERROR("Reconfigure: failed to query version info: %s",
74  Channel::statusString(status));
75  return;
76  }
77 
78  status = driver_->getDeviceInfo(deviceInfo);
79  if (Status_Ok != status) {
80  ROS_ERROR("Reconfigure: failed to query device info: %s",
81  Channel::statusString(status));
82  return;
83  }
84 
85  status = driver_->getDeviceModes(deviceModes);
86  if (Status_Ok != status) {
87  ROS_ERROR("Reconfigure: failed to query device modes: %s",
88  Channel::statusString(status));
89  return;
90  }
91 
92  const bool ground_surface_supported =
93  std::any_of(deviceModes.begin(), deviceModes.end(), [](const auto &mode) {
94  return (mode.supportedDataSources & Source_Ground_Surface_Spline_Data) &&
95  (mode.supportedDataSources & Source_Ground_Surface_Class_Image); });
96 
97  if (deviceInfo.lightingType != 0 || system::DeviceInfo::HARDWARE_REV_MULTISENSE_KS21 == deviceInfo.hardwareRevision)
98  {
99  lighting_supported_ = true;
100  }
101  if (deviceInfo.motorType != 0)
102  {
103  motor_supported_ = true;
104  }
105  if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_C6S2_S27 == deviceInfo.hardwareRevision ||
106  system::DeviceInfo::HARDWARE_REV_MULTISENSE_S30 == deviceInfo.hardwareRevision ||
107  system::DeviceInfo::HARDWARE_REV_MULTISENSE_KS21 == deviceInfo.hardwareRevision ||
108  system::DeviceInfo::HARDWARE_REV_MULTISENSE_REMOTE_HEAD_VPB == deviceInfo.hardwareRevision ||
109  system::DeviceInfo::HARDWARE_REV_MULTISENSE_REMOTE_HEAD_STEREO == deviceInfo.hardwareRevision ||
110  system::DeviceInfo::HARDWARE_REV_MULTISENSE_REMOTE_HEAD_MONOCAM == deviceInfo.hardwareRevision)
111  {
112  ptp_supported_ = true;
113  }
114 
115  if (versionInfo.sensorFirmwareVersion >= 0x0403) {
116  roi_supported_ = true;
117  }
118 
119  if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_C6S2_S27 == deviceInfo.hardwareRevision ||
120  system::DeviceInfo::HARDWARE_REV_MULTISENSE_S30 == deviceInfo.hardwareRevision)
121  {
122  if (versionInfo.sensorFirmwareVersion >= 0x0600) {
123  aux_supported_ = true;
124  }
125  else
126  {
127  aux_supported_ = false;
128  ROS_WARN("Reconfigure: MultiSense firmware version does not support the updated aux camera exposure controls. "
129  "The ROS driver will work normally, but you will have limited control over aux camera exposure parameters. "
130  "Please use the 2eae444 has of multisene_ros or contact support@carnegierobotics.com for "
131  "a updated firmware version greater than 6.0 to enable aux camera exposure controls.");
132  }
133  }
134 
135  if (versionInfo.sensorFirmwareVersion >= 0x0513) {
137  }
138 
139  //
140  // Launch the correct reconfigure server for this device configuration.
141 
142  if (system::DeviceInfo::HARDWARE_REV_BCAM == deviceInfo.hardwareRevision) {
143 
145  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::bcam_imx104Config> > (
146  new dynamic_reconfigure::Server<multisense_ros::bcam_imx104Config>(device_nh_));
147  server_bcam_imx104_->setCallback(std::bind(&Reconfigure::callback_bcam_imx104, this,
148  std::placeholders::_1, std::placeholders::_2));
149 
150  } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_ST21 == deviceInfo.hardwareRevision) {
151 
153  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::st21_sgm_vga_imuConfig> > (
154  new dynamic_reconfigure::Server<multisense_ros::st21_sgm_vga_imuConfig>(device_nh_));
155  server_st21_vga_->setCallback(std::bind(&Reconfigure::callback_st21_vga, this,
156  std::placeholders::_1, std::placeholders::_2));
157 
158  } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_M == deviceInfo.hardwareRevision) {
159 
160  switch(deviceInfo.imagerType) {
161  case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
162  case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
163 
165  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv2000Config> > (
166  new dynamic_reconfigure::Server<multisense_ros::mono_cmv2000Config>(device_nh_));
167  server_mono_cmv2000_->setCallback(std::bind(&Reconfigure::callback_mono_cmv2000, this,
168  std::placeholders::_1, std::placeholders::_2));
169 
170  break;
171  case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
172  case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
173 
175  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv4000Config> > (
176  new dynamic_reconfigure::Server<multisense_ros::mono_cmv4000Config>(device_nh_));
177  server_mono_cmv4000_->setCallback(std::bind(&Reconfigure::callback_mono_cmv4000, this,
178  std::placeholders::_1, std::placeholders::_2));
179 
180  break;
181  }
182  } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_C6S2_S27 == deviceInfo.hardwareRevision ||
183  system::DeviceInfo::HARDWARE_REV_MULTISENSE_S30 == deviceInfo.hardwareRevision) {
184 
185  if (ground_surface_supported) {
187  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234_ground_surfaceConfig> > (
188  new dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234_ground_surfaceConfig>(device_nh_));
190  std::placeholders::_1, std::placeholders::_2));
191  } else {
193  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config> > (
194  new dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config>(device_nh_));
195  server_s27_AR0234_->setCallback(std::bind(&Reconfigure::callback_s27_AR0234, this,
196  std::placeholders::_1, std::placeholders::_2));
197  }
198  } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_KS21 == deviceInfo.hardwareRevision) {
199 
200  if (ground_surface_supported) {
202  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::ks21_sgm_AR0234_ground_surfaceConfig> > (
203  new dynamic_reconfigure::Server<multisense_ros::ks21_sgm_AR0234_ground_surfaceConfig>(device_nh_));
205  std::placeholders::_1, std::placeholders::_2));
206  } else {
208  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::ks21_sgm_AR0234Config> > (
209  new dynamic_reconfigure::Server<multisense_ros::ks21_sgm_AR0234Config>(device_nh_));
210  server_ks21_sgm_AR0234_->setCallback(std::bind(&Reconfigure::callback_ks21_AR0234, this,
211  std::placeholders::_1, std::placeholders::_2));
212  }
213  } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_REMOTE_HEAD_VPB == deviceInfo.hardwareRevision) {
215  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::remote_head_vpbConfig > > (
216  new dynamic_reconfigure::Server<multisense_ros::remote_head_vpbConfig>(device_nh_));
218  std::placeholders::_1, std::placeholders::_2));
219  } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_REMOTE_HEAD_STEREO == deviceInfo.hardwareRevision) {
220  if (ground_surface_supported) {
222  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::remote_head_sgm_AR0234_ground_surfaceConfig > > (
223  new dynamic_reconfigure::Server<multisense_ros::remote_head_sgm_AR0234_ground_surfaceConfig>(device_nh_));
225  std::placeholders::_1, std::placeholders::_2));
226  } else {
228  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::remote_head_sgm_AR0234Config > > (
229  new dynamic_reconfigure::Server<multisense_ros::remote_head_sgm_AR0234Config>(device_nh_));
231  std::placeholders::_1, std::placeholders::_2));
232  }
233  } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_REMOTE_HEAD_MONOCAM == deviceInfo.hardwareRevision) {
235  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::remote_head_monocam_AR0234Config > > (
236  new dynamic_reconfigure::Server<multisense_ros::remote_head_monocam_AR0234Config>(device_nh_));
238  std::placeholders::_1, std::placeholders::_2));
239  } else if (versionInfo.sensorFirmwareVersion <= 0x0202) {
240 
241  switch(deviceInfo.imagerType) {
242  case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
243  case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
244 
246  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000Config> > (
247  new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000Config>(device_nh_));
248  server_sl_bm_cmv2000_->setCallback(std::bind(&Reconfigure::callback_sl_bm_cmv2000, this,
249  std::placeholders::_1, std::placeholders::_2));
250 
251  break;
252  case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
253  case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
254 
256  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000Config> > (
257  new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000Config>(device_nh_));
258  server_sl_bm_cmv4000_->setCallback(std::bind(&Reconfigure::callback_sl_bm_cmv4000, this,
259  std::placeholders::_1, std::placeholders::_2));
260 
261  break;
262  default:
263 
264  ROS_ERROR("Reconfigure: unsupported imager type \"%d\"", deviceInfo.imagerType);
265  return;
266  }
267 
268  } else if (versionInfo.sensorFirmwareVersion < 0x0300) {
269 
270  switch(deviceInfo.imagerType) {
271  case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
272  case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
273 
275  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000_imuConfig> > (
276  new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000_imuConfig>(device_nh_));
278  std::placeholders::_1, std::placeholders::_2));
279 
280  break;
281  case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
282  case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
283 
285  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000_imuConfig> > (
286  new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000_imuConfig>(device_nh_));
288  std::placeholders::_1, std::placeholders::_2));
289 
290  break;
291  default:
292 
293  ROS_ERROR("Reconfigure: unsupported imager type \"%d\"", deviceInfo.imagerType);
294  return;
295  }
296 
297  } else {
298 
299  switch(deviceInfo.imagerType) {
300  case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
301  case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
302 
304  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv2000_imuConfig> > (
305  new dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv2000_imuConfig>(device_nh_));
307  std::placeholders::_1, std::placeholders::_2));
308 
309  break;
310  case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
311  case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
312 
314  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv4000_imuConfig> > (
315  new dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv4000_imuConfig>(device_nh_));
317  std::placeholders::_1, std::placeholders::_2));
318  break;
319  case system::DeviceInfo::IMAGER_TYPE_AR0234_GREY:
320  case system::DeviceInfo::IMAGER_TYPE_AR0239_COLOR:
321 
322  if (ground_surface_supported) {
324  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234_ground_surfaceConfig> > (
325  new dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234_ground_surfaceConfig>(device_nh_));
327  std::placeholders::_1, std::placeholders::_2));
328  } else {
330  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config> > (
331  new dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config>(device_nh_));
332  server_s27_AR0234_->setCallback(std::bind(&Reconfigure::callback_s27_AR0234, this,
333  std::placeholders::_1, std::placeholders::_2));
334  }
335 
336  break;
337 
338  default:
339 
340  ROS_ERROR("Reconfigure: unsupported imager type \"%d\"", deviceInfo.imagerType);
341  return;
342  }
343  }
344 
347 }
348 
350 {
351 }
352 
353 //
354 // Helper to change resolution. Will check against supported device modes
355 
357  int32_t width,
358  int32_t height,
359  int32_t disparities)
360 {
361  //
362  // See if we need to change resolutions
363  if (width == static_cast<int32_t>(cfg.width()) &&
364  height == static_cast<int32_t>(cfg.height()) &&
365  disparities == static_cast<int32_t>(cfg.disparities()))
366  return false;
367 
368  //
369  // Query all supported resolutions from the sensor, if we haven't already
370 
371  if (device_modes_.empty()) {
372 
374  if (Status_Ok != status) {
375  ROS_ERROR("Reconfigure: failed to query sensor modes: %s",
376  Channel::statusString(status));
377  return false;
378  }
379  }
380 
381  //
382  // Verify that this resolution is supported
383 
384  bool supported = false;
385  std::vector<system::DeviceMode>::const_iterator it = device_modes_.begin();
386  for(; it != device_modes_.end(); ++it) {
387 
388  const system::DeviceMode& m = *it;
389 
390  if (width == static_cast<int32_t>(m.width) &&
391  height == static_cast<int32_t>(m.height) &&
392  disparities == static_cast<int32_t>(m.disparities)) {
393 
394  supported = true;
395  break;
396  }
397  }
398 
399  if (false == supported) {
400  ROS_ERROR("Reconfigure: sensor does not support a resolution of: %dx%d (%d disparities)",
401  width, height, disparities);
402  return false;
403  }
404 
405  ROS_WARN("Reconfigure: changing sensor resolution to %dx%d (%d disparities), from %dx%d "
406  "(%d disparities): reconfiguration may take up to 30 seconds",
407  width, height, disparities,
408  cfg.width(), cfg.height(), cfg.disparities());
409 
410  cfg.setResolution(width, height);
411  cfg.setDisparities(disparities);
412 
413  return true;
414 }
415 
416 template<class T> void Reconfigure::configureSgm(image::Config& cfg, const T& dyn)
417 {
418  cfg.setStereoPostFilterStrength(dyn.stereo_post_filtering);
419 }
420 
421 template<class T> void Reconfigure::configureHdr(image::Config& cfg, const T& dyn)
422 {
423  cfg.setHdr(dyn.hdr_enable);
424 }
425 
426 template<class T> void Reconfigure::configureAutoWhiteBalance(image::Config& cfg, const T& dyn)
427 {
428  cfg.setWhiteBalance(dyn.white_balance_red, dyn.white_balance_blue);
429  cfg.setAutoWhiteBalance(dyn.auto_white_balance);
430  cfg.setAutoWhiteBalanceDecay(dyn.auto_white_balance_decay);
431  cfg.setAutoWhiteBalanceThresh(dyn.auto_white_balance_thresh);
432 }
433 
434 template<class T> void Reconfigure::configureAuxCamera(const T& dyn)
435 {
436  if (aux_supported_) {
437 
438  image::AuxConfig auxConfig;
439  Status status = driver_->getAuxImageConfig(auxConfig);
440  if (Status_Ok != status) {
441  ROS_ERROR("Reconfigure: failed to query aux image config: %s",
442  Channel::statusString(status));
443  return;
444  }
445 
446  //
447  // See if we already have a secondary exposure we want to modify. If not create one for the aux camera
448 
449  auxConfig.setGain(dyn.aux_gain);
450  auxConfig.setExposure(dyn.aux_exposure_time * 1e6);
451  auxConfig.setAutoExposure(dyn.aux_auto_exposure);
452  auxConfig.setAutoExposureMax(dyn.aux_auto_exposure_max_time * 1e6);
453  auxConfig.setAutoExposureDecay(dyn.aux_auto_exposure_decay);
454  auxConfig.setAutoExposureThresh(dyn.aux_auto_exposure_thresh);
455  auxConfig.setAutoExposureTargetIntensity(dyn.aux_auto_exposure_target_intensity);
456 
457  if (dyn.aux_roi_auto_exposure) {
458  if (roi_supported_) {
459  //
460  // Ensure the commanded ROI region is in the full resolution image
461 
462  const int32_t maxX = dyn.__getMax__().aux_roi_auto_exposure_x;
463  const int32_t maxY = dyn.__getMax__().aux_roi_auto_exposure_y;
464 
465  const int32_t x = fmax(0, fmin(dyn.aux_roi_auto_exposure_x, maxX));
466  const int32_t y = fmax(0, fmin(dyn.aux_roi_auto_exposure_y, maxY));
467 
468  auxConfig.setAutoExposureRoi(x, y,
469  fmax(0, fmin(dyn.aux_roi_auto_exposure_width, maxX - x)),
470  fmax(0, fmin(dyn.aux_roi_auto_exposure_height, maxY - y)));
471  } else {
472  ROS_WARN("Reconfigure: ROI auto exposure is not supported with this firmware version");
473  return;
474  }
475 
476  } else {
477  auxConfig.setAutoExposureRoi(0, 0, Roi_Full_Image, Roi_Full_Image);
478  }
479 
480  status = driver_->setAuxImageConfig(auxConfig);
481  if (Status_Ok != status)
482  ROS_ERROR("Reconfigure: failed to set aux image config: %s",
483  Channel::statusString(status));
484 
485  }
486 }
487 
488 template<class T> void Reconfigure::configureCamera(image::Config& cfg, const T& dyn)
489 {
490  DataSource streamsEnabled = 0;
491  int32_t width, height, disparities;
492  bool resolutionChange=false;
493  Status status=Status_Ok;
494 
495  //
496  // Decode the resolution string
497 
498  if (3 != sscanf(dyn.resolution.c_str(), "%dx%dx%d", &width, &height, &disparities)) {
499  ROS_ERROR("Reconfigure: malformed resolution string: \"%s\"", dyn.resolution.c_str());
500  return;
501  }
502 
503  //
504  // If a resolution change is desired
505 
506  if ((resolutionChange = changeResolution(cfg, width, height, disparities) || crop_mode_changed_)) {
507  crop_mode_changed_ = false;
508  //
509  // Halt streams during the resolution change
510  status = driver_->getEnabledStreams(streamsEnabled);
511  if (Status_Ok != status) {
512  ROS_ERROR("Reconfigure: failed to get enabled streams: %s",
513  Channel::statusString(status));
514  return;
515  }
516  status = driver_->stopStreams(streamsEnabled);
517  if (Status_Ok != status) {
518  ROS_ERROR("Reconfigure: failed to stop streams for a resolution change: %s",
519  Channel::statusString(status));
520  return;
521  }
522  }
523 
524  //
525  // Set all other image config from dynamic reconfigure
526 
527  cfg.setFps(dyn.fps);
528  cfg.setGain(dyn.gain);
529  cfg.setExposure(dyn.exposure_time * 1e6);
530  cfg.setAutoExposure(dyn.auto_exposure);
531  cfg.setAutoExposureMax(dyn.auto_exposure_max_time * 1e6);
532  cfg.setAutoExposureDecay(dyn.auto_exposure_decay);
533  cfg.setAutoExposureThresh(dyn.auto_exposure_thresh);
534  cfg.setAutoExposureTargetIntensity(dyn.auto_exposure_target_intensity);
535 
536  if (dyn.roi_auto_exposure) {
537  if (roi_supported_) {
538  //
539  // Ensure the commanded ROI region is in the full resolution image
540 
541  const int32_t maxX = dyn.__getMax__().roi_auto_exposure_x;
542  const int32_t maxY = dyn.__getMax__().roi_auto_exposure_y;
543 
544  const int32_t x = fmax(0, fmin(dyn.roi_auto_exposure_x, maxX));
545  const int32_t y = fmax(0, fmin(dyn.roi_auto_exposure_y, maxY));
546 
547  cfg.setAutoExposureRoi(x, y,
548  fmax(0, fmin(dyn.roi_auto_exposure_width, maxX - x)),
549  fmax(0, fmin(dyn.roi_auto_exposure_height, maxY - y)));
550  } else {
551  ROS_WARN("Reconfigure: ROI auto exposure is not supported with this firmware version");
552  }
553 
554  } else {
555  cfg.setAutoExposureRoi(0, 0, Roi_Full_Image, Roi_Full_Image);
556  }
557 
558  //
559  // Apply, sensor enforces limits per setting.
560 
561  status = driver_->setImageConfig(cfg);
562  if (Status_Ok != status)
563  ROS_ERROR("Reconfigure: failed to set image config: %s",
564  Channel::statusString(status));
565 
566  status = driver_->getImageConfig(cfg);
567  if (Status_Ok != status)
568  ROS_ERROR("Reconfigure: failed to query image config: %s",
569  Channel::statusString(status));
570 
572 
573  //
574  // If we are changing the resolution, let others know about it
575 
576  if (resolutionChange) {
577  status = driver_->startStreams(streamsEnabled);
578  if (Status_Ok != status)
579  ROS_ERROR("Reconfigure: failed to restart streams after a resolution change: %s",
580  Channel::statusString(status));
581  }
582 
583  //
584  // Enable/disable network-based time synchronization.
585  //
586  // If enabled, sensor timestamps will be reported in the local
587  // system clock's frame, using a continuously updated offset from
588  // the sensor's internal clock.
589  //
590  // If disabled, sensor timestamps will be reported in the sensor
591  // clock's frame, which is free-running from zero on power up.
592  //
593  // Enabled by default.
594 
595  driver_->networkTimeSynchronization(dyn.network_time_sync);
596 
597  //
598  // Set our transmit delay
600  d.delay = dyn.desired_transmit_delay;
601  status = driver_->setTransmitDelay(d);
602  if (Status_Ok != status) {
603  ROS_ERROR("Reconfigure: failed to set transmit delay: %s",
604  Channel::statusString(status));
605  }
606 }
607 
608 template<class T> void Reconfigure::configureMotor(const T& dyn)
609 {
610  //
611  // Send the desired motor speed
612 
613  if (motor_supported_) {
614 
615  const float radiansPerSecondToRpm = 9.54929659643;
616 
617  Status status = driver_->setMotorSpeed(radiansPerSecondToRpm * dyn.motor_speed);
618  if (Status_Ok != status) {
619  if (Status_Unsupported == status)
620  motor_supported_ = false;
621  else
622  ROS_ERROR("Reconfigure: failed to set motor speed: %s",
623  Channel::statusString(status));
624  }
625  }
626 }
627 
628 template<class T> void Reconfigure::configureLeds(const T& dyn)
629 {
630  //
631  // Send the desired lighting configuration
632 
633  if (lighting_supported_) {
634 
635  lighting::Config leds;
636 
637  if (false == dyn.lighting) {
638  leds.setFlash(false);
639  leds.setDutyCycle(0.0);
640  } else {
641  leds.setFlash(dyn.flash);
642  leds.setDutyCycle(dyn.led_duty_cycle * 100.0);
643  }
644 
645  Status status = driver_->setLightingConfig(leds);
646  if (Status_Ok != status) {
647  if (Status_Unsupported == status)
648  lighting_supported_ = false;
649  else
650  ROS_ERROR("Reconfigure: failed to set lighting config: %s",
651  Channel::statusString(status));
652  }
653  }
654 }
655 
656 template<class T> void Reconfigure::configureS19Leds(const T& dyn)
657 {
658  //
659  // Send the desired lighting configuration
660 
661  if (lighting_supported_) {
662 
663  lighting::Config leds;
664 
665  if (false == dyn.lighting) {
666  leds.setFlash(false);
667  leds.setDutyCycle(0.0);
668  } else {
669  leds.setFlash(dyn.flash);
670  leds.setDutyCycle(dyn.led_duty_cycle * 100.0);
671  leds.setNumberOfPulses(dyn.led_number_of_pulses);
672  leds.setStartupTime(dyn.led_startup_time_us);
673  leds.setInvertPulse(dyn.led_invert_pulse);
674  }
675 
676  Status status = driver_->setLightingConfig(leds);
677  if (Status_Ok != status) {
678  if (Status_Unsupported == status)
679  lighting_supported_ = false;
680  else
681  ROS_ERROR("Reconfigure: failed to set lighting config: %s",
682  Channel::statusString(status));
683  }
684  }
685 }
686 
687 template<class T> void Reconfigure::configureImu(const T& dyn)
688 {
689  if (imu_configs_.empty()) {
691  imu_configs_);
692  if (Status_Ok != status) {
693  ROS_ERROR("Reconfigure: failed to query IMU config: %s",
694  Channel::statusString(status));
695  return;
696  }
697  }
698 
699  std::vector<imu::Config> changedConfigs;
700  std::vector<imu::Config>::iterator it = imu_configs_.begin();
701  for(; it!=imu_configs_.end(); ++it) {
702 
703  imu::Config& c = *it;
704 
705  if ("accelerometer" == c.name &&
706  (c.enabled != dyn.accelerometer_enabled ||
707  static_cast<int>(c.rateTableIndex) != dyn.accelerometer_rate ||
708  static_cast<int>(c.rangeTableIndex) != dyn.accelerometer_range)) {
709 
710  c.enabled = dyn.accelerometer_enabled;
711  c.rateTableIndex = dyn.accelerometer_rate;
712  c.rangeTableIndex = dyn.accelerometer_range;
713  changedConfigs.push_back(c);
714  }
715 
716  if ("gyroscope" == c.name &&
717  (c.enabled != dyn.gyroscope_enabled ||
718  static_cast<int>(c.rateTableIndex) != dyn.gyroscope_rate ||
719  static_cast<int>(c.rangeTableIndex) != dyn.gyroscope_range)) {
720 
721  c.enabled = dyn.gyroscope_enabled;
722  c.rateTableIndex = dyn.gyroscope_rate;
723  c.rangeTableIndex = dyn.gyroscope_range;
724  changedConfigs.push_back(c);
725  }
726 
727  if ("magnetometer" == c.name &&
728  (c.enabled != dyn.magnetometer_enabled ||
729  static_cast<int>(c.rateTableIndex) != dyn.magnetometer_rate ||
730  static_cast<int>(c.rangeTableIndex) != dyn.magnetometer_range)) {
731 
732  c.enabled = dyn.magnetometer_enabled;
733  c.rateTableIndex = dyn.magnetometer_rate;
734  c.rangeTableIndex = dyn.magnetometer_range;
735  changedConfigs.push_back(c);
736  }
737  }
738 
739  if (changedConfigs.size() > 0 ||
740  static_cast<int>(imu_samples_per_message_) != dyn.imu_samples_per_message) {
741 
742  ROS_WARN("Reconfigure: IMU configuration changes will take effect after all IMU "
743  "topic subscriptions have been closed.");
744 
745  imu_samples_per_message_ = dyn.imu_samples_per_message;
746 
747  Status status = driver_->setImuConfig(false, // store in non-volatile flash
749  changedConfigs); // can be empty
750  if (Status_Ok != status) {
751  ROS_ERROR("Reconfigure: failed to set IMU configuration: %s",
752  Channel::statusString(status));
753  imu_configs_.clear();
754  }
755  }
756 }
757 
758 template<class T> void Reconfigure::configureBorderClip(const T& dyn)
759 {
760 
761  if (static_cast<BorderClip>(dyn.border_clip_type) != border_clip_type_ ||
762  dyn.border_clip_value != border_clip_value_) {
763  border_clip_type_ = static_cast<BorderClip>(dyn.border_clip_type);
764  border_clip_value_ = dyn.border_clip_value;
766  }
767 }
768 
769 template<class T> void Reconfigure::configurePointCloudRange(const T& dyn)
770 {
771  max_point_cloud_range_callback_(dyn.max_point_cloud_range);
772 }
773 
774 template<class T> void Reconfigure::configurePtp(const T& dyn)
775 {
776  if (ptp_supported_) {
777  Status status = driver_->ptpTimeSynchronization(dyn.ptp_time_sync);
778  if (Status_Ok != status) {
779  if (Status_Unsupported == status || Status_Unknown == status) {
780  ptp_supported_ = false;
781  } else {
782  ROS_ERROR("Reconfigure: enable PTP time synchronization: %s",
783  Channel::statusString(status));
784  }
785  }
786  }
787 
788  if (dyn.trigger_source != 3 || (ptp_supported_ && dyn.trigger_source == 3)) {
789  Status status = driver_->setTriggerSource(dyn.trigger_source);
790  if (Status_Ok != status) {
791  if (Status_Unsupported == status || Status_Unknown == status) {
792  ptp_supported_ = false;
793  } else {
794  ROS_ERROR("Reconfigure: failed to set trigger source: %s",
795  Channel::statusString(status));
796  }
797  }
798  }
799 }
800 
801 template<class T> void Reconfigure::configureStereoProfile(crl::multisense::CameraProfile &profile, const T& dyn)
802 {
803  profile |= (dyn.high_contrast_profile ? crl::multisense::High_Contrast : profile);
804  profile |= (dyn.show_roi_profile ? crl::multisense::Show_ROIs : profile);
805 }
806 
808 {
809  profile |= (dyn.ground_surface_profile ? crl::multisense::Ground_Surface : profile);
810 }
811 
813 {
814  profile |= (dyn.full_res_aux_profile ? crl::multisense::Full_Res_Aux_Cam : profile);
815 }
816 
818 {
819  profile |= (dyn.detail_disparity_profile ? crl::multisense::Detail_Disparity : profile);
820 }
821 
822 template<class T> void Reconfigure::configureExtrinsics(const T& dyn)
823 {
824  constexpr float deg_to_rad = M_PI / 180.0f;
825  if (std::abs(dyn.origin_from_camera_position_x_m - calibration_.x) < 1e-3 &&
826  std::abs(dyn.origin_from_camera_position_y_m - calibration_.y) < 1e-3 &&
827  std::abs(dyn.origin_from_camera_position_z_m - calibration_.z) < 1e-3 &&
828  std::abs(dyn.origin_from_camera_rotation_x_deg * deg_to_rad - calibration_.roll) < 1e-3 &&
829  std::abs(dyn.origin_from_camera_rotation_y_deg * deg_to_rad - calibration_.pitch) < 1e-3 &&
830  std::abs(dyn.origin_from_camera_rotation_z_deg * deg_to_rad - calibration_.yaw) < 1e-3) {
831  return;
832  }
833 
834  //
835  // Update calibration on camera via libmultisense
836 
837  calibration_.x = dyn.origin_from_camera_position_x_m;
838  calibration_.y = dyn.origin_from_camera_position_y_m;
839  calibration_.z = dyn.origin_from_camera_position_z_m;
840 
841  calibration_.roll = dyn.origin_from_camera_rotation_x_deg * deg_to_rad;
842  calibration_.pitch = dyn.origin_from_camera_rotation_y_deg * deg_to_rad;
843  calibration_.yaw = dyn.origin_from_camera_rotation_z_deg * deg_to_rad;
844 
847  if (Status_Ok != status) {
848  ROS_ERROR("Reconfigure: failed to set external calibration: %s",
849  Channel::statusString(status));
850  return;
851  }
852  }
853 
854  // Update camera class locally to modify pointcloud transform in rviz
856 }
857 
858 template<class T> void Reconfigure::configureGroundSurfaceParams(const T& dyn)
859 {
860  //
861  // Update calibration on camera via libmultisense
863 
864  params.ground_surface_number_of_levels_x = dyn.ground_surface_spline_resolution_x;
865  params.ground_surface_number_of_levels_z = dyn.ground_surface_spline_resolution_z;
866 
867  if (dyn.ground_surface_pre_transform_data == "Quadratic")
868  params.ground_surface_base_model = 0;
869  else if (dyn.ground_surface_pre_transform_data == "Mean")
870  params.ground_surface_base_model = 1;
871  else if (dyn.ground_surface_pre_transform_data == "Zero")
872  params.ground_surface_base_model = 2;
873 
874  params.ground_surface_pointcloud_grid_size = dyn.ground_surface_pointcloud_grid_size;
875  params.ground_surface_min_points_per_grid = dyn.ground_surface_min_points_per_grid;
876  params.ground_surface_pointcloud_decimation = dyn.ground_surface_pointcloud_decimation;
877  params.ground_surface_pointcloud_max_range_m = dyn.ground_surface_pointcloud_global_max_z_m;
878  params.ground_surface_pointcloud_min_range_m = dyn.ground_surface_pointcloud_global_min_z_m;
879  params.ground_surface_pointcloud_max_width_m = dyn.ground_surface_pointcloud_global_max_x_m;
880  params.ground_surface_pointcloud_min_width_m = dyn.ground_surface_pointcloud_global_min_x_m;
881  params.ground_surface_pointcloud_max_height_m = dyn.ground_surface_pointcloud_global_max_height_m;
882  params.ground_surface_pointcloud_min_height_m = dyn.ground_surface_pointcloud_global_min_height_m;
883  params.ground_surface_obstacle_height_thresh_m = dyn.ground_surface_obstacle_height_thresh_m;
884  params.ground_surface_obstacle_percentage_thresh = dyn.ground_surface_obstacle_percentage_thresh;
885  params.ground_surface_max_fitting_iterations = dyn.ground_surface_max_fitting_iterations;
886  params.ground_surface_adjacent_cell_search_size_m = dyn.ground_surface_adjacent_cell_search_size_m;
887 
888  // Update ground surface params on camera
889  Status status = driver_->setGroundSurfaceParams(params);
890  if (Status_Ok != status) {
891  ROS_ERROR("Reconfigure: failed to set ground surface params: %s",
892  Channel::statusString(status));
893  return;
894  }
895 
896  //
897  // Update spline drawing parameters locally
900  dyn.ground_surface_pointcloud_global_max_z_m,
901  dyn.ground_surface_pointcloud_global_min_z_m,
902  dyn.ground_surface_pointcloud_global_max_x_m,
903  dyn.ground_surface_pointcloud_global_min_x_m,
904  dyn.ground_surface_spline_draw_resolution}
905  );
906 }
907 
908 #define GET_CONFIG() \
909  image::Config cfg; \
910  Status status = driver_->getImageConfig(cfg); \
911  if (Status_Ok != status) { \
912  ROS_ERROR("Reconfigure: failed to query image config: %s", \
913  Channel::statusString(status)); \
914  return; \
915  } \
916 
917 #define SL_BM() do { \
918  GET_CONFIG(); \
919  configureAutoWhiteBalance(cfg, dyn); \
920  configureCamera(cfg, dyn); \
921  configureMotor(dyn); \
922  configureLeds(dyn); \
923  configureBorderClip(dyn); \
924  configurePointCloudRange(dyn); \
925  configureExtrinsics(dyn); \
926  } while(0)
927 
928 #define SL_BM_IMU() do { \
929  GET_CONFIG(); \
930  configureAutoWhiteBalance(cfg, dyn); \
931  configureCamera(cfg, dyn); \
932  configureMotor(dyn); \
933  configureLeds(dyn); \
934  configureImu(dyn); \
935  configureBorderClip(dyn); \
936  configurePointCloudRange(dyn); \
937  configureExtrinsics(dyn); \
938  } while(0)
939 
940 #define MONO_BM_IMU() do { \
941  GET_CONFIG(); \
942  configureAutoWhiteBalance(cfg, dyn); \
943  configureCamera(cfg, dyn); \
944  configureLeds(dyn); \
945  configureImu(dyn); \
946  configureExtrinsics(dyn); \
947  } while(0)
948 
949 #define SL_SGM_IMU() do { \
950  GET_CONFIG(); \
951  configureSgm(cfg, dyn); \
952  configureHdr(cfg, dyn); \
953  configureAutoWhiteBalance(cfg, dyn); \
954  configureCamera(cfg, dyn); \
955  configureMotor(dyn); \
956  configureLeds(dyn); \
957  configureImu(dyn); \
958  configureBorderClip(dyn); \
959  configurePointCloudRange(dyn); \
960  configureExtrinsics(dyn); \
961  } while(0)
962 
963 #define SL_SGM() do { \
964  GET_CONFIG(); \
965  configureSgm(cfg, dyn); \
966  configureHdr(cfg, dyn); \
967  configureAutoWhiteBalance(cfg, dyn); \
968  configureCamera(cfg, dyn); \
969  configureBorderClip(dyn); \
970  configurePointCloudRange(dyn); \
971  configureExtrinsics(dyn); \
972  } while(0)
973 
974 #define SL_SGM_IMU_CMV4000() do { \
975  GET_CONFIG(); \
976  configureSgm(cfg, dyn); \
977  configureHdr(cfg, dyn); \
978  configureAutoWhiteBalance(cfg, dyn); \
979  configureCamera(cfg, dyn); \
980  configureMotor(dyn); \
981  configureLeds(dyn); \
982  configureImu(dyn); \
983  configureBorderClip(dyn); \
984  configurePointCloudRange(dyn); \
985  configureExtrinsics(dyn); \
986  } while(0)
987 
988 #define S27_SGM() do { \
989  GET_CONFIG(); \
990  configureSgm(cfg, dyn); \
991  crl::multisense::CameraProfile profile = crl::multisense::User_Control; \
992  configureStereoProfile(profile, dyn); \
993  configureDetailDisparityStereoProfile(profile, dyn); \
994  configureFullResAuxStereoProfile(profile, dyn); \
995  cfg.setCameraProfile(profile); \
996  configureAutoWhiteBalance(cfg, dyn); \
997  configureAuxCamera(dyn); \
998  configureCamera(cfg, dyn); \
999  configureBorderClip(dyn); \
1000  configurePtp(dyn); \
1001  configurePointCloudRange(dyn); \
1002  configureExtrinsics(dyn); \
1003  } while(0)
1004 
1005 #define KS21_SGM() do { \
1006  GET_CONFIG(); \
1007  configureSgm(cfg, dyn); \
1008  crl::multisense::CameraProfile profile = crl::multisense::User_Control; \
1009  configureStereoProfile(profile, dyn); \
1010  configureDetailDisparityStereoProfile(profile, dyn); \
1011  cfg.setCameraProfile(profile); \
1012  configureCamera(cfg, dyn); \
1013  configureBorderClip(dyn); \
1014  configureS19Leds(dyn); \
1015  configurePtp(dyn); \
1016  configurePointCloudRange(dyn); \
1017  configureExtrinsics(dyn); \
1018  } while(0)
1019 
1020 #define S27_SGM_GROUND_SURFACE() do { \
1021  GET_CONFIG(); \
1022  configureSgm(cfg, dyn); \
1023  crl::multisense::CameraProfile profile = crl::multisense::User_Control; \
1024  configureStereoProfile(profile, dyn); \
1025  configureDetailDisparityStereoProfile(profile, dyn); \
1026  configureGroundSurfaceStereoProfile(profile, dyn); \
1027  configureFullResAuxStereoProfile(profile, dyn); \
1028  cfg.setCameraProfile(profile); \
1029  configureAutoWhiteBalance(cfg, dyn); \
1030  configureAuxCamera(dyn); \
1031  configureCamera(cfg, dyn); \
1032  configureBorderClip(dyn); \
1033  configurePtp(dyn); \
1034  configurePointCloudRange(dyn); \
1035  configureExtrinsics(dyn); \
1036  configureGroundSurfaceParams(dyn); \
1037  } while(0)
1038 
1039 #define KS21_SGM_GROUND_SURFACE() do { \
1040  GET_CONFIG(); \
1041  configureSgm(cfg, dyn); \
1042  crl::multisense::CameraProfile profile = crl::multisense::User_Control; \
1043  configureStereoProfile(profile, dyn); \
1044  configureDetailDisparityStereoProfile(profile, dyn); \
1045  configureGroundSurfaceStereoProfile(profile, dyn); \
1046  cfg.setCameraProfile(profile); \
1047  configureCamera(cfg, dyn); \
1048  configureBorderClip(dyn); \
1049  configureS19Leds(dyn); \
1050  configurePtp(dyn); \
1051  configurePointCloudRange(dyn); \
1052  configureExtrinsics(dyn); \
1053  configureGroundSurfaceParams(dyn); \
1054  } while(0)
1055 
1056 #define REMOTE_HEAD_VPB() do { \
1057  GET_CONFIG(); \
1058  configurePtp(dyn); \
1059  configureExtrinsics(dyn); \
1060  } while(0)
1061 
1062 #define REMOTE_HEAD_SGM_AR0234() do { \
1063  GET_CONFIG(); \
1064  configureSgm(cfg, dyn); \
1065  crl::multisense::CameraProfile profile = crl::multisense::User_Control; \
1066  configureStereoProfile(profile, dyn); \
1067  configureDetailDisparityStereoProfile(profile, dyn); \
1068  cfg.setCameraProfile(profile); \
1069  configureCamera(cfg, dyn); \
1070  configureBorderClip(dyn); \
1071  configureS19Leds(dyn); \
1072  configurePtp(dyn); \
1073  configurePointCloudRange(dyn); \
1074  configureExtrinsics(dyn); \
1075  } while(0)
1076 
1077 #define REMOTE_HEAD_SGM_AR0234_GROUND_SURFACE() do { \
1078  GET_CONFIG(); \
1079  configureSgm(cfg, dyn); \
1080  crl::multisense::CameraProfile profile = crl::multisense::User_Control; \
1081  configureStereoProfile(profile, dyn); \
1082  configureDetailDisparityStereoProfile(profile, dyn); \
1083  configureGroundSurfaceStereoProfile(profile, dyn); \
1084  cfg.setCameraProfile(profile); \
1085  configureCamera(cfg, dyn); \
1086  configureBorderClip(dyn); \
1087  configureS19Leds(dyn); \
1088  configurePtp(dyn); \
1089  configurePointCloudRange(dyn); \
1090  configureExtrinsics(dyn); \
1091  configureGroundSurfaceParams(dyn); \
1092  } while(0)
1093 
1094 #define REMOTE_HEAD_MONOCAM_AR0234() do { \
1095  GET_CONFIG(); \
1096  crl::multisense::CameraProfile profile = crl::multisense::User_Control; \
1097  configureStereoProfile(profile, dyn); \
1098  cfg.setCameraProfile(profile); \
1099  configureCamera(cfg, dyn); \
1100  configureS19Leds(dyn); \
1101  configurePtp(dyn); \
1102  configureExtrinsics(dyn); \
1103  } while(0)
1104 
1105 //
1106 // The dynamic reconfigure callbacks (MultiSense S* & feature variations)
1107 
1108 void Reconfigure::callback_sl_bm_cmv2000 (multisense_ros::sl_bm_cmv2000Config& dyn, uint32_t level) { (void) level; SL_BM(); }
1109 void Reconfigure::callback_sl_bm_cmv2000_imu (multisense_ros::sl_bm_cmv2000_imuConfig& dyn, uint32_t level) { (void) level; SL_BM_IMU(); }
1110 void Reconfigure::callback_sl_bm_cmv4000 (multisense_ros::sl_bm_cmv4000Config& dyn, uint32_t level) { (void) level; SL_BM(); }
1111 void Reconfigure::callback_sl_bm_cmv4000_imu (multisense_ros::sl_bm_cmv4000_imuConfig& dyn, uint32_t level) { (void) level; SL_BM_IMU(); }
1112 void Reconfigure::callback_sl_sgm_cmv2000_imu (multisense_ros::sl_sgm_cmv2000_imuConfig& dyn, uint32_t level) { (void) level; SL_SGM_IMU(); }
1113 void Reconfigure::callback_sl_sgm_cmv4000_imu (multisense_ros::sl_sgm_cmv4000_imuConfig& dyn, uint32_t level) { (void) level; SL_SGM_IMU_CMV4000(); }
1114 void Reconfigure::callback_mono_cmv2000 (multisense_ros::mono_cmv2000Config& dyn, uint32_t level) { (void) level; MONO_BM_IMU(); }
1115 void Reconfigure::callback_mono_cmv4000 (multisense_ros::mono_cmv4000Config& dyn, uint32_t level) { (void) level; MONO_BM_IMU(); }
1116 void Reconfigure::callback_s27_AR0234 (multisense_ros::s27_sgm_AR0234Config& dyn, uint32_t level) { (void) level; S27_SGM(); }
1117 void Reconfigure::callback_ks21_AR0234 (multisense_ros::ks21_sgm_AR0234Config& dyn, uint32_t level) { (void) level; KS21_SGM(); }
1118 void Reconfigure::callback_remote_head_vpb (multisense_ros::remote_head_vpbConfig& dyn, uint32_t level) { (void) level; REMOTE_HEAD_VPB(); }
1119 void Reconfigure::callback_remote_head_sgm_AR0234 (multisense_ros::remote_head_sgm_AR0234Config& dyn, uint32_t level) { (void) level; REMOTE_HEAD_SGM_AR0234(); }
1120 void Reconfigure::callback_remote_head_monocam_AR0234(multisense_ros::remote_head_monocam_AR0234Config& dyn, uint32_t level) { (void) level; REMOTE_HEAD_MONOCAM_AR0234(); }
1121 
1122 void Reconfigure::callback_s27_AR0234_ground_surface (multisense_ros::s27_sgm_AR0234_ground_surfaceConfig& dyn, uint32_t level) { (void) level; S27_SGM_GROUND_SURFACE(); }
1123 void Reconfigure::callback_ks21_AR0234_ground_surface (multisense_ros::ks21_sgm_AR0234_ground_surfaceConfig& dyn, uint32_t level) { (void) level; KS21_SGM_GROUND_SURFACE(); }
1124 void Reconfigure::callback_remote_head_sgm_AR0234_ground_surface(multisense_ros::remote_head_sgm_AR0234_ground_surfaceConfig& dyn, uint32_t level) { (void) level; REMOTE_HEAD_SGM_AR0234_GROUND_SURFACE(); }
1125 
1126 //
1127 // BCAM (Sony IMX104)
1128 
1129 void Reconfigure::callback_bcam_imx104(multisense_ros::bcam_imx104Config& dyn,
1130  uint32_t level)
1131 {
1132  (void) level;
1133 
1134  GET_CONFIG();
1135  DataSource streamsEnabled = 0;
1136  int32_t width, height;
1137  bool resolutionChange=false;
1138 
1139  //
1140  // Decode the resolution string
1141 
1142  if (2 != sscanf(dyn.resolution.c_str(), "%dx%dx", &width, &height)) {
1143  ROS_ERROR("Reconfigure: malformed resolution string: \"%s\"", dyn.resolution.c_str());
1144  return;
1145  }
1146 
1147  //
1148  // If a resolution change is desired
1149 
1150  if ((resolutionChange = changeResolution(cfg, width, height, 0))) {
1151 
1152  //
1153  // Halt streams during the resolution change
1154 
1155  status = driver_->getEnabledStreams(streamsEnabled);
1156  if (Status_Ok != status) {
1157  ROS_ERROR("Reconfigure: failed to get enabled streams: %s",
1158  Channel::statusString(status));
1159  return;
1160  }
1161  status = driver_->stopStreams(streamsEnabled);
1162  if (Status_Ok != status) {
1163  ROS_ERROR("Reconfigure: failed to stop streams for a resolution change: %s",
1164  Channel::statusString(status));
1165  return;
1166  }
1167  }
1168 
1169  //
1170  // Set all other image config from dynamic reconfigure
1171 
1172  cfg.setFps(static_cast<float>(dyn.fps));
1173  cfg.setGain(dyn.gain);
1174  cfg.setExposure(dyn.exposure_time * 1e6);
1175  cfg.setAutoExposure(dyn.auto_exposure);
1176  cfg.setAutoExposureMax(dyn.auto_exposure_max_time * 1e6);
1177  cfg.setAutoExposureDecay(dyn.auto_exposure_decay);
1178  cfg.setAutoExposureThresh(dyn.auto_exposure_thresh);
1179  cfg.setWhiteBalance(dyn.white_balance_red,
1180  dyn.white_balance_blue);
1181  cfg.setAutoWhiteBalance(dyn.auto_white_balance);
1182  cfg.setAutoWhiteBalanceDecay(dyn.auto_white_balance_decay);
1183  cfg.setAutoWhiteBalanceThresh(dyn.auto_white_balance_thresh);
1184 
1185  //
1186  // Apply, sensor enforces limits per setting.
1187 
1188  status = driver_->setImageConfig(cfg);
1189  if (Status_Ok != status)
1190  ROS_ERROR("Reconfigure: failed to set image config: %s",
1191  Channel::statusString(status));
1192 
1193  status = driver_->getImageConfig(cfg);
1194  if (Status_Ok != status)
1195  ROS_ERROR("Reconfigure: failed to query image config: %s",
1196  Channel::statusString(status));
1197 
1199 
1200  //
1201  // If we are changing the resolution, let others know about it
1202 
1203  if (resolutionChange) {
1204 
1205  status = driver_->startStreams(streamsEnabled);
1206  if (Status_Ok != status)
1207  ROS_ERROR("Reconfigure: failed to restart streams after a resolution change: %s",
1208  Channel::statusString(status));
1209  }
1210 }
1211 
1212 //
1213 // ST21 FLIR Thermal Imagers
1214 // Seperate callback required due to limited subset of dyn parameters
1215 // in st21_sgm_vga_imuConfig. configureCamera results in SFINAE errors
1216 
1217 void Reconfigure::callback_st21_vga(multisense_ros::st21_sgm_vga_imuConfig& dyn,
1218  uint32_t level)
1219 {
1220  (void) level;
1221  DataSource streamsEnabled = 0;
1222  int32_t width, height, disparities;
1223  bool resolutionChange=false;
1224 
1225  GET_CONFIG();
1226 
1227  //
1228  // Decode the resolution string
1229 
1230  if (3 != sscanf(dyn.resolution.c_str(), "%dx%dx%d", &width, &height, &disparities)) {
1231  ROS_ERROR("Reconfigure: malformed resolution string: \"%s\"", dyn.resolution.c_str());
1232  return;
1233  }
1234 
1235  //
1236  // If a resolution change is desired
1237 
1238  if ((resolutionChange = changeResolution(cfg, width, height, disparities))) {
1239 
1240  //
1241  // Halt streams during the resolution change
1242 
1243  status = driver_->getEnabledStreams(streamsEnabled);
1244  if (Status_Ok != status) {
1245  ROS_ERROR("Reconfigure: failed to get enabled streams: %s",
1246  Channel::statusString(status));
1247  return;
1248  }
1249  status = driver_->stopStreams(streamsEnabled);
1250  if (Status_Ok != status) {
1251  ROS_ERROR("Reconfigure: failed to stop streams for a resolution change: %s",
1252  Channel::statusString(status));
1253  return;
1254  }
1255  }
1256 
1257  cfg.setFps(dyn.fps);
1258 
1259  configureSgm(cfg, dyn);
1260  configureImu(dyn);
1261 
1262  //
1263  // Apply, sensor enforces limits per setting.
1264 
1265  status = driver_->setImageConfig(cfg);
1266  if (Status_Ok != status)
1267  ROS_ERROR("Reconfigure: failed to set image config: %s",
1268  Channel::statusString(status));
1269 
1270  status = driver_->getImageConfig(cfg);
1271  if (Status_Ok != status)
1272  ROS_ERROR("Reconfigure: failed to query image config: %s",
1273  Channel::statusString(status));
1274 
1276 
1277  //
1278  // If we are changing the resolution, let others know about it
1279 
1280  if (resolutionChange) {
1281 
1282  status = driver_->startStreams(streamsEnabled);
1283  if (Status_Ok != status)
1284  ROS_ERROR("Reconfigure: failed to restart streams after a resolution change: %s",
1285  Channel::statusString(status));
1286  }
1287 
1288  configureBorderClip(dyn);
1290 }
1291 
1292 } // namespace
virtual Status startStreams(DataSource mask)=0
d
void callback_sl_bm_cmv4000(multisense_ros::sl_bm_cmv4000Config &config, uint32_t level)
void callback_s27_AR0234(multisense_ros::s27_sgm_AR0234Config &config, uint32_t level)
uint32_t CameraProfile
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv2000_imuConfig > > server_sl_bm_cmv2000_imu_
Definition: reconfigure.h:157
void configureCamera(crl::multisense::image::Config &cfg, const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::remote_head_sgm_AR0234Config > > server_remote_head_sgm_AR0234_
Definition: reconfigure.h:172
void setStereoPostFilterStrength(float s)
static CRL_CONSTEXPR CameraProfile Full_Res_Aux_Cam
std::function< void(BorderClip, double)> border_clip_change_callback_
Definition: reconfigure.h:198
#define SL_BM_IMU()
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::mono_cmv4000Config > > server_mono_cmv4000_
Definition: reconfigure.h:165
void configureBorderClip(const T &dyn)
virtual Status getEnabledStreams(DataSource &mask)=0
virtual Status setMotorSpeed(float rpm)=0
void setAutoExposureTargetIntensity(float d)
void setAutoWhiteBalanceThresh(float t)
void configureGroundSurfaceStereoProfile(crl::multisense::CameraProfile &profile, const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv4000_imuConfig > > server_sl_bm_cmv4000_imu_
Definition: reconfigure.h:159
std::vector< crl::multisense::system::DeviceMode > device_modes_
Definition: reconfigure.h:149
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::ks21_sgm_AR0234Config > > server_ks21_sgm_AR0234_
Definition: reconfigure.h:167
static CRL_CONSTEXPR CameraProfile Detail_Disparity
NONE
void setAutoWhiteBalanceDecay(uint32_t d)
crl::multisense::Channel * driver_
Definition: reconfigure.h:134
virtual Status setGroundSurfaceParams(const system::GroundSurfaceParams &params)=0
void callback_ks21_AR0234(multisense_ros::ks21_sgm_AR0234Config &config, uint32_t level)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::bcam_imx104Config > > server_bcam_imx104_
Definition: reconfigure.h:162
void callback_mono_cmv4000(multisense_ros::mono_cmv4000Config &config, uint32_t level)
virtual Status stopStreams(DataSource mask)=0
static CRL_CONSTEXPR CameraProfile Show_ROIs
void configureAuxCamera(const T &dyn)
#define SL_SGM_IMU()
void callback_mono_cmv2000(multisense_ros::mono_cmv2000Config &config, uint32_t level)
void configurePointCloudRange(const T &dyn)
void callback_sl_sgm_cmv4000_imu(multisense_ros::sl_sgm_cmv4000_imuConfig &config, uint32_t level)
void callback_remote_head_sgm_AR0234(multisense_ros::remote_head_sgm_AR0234Config &dyn, uint32_t level)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::st21_sgm_vga_imuConfig > > server_st21_vga_
Definition: reconfigure.h:163
void callback_st21_vga(multisense_ros::st21_sgm_vga_imuConfig &config, uint32_t level)
void setResolution(uint32_t w, uint32_t h)
virtual Status networkTimeSynchronization(bool enabled)=0
bool setDutyCycle(float percent)
#define S27_SGM_GROUND_SURFACE()
#define GET_CONFIG()
virtual Status ptpTimeSynchronization(bool enabled)=0
virtual Status setExternalCalibration(const system::ExternalCalibration &calibration)=0
void callback_s27_AR0234_ground_surface(multisense_ros::s27_sgm_AR0234_ground_surfaceConfig &dyn, uint32_t level)
#define ROS_WARN(...)
virtual Status getVersionInfo(system::VersionInfo &v)=0
virtual Status getImuConfig(uint32_t &samplesPerMessage, std::vector< imu::Config > &c)=0
void callback_sl_sgm_cmv2000_imu(multisense_ros::sl_sgm_cmv2000_imuConfig &config, uint32_t level)
void configureExtrinsics(const T &dyn)
#define REMOTE_HEAD_MONOCAM_AR0234()
void callback_remote_head_sgm_AR0234_ground_surface(multisense_ros::remote_head_sgm_AR0234_ground_surfaceConfig &dyn, uint32_t level)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_sgm_cmv2000_imuConfig > > server_sl_sgm_cmv2000_imu_
Definition: reconfigure.h:160
ros::NodeHandle device_nh_
Definition: reconfigure.h:144
void configureHdr(crl::multisense::image::Config &cfg, const T &dyn)
#define REMOTE_HEAD_SGM_AR0234_GROUND_SURFACE()
void setAutoExposureDecay(uint32_t d)
void callback_sl_bm_cmv4000_imu(multisense_ros::sl_bm_cmv4000_imuConfig &config, uint32_t level)
std::function< void(ground_surface_utilities::SplineDrawParameters)> spline_draw_parameters_callback_
Definition: reconfigure.h:214
crl::multisense::system::ExternalCalibration calibration_
Definition: reconfigure.h:208
virtual Status setImuConfig(bool storeSettingsInFlash, uint32_t samplesPerMessage, const std::vector< imu::Config > &c)=0
void configureMotor(const T &dyn)
void callback_ks21_AR0234_ground_surface(multisense_ros::ks21_sgm_AR0234_ground_surfaceConfig &dyn, uint32_t level)
bool setInvertPulse(const bool invert)
#define SL_BM()
void configureImu(const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::remote_head_vpbConfig > > server_remote_head_vpb_
Definition: reconfigure.h:171
virtual Status setTriggerSource(TriggerSource s)=0
Struct containing parameters for drawing a pointcloud representation of a B-Spline model...
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::ks21_sgm_AR0234_ground_surfaceConfig > > server_ks21_sgm_AR0234_ground_surface_
Definition: reconfigure.h:169
virtual Status getDeviceModes(std::vector< system::DeviceMode > &m)=0
std::function< void(crl::multisense::system::ExternalCalibration)> extrinsics_callback_
Definition: reconfigure.h:209
void setDisparities(uint32_t d)
#define S27_SGM()
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv4000Config > > server_sl_bm_cmv4000_
Definition: reconfigure.h:158
virtual Status setLightingConfig(const lighting::Config &c)=0
void configureDetailDisparityStereoProfile(crl::multisense::CameraProfile &profile, const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::remote_head_sgm_AR0234_ground_surfaceConfig > > server_remote_head_sgm_AR0234_ground_surface_
Definition: reconfigure.h:173
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::remote_head_monocam_AR0234Config > > server_remote_head_monocam_AR0234_
Definition: reconfigure.h:174
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv2000Config > > server_sl_bm_cmv2000_
Definition: reconfigure.h:156
virtual Status setImageConfig(const image::Config &c)=0
void setAutoExposureTargetIntensity(float d)
void setAutoExposureMax(uint32_t m)
static CRL_CONSTEXPR CameraProfile High_Contrast
void setWhiteBalance(float r, float b)
std::function< void(crl::multisense::image::Config)> resolution_change_callback_
Definition: reconfigure.h:139
void configureSgm(crl::multisense::image::Config &cfg, const T &dyn)
#define REMOTE_HEAD_SGM_AR0234()
void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
uint32_t DataSource
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::s27_sgm_AR0234_ground_surfaceConfig > > server_s27_AR0234_ground_surface_
Definition: reconfigure.h:168
void configureAutoWhiteBalance(crl::multisense::image::Config &cfg, const T &dyn)
bool changeResolution(crl::multisense::image::Config &cfg, int32_t width, int32_t height, int32_t disparities)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::s27_sgm_AR0234Config > > server_s27_AR0234_
Definition: reconfigure.h:166
virtual Status setAuxImageConfig(const image::AuxConfig &c)=0
virtual Status setTransmitDelay(const image::TransmitDelay &c)=0
bool setStartupTime(uint32_t ledTransientResponse_us)
static CRL_CONSTEXPR CameraProfile Ground_Surface
void configureFullResAuxStereoProfile(crl::multisense::CameraProfile &profile, const T &dyn)
void callback_remote_head_vpb(multisense_ros::remote_head_vpbConfig &dyn, uint32_t level)
#define SL_SGM_IMU_CMV4000()
void callback_sl_bm_cmv2000(multisense_ros::sl_bm_cmv2000Config &config, uint32_t level)
#define KS21_SGM()
void configureStereoProfile(crl::multisense::CameraProfile &profile, const T &dyn)
bool reconfigure_external_calibration_supported_
Definition: reconfigure.h:186
bool setNumberOfPulses(const uint32_t numPulses)
virtual Status getDeviceInfo(system::DeviceInfo &info)=0
#define REMOTE_HEAD_VPB()
void callback_bcam_imx104(multisense_ros::bcam_imx104Config &config, uint32_t level)
#define MONO_BM_IMU()
void configureGroundSurfaceParams(const T &dyn)
void setAutoExposureDecay(uint32_t d)
void callback_sl_bm_cmv2000_imu(multisense_ros::sl_bm_cmv2000_imuConfig &config, uint32_t level)
void configurePtp(const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::mono_cmv2000Config > > server_mono_cmv2000_
Definition: reconfigure.h:164
std::vector< crl::multisense::imu::Config > imu_configs_
Definition: reconfigure.h:151
std::function< void(double)> max_point_cloud_range_callback_
Definition: reconfigure.h:203
#define KS21_SGM_GROUND_SURFACE()
void configureS19Leds(const T &dyn)
void callback_remote_head_monocam_AR0234(multisense_ros::remote_head_monocam_AR0234Config &dyn, uint32_t level)
#define ROS_ERROR(...)
virtual Status getImageConfig(image::Config &c)=0
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_sgm_cmv4000_imuConfig > > server_sl_sgm_cmv4000_imu_
Definition: reconfigure.h:161
void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
void configureLeds(const T &dyn)
virtual Status getAuxImageConfig(image::AuxConfig &c)=0


multisense_ros
Author(s):
autogenerated on Sat Jun 24 2023 03:01:30