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


multisense_ros
Author(s):
autogenerated on Thu Feb 20 2025 03:51:03