42                          std::function<
void (
BorderClip, 
double)> borderClipChangeCallback,
    43                          std::function<
void (
double)> maxPointCloudRangeCallback,
    47     resolution_change_callback_(resolutionChangeCallback),
    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),
    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)
    66     std::vector<system::DeviceMode> deviceModes;
    72     if (Status_Ok != status) {
    73         ROS_ERROR(
"Reconfigure: failed to query version info: %s",
    74                   Channel::statusString(status));
    79     if (Status_Ok != status) {
    80         ROS_ERROR(
"Reconfigure: failed to query device info: %s",
    81                   Channel::statusString(status));
    86     if (Status_Ok != status) {
    87         ROS_ERROR(
"Reconfigure: failed to query device modes: %s",
    88                   Channel::statusString(status));
    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); });
   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)
   119     if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_C6S2_S27 == deviceInfo.
hardwareRevision ||
   120         system::DeviceInfo::HARDWARE_REV_MULTISENSE_S30 == deviceInfo.
hardwareRevision)
   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.");
   145             std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::bcam_imx104Config> > (
   146                 new dynamic_reconfigure::Server<multisense_ros::bcam_imx104Config>(
device_nh_));
   148                                                    std::placeholders::_1, std::placeholders::_2));
   150     } 
else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_ST21 == deviceInfo.
hardwareRevision) {
   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_));
   156                                                 std::placeholders::_1, std::placeholders::_2));
   158     } 
else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_M == deviceInfo.
hardwareRevision) {
   161         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
   162         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
   165                 std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv2000Config> > (
   166                     new dynamic_reconfigure::Server<multisense_ros::mono_cmv2000Config>(
device_nh_));
   168                                                         std::placeholders::_1, std::placeholders::_2));
   171         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
   172         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
   175                 std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv4000Config> > (
   176                     new dynamic_reconfigure::Server<multisense_ros::mono_cmv4000Config>(
device_nh_));
   178                                                         std::placeholders::_1, std::placeholders::_2));
   182     } 
else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_C6S2_S27 == deviceInfo.
hardwareRevision ||
   183                system::DeviceInfo::HARDWARE_REV_MULTISENSE_S30 == deviceInfo.
hardwareRevision) {
   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));
   193                 std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config> > (
   194                     new dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config>(
device_nh_));
   196                                             std::placeholders::_1, std::placeholders::_2));
   198     } 
else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_KS21 == deviceInfo.
hardwareRevision) {
   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));
   208                 std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::ks21_sgm_AR0234Config> > (
   209                     new dynamic_reconfigure::Server<multisense_ros::ks21_sgm_AR0234Config>(
device_nh_));
   211                                                 std::placeholders::_1, std::placeholders::_2));
   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));
   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));
   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));
   242         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
   243         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
   246                 std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000Config> > (
   247                     new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000Config>(
device_nh_));
   249                                                          std::placeholders::_1, std::placeholders::_2));
   252         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
   253         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
   256                 std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000Config> > (
   257                     new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000Config>(
device_nh_));
   259                                                          std::placeholders::_1, std::placeholders::_2));
   271         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
   272         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
   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));
   281         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
   282         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
   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));
   300         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
   301         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
   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));
   310         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
   311         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
   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));
   319         case system::DeviceInfo::IMAGER_TYPE_AR0234_GREY:
   320         case system::DeviceInfo::IMAGER_TYPE_AR0239_COLOR:
   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));
   330                     std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config> > (
   331                         new dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config>(
device_nh_));
   333                                                 std::placeholders::_1, std::placeholders::_2));
   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()))
   374         if (Status_Ok != status) {
   375             ROS_ERROR(
"Reconfigure: failed to query sensor modes: %s",
   376                       Channel::statusString(status));
   384     bool supported = 
false;
   385     std::vector<system::DeviceMode>::const_iterator it = 
device_modes_.begin();
   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)) {
   399     if (
false == supported) {
   400         ROS_ERROR(
"Reconfigure: sensor does not support a resolution of: %dx%d (%d disparities)",
   401                   width, height, disparities);
   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,
   423     cfg.
setHdr(dyn.hdr_enable);
   440         if (Status_Ok != status) {
   441             ROS_ERROR(
"Reconfigure: failed to query aux image config: %s",
   442                       Channel::statusString(status));
   449         auxConfig.
setGain(dyn.aux_gain);
   450         auxConfig.
setExposure(dyn.aux_exposure_time * 1e6);
   457         if (dyn.aux_roi_auto_exposure) {
   462                 const int32_t maxX = dyn.__getMax__().aux_roi_auto_exposure_x;
   463                 const int32_t maxY = dyn.__getMax__().aux_roi_auto_exposure_y;
   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));
   469                                             fmax(0, fmin(dyn.aux_roi_auto_exposure_width, maxX - x)),
   470                                             fmax(0, fmin(dyn.aux_roi_auto_exposure_height, maxY - y)));
   472                 ROS_WARN(
"Reconfigure: ROI auto exposure is not supported with this firmware version");
   481         if (Status_Ok != status)
   482             ROS_ERROR(
"Reconfigure: failed to set aux image config: %s",
   483                       Channel::statusString(status));
   491     int32_t       width, height, disparities;
   492     bool          resolutionChange=
false;
   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());
   511         if (Status_Ok != status) {
   512             ROS_ERROR(
"Reconfigure: failed to get enabled streams: %s",
   513                       Channel::statusString(status));
   517         if (Status_Ok != status) {
   518             ROS_ERROR(
"Reconfigure: failed to stop streams for a resolution change: %s",
   519                       Channel::statusString(status));
   536     if (dyn.roi_auto_exposure) {
   541             const int32_t maxX = dyn.__getMax__().roi_auto_exposure_x;
   542             const int32_t maxY = dyn.__getMax__().roi_auto_exposure_y;
   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));
   548                                    fmax(0, fmin(dyn.roi_auto_exposure_width, maxX - x)),
   549                                    fmax(0, fmin(dyn.roi_auto_exposure_height, maxY - y)));
   551             ROS_WARN(
"Reconfigure: ROI auto exposure is not supported with this firmware version");
   562     if (Status_Ok != status)
   563         ROS_ERROR(
"Reconfigure: failed to set image config: %s",
   564                   Channel::statusString(status));
   567     if (Status_Ok != status)
   568         ROS_ERROR(
"Reconfigure: failed to query image config: %s",
   569                   Channel::statusString(status));
   576     if (resolutionChange) {
   578         if (Status_Ok != status)
   579             ROS_ERROR(
"Reconfigure: failed to restart streams after a resolution change: %s",
   580                       Channel::statusString(status));
   600     d.
delay = dyn.desired_transmit_delay;
   602     if (Status_Ok != status) {
   603         ROS_ERROR(
"Reconfigure: failed to set transmit delay: %s",
   604                   Channel::statusString(status));
   615         const float radiansPerSecondToRpm = 9.54929659643;
   618         if (Status_Ok != status) {
   619             if (Status_Unsupported == status)
   622                 ROS_ERROR(
"Reconfigure: failed to set motor speed: %s",
   623                           Channel::statusString(status));
   637         if (
false == dyn.lighting) {
   646         if (Status_Ok != status) {
   647             if (Status_Unsupported == status)
   650                 ROS_ERROR(
"Reconfigure: failed to set lighting config: %s",
   651                           Channel::statusString(status));
   665         if (
false == dyn.lighting) {
   677         if (Status_Ok != status) {
   678             if (Status_Unsupported == status)
   681                 ROS_ERROR(
"Reconfigure: failed to set lighting config: %s",
   682                           Channel::statusString(status));
   692         if (Status_Ok != status) {
   693             ROS_ERROR(
"Reconfigure: failed to query IMU config: %s",
   694                       Channel::statusString(status));
   699     std::vector<imu::Config> changedConfigs;
   700     std::vector<imu::Config>::iterator it = 
imu_configs_.begin();
   705         if (
"accelerometer" == c.
name &&
   706             (c.
enabled      != dyn.accelerometer_enabled ||
   710             c.
enabled         = dyn.accelerometer_enabled;
   713             changedConfigs.push_back(c);
   716         if (
"gyroscope" == c.
name &&
   717             (c.
enabled  != dyn.gyroscope_enabled ||
   721             c.
enabled         = dyn.gyroscope_enabled;
   724             changedConfigs.push_back(c);
   727         if (
"magnetometer" == c.
name &&
   728             (c.
enabled     != dyn.magnetometer_enabled ||
   732             c.
enabled         = dyn.magnetometer_enabled;
   735             changedConfigs.push_back(c);
   739     if (changedConfigs.size() > 0 ||
   742         ROS_WARN(
"Reconfigure: IMU configuration changes will take effect after all IMU "   743          "topic subscriptions have been closed.");
   750         if (Status_Ok != status) {
   751             ROS_ERROR(
"Reconfigure: failed to set IMU configuration: %s",
   752                       Channel::statusString(status));
   778         if (Status_Ok != status) {
   779             if (Status_Unsupported == status || Status_Unknown == status) {
   782                 ROS_ERROR(
"Reconfigure: enable PTP time synchronization: %s",
   783                           Channel::statusString(status));
   788     if (dyn.trigger_source != 3 ||  (
ptp_supported_ && dyn.trigger_source == 3)) {
   790         if (Status_Ok != status) {
   791             if (Status_Unsupported == status || Status_Unknown == status) {
   794                 ROS_ERROR(
"Reconfigure: failed to set trigger source: %s",
   795                           Channel::statusString(status));
   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) {
   847         if (Status_Ok != status) {
   848                 ROS_ERROR(
"Reconfigure: failed to set external calibration: %s",
   849                             Channel::statusString(status));
   867     if (dyn.ground_surface_pre_transform_data == 
"Quadratic")
   869     else if (dyn.ground_surface_pre_transform_data == 
"Mean")
   871     else if (dyn.ground_surface_pre_transform_data == 
"Zero")
   890     if (Status_Ok != status) {
   891             ROS_ERROR(
"Reconfigure: failed to set ground surface params: %s",
   892                         Channel::statusString(status));
   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}
   908 #define GET_CONFIG()                                                    \   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));                       \   917 #define SL_BM()  do {                                           \   919         configureAutoWhiteBalance(cfg, dyn);                    \   920         configureCamera(cfg, dyn);                              \   921         configureMotor(dyn);                                    \   922         configureLeds(dyn);                                     \   923         configureBorderClip(dyn);                               \   924         configurePointCloudRange(dyn);                          \   925         configureExtrinsics(dyn);                               \   928 #define SL_BM_IMU()  do {                                       \   930         configureAutoWhiteBalance(cfg, dyn);                    \   931         configureCamera(cfg, dyn);                              \   932         configureMotor(dyn);                                    \   933         configureLeds(dyn);                                     \   935         configureBorderClip(dyn);                               \   936         configurePointCloudRange(dyn);                          \   937         configureExtrinsics(dyn);                               \   940 #define MONO_BM_IMU()  do {                                     \   942         configureAutoWhiteBalance(cfg, dyn);                    \   943         configureCamera(cfg, dyn);                              \   944         configureLeds(dyn);                                     \   946         configureExtrinsics(dyn);                               \   949 #define SL_SGM_IMU()  do {                                      \   951         configureSgm(cfg, dyn);                                 \   952         configureHdr(cfg, dyn);                                 \   953         configureAutoWhiteBalance(cfg, dyn);                    \   954         configureCamera(cfg, dyn);                              \   955         configureMotor(dyn);                                    \   956         configureLeds(dyn);                                     \   958         configureBorderClip(dyn);                               \   959         configurePointCloudRange(dyn);                          \   960         configureExtrinsics(dyn);                               \   963 #define SL_SGM()  do {                                          \   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);                               \   974 #define SL_SGM_IMU_CMV4000()  do {                              \   976         configureSgm(cfg, dyn);                                 \   977         configureHdr(cfg, dyn);                                 \   978         configureAutoWhiteBalance(cfg, dyn);                    \   979         configureCamera(cfg, dyn);                              \   980         configureMotor(dyn);                                    \   981         configureLeds(dyn);                                     \   983         configureBorderClip(dyn);                               \   984         configurePointCloudRange(dyn);                          \   985         configureExtrinsics(dyn);                               \   988 #define S27_SGM()  do {                                         \   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);                               \  1005 #define KS21_SGM()  do {                                        \  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);                               \  1020 #define S27_SGM_GROUND_SURFACE()  do {                          \  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);                      \  1039 #define KS21_SGM_GROUND_SURFACE()  do {                         \  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);                      \  1056 #define REMOTE_HEAD_VPB()  do {                                 \  1058         configurePtp(dyn);                                      \  1059         configureExtrinsics(dyn);                               \  1062 #define REMOTE_HEAD_SGM_AR0234()  do {                          \  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);                               \  1077 #define REMOTE_HEAD_SGM_AR0234_GROUND_SURFACE()  do {           \  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);                      \  1094 #define REMOTE_HEAD_MONOCAM_AR0234()  do {                      \  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);                               \  1136     int32_t     width, height;
  1137     bool        resolutionChange=
false;
  1142     if (2 != sscanf(dyn.resolution.c_str(), 
"%dx%dx", &width, &height)) {
  1143         ROS_ERROR(
"Reconfigure: malformed resolution string: \"%s\"", dyn.resolution.c_str());
  1156         if (Status_Ok != status) {
  1157             ROS_ERROR(
"Reconfigure: failed to get enabled streams: %s",
  1158                       Channel::statusString(status));
  1162         if (Status_Ok != status) {
  1163             ROS_ERROR(
"Reconfigure: failed to stop streams for a resolution change: %s",
  1164                       Channel::statusString(status));
  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);
  1189     if (Status_Ok != status)
  1190         ROS_ERROR(
"Reconfigure: failed to set image config: %s",
  1191                   Channel::statusString(status));
  1194     if (Status_Ok != status)
  1195         ROS_ERROR(
"Reconfigure: failed to query image config: %s",
  1196                   Channel::statusString(status));
  1203     if (resolutionChange) {
  1206         if (Status_Ok != status)
  1207             ROS_ERROR(
"Reconfigure: failed to restart streams after a resolution change: %s",
  1208                       Channel::statusString(status));
  1222     int32_t       width, height, disparities;
  1223     bool          resolutionChange=
false;
  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());
  1238     if ((resolutionChange = 
changeResolution(cfg, width, height, disparities))) {
  1244         if (Status_Ok != status) {
  1245             ROS_ERROR(
"Reconfigure: failed to get enabled streams: %s",
  1246                       Channel::statusString(status));
  1250         if (Status_Ok != status) {
  1251             ROS_ERROR(
"Reconfigure: failed to stop streams for a resolution change: %s",
  1252                       Channel::statusString(status));
  1257     cfg.setFps(dyn.fps);
  1266     if (Status_Ok != status)
  1267         ROS_ERROR(
"Reconfigure: failed to set image config: %s",
  1268                   Channel::statusString(status));
  1271     if (Status_Ok != status)
  1272         ROS_ERROR(
"Reconfigure: failed to query image config: %s",
  1273                   Channel::statusString(status));
  1280     if (resolutionChange) {
  1283         if (Status_Ok != status)
  1284             ROS_ERROR(
"Reconfigure: failed to restart streams after a resolution change: %s",
  1285                       Channel::statusString(status));
 virtual Status startStreams(DataSource mask)=0
void setStereoPostFilterStrength(float s)
static CRL_CONSTEXPR CameraProfile Full_Res_Aux_Cam
float ground_surface_pointcloud_grid_size
virtual Status getEnabledStreams(DataSource &mask)=0
void setAutoExposure(bool e)
virtual Status setMotorSpeed(float rpm)=0
void setAutoExposureTargetIntensity(float d)
void setAutoWhiteBalanceThresh(float t)
float ground_surface_pointcloud_max_range_m
static CRL_CONSTEXPR CameraProfile Detail_Disparity
void setAutoWhiteBalanceDecay(uint32_t d)
virtual Status setGroundSurfaceParams(const system::GroundSurfaceParams ¶ms)=0
float ground_surface_obstacle_height_thresh_m
virtual Status stopStreams(DataSource mask)=0
static CRL_CONSTEXPR CameraProfile Show_ROIs
float ground_surface_adjacent_cell_search_size_m
void setResolution(uint32_t w, uint32_t h)
virtual Status networkTimeSynchronization(bool enabled)=0
bool setDutyCycle(float percent)
virtual Status ptpTimeSynchronization(bool enabled)=0
virtual Status setExternalCalibration(const system::ExternalCalibration &calibration)=0
int ground_surface_number_of_levels_z
virtual Status getVersionInfo(system::VersionInfo &v)=0
virtual Status getImuConfig(uint32_t &samplesPerMessage, std::vector< imu::Config > &c)=0
float ground_surface_pointcloud_min_range_m
float ground_surface_pointcloud_max_width_m
float ground_surface_pointcloud_max_height_m
void setAutoExposureDecay(uint32_t d)
virtual Status setImuConfig(bool storeSettingsInFlash, uint32_t samplesPerMessage, const std::vector< imu::Config > &c)=0
bool setInvertPulse(const bool invert)
void setExposure(uint32_t e)
virtual Status setTriggerSource(TriggerSource s)=0
void setFlash(bool onOff)
Struct containing parameters for drawing a pointcloud representation of a B-Spline model...
uint32_t hardwareRevision
void setAutoExposureMax(uint32_t m)
virtual Status getDeviceModes(std::vector< system::DeviceMode > &m)=0
void setAutoExposure(bool e)
void setDisparities(uint32_t d)
float ground_surface_obstacle_percentage_thresh
virtual Status setLightingConfig(const lighting::Config &c)=0
void setExposure(uint32_t e)
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)
int ground_surface_min_points_per_grid
int ground_surface_number_of_levels_x
VersionType sensorFirmwareVersion
int ground_surface_base_model
void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
virtual Status setAuxImageConfig(const image::AuxConfig &c)=0
float ground_surface_pointcloud_min_height_m
virtual Status setTransmitDelay(const image::TransmitDelay &c)=0
uint32_t disparities() const
bool setStartupTime(uint32_t ledTransientResponse_us)
static CRL_CONSTEXPR CameraProfile Ground_Surface
float ground_surface_pointcloud_min_width_m
bool setNumberOfPulses(const uint32_t numPulses)
virtual Status getDeviceInfo(system::DeviceInfo &info)=0
void setAutoExposureDecay(uint32_t d)
int ground_surface_max_fitting_iterations
void setAutoWhiteBalance(bool e)
void setAutoExposureThresh(float t)
virtual Status getImageConfig(image::Config &c)=0
void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
int ground_surface_pointcloud_decimation
virtual Status getAuxImageConfig(image::AuxConfig &c)=0
void setAutoExposureThresh(float t)