reconfigure.cpp
Go to the documentation of this file.
00001 
00034 #include <multisense_ros/reconfigure.h>
00035 
00036 using namespace crl::multisense;
00037 
00038 namespace multisense_ros {
00039 
00040 Reconfigure::Reconfigure(Channel* driver,
00041                          boost::function<void ()> resolutionChangeCallback,
00042                          boost::function<void (int, int)> borderClipChangeCallback) :
00043     driver_(driver),
00044     resolution_change_callback_(resolutionChangeCallback),
00045     device_nh_(""),
00046     device_modes_(),
00047     imu_samples_per_message_(0),
00048     imu_configs_(),
00049     server_sl_bm_cmv2000_(),
00050     server_sl_bm_cmv2000_imu_(),
00051     server_sl_bm_cmv4000_(),
00052     server_sl_bm_cmv4000_imu_(),
00053     server_sl_sgm_cmv2000_imu_(),
00054     server_sl_sgm_cmv4000_imu_(),
00055     server_bcam_imx104_(),
00056     server_st21_vga_(),
00057     lighting_supported_(true),
00058     motor_supported_(true),
00059     border_clip_type_(RECTANGULAR),
00060     border_clip_value_(0.0),
00061     border_clip_change_callback_(borderClipChangeCallback)
00062 {
00063     system::DeviceInfo  deviceInfo;
00064     system::VersionInfo versionInfo;
00065 
00066     //
00067     // Query device and version information from sensor
00068 
00069     Status status = driver_->getVersionInfo(versionInfo);
00070     if (Status_Ok != status) {
00071         ROS_ERROR("Reconfigure: failed to query version info: %s",
00072                   Channel::statusString(status));
00073         return;
00074     }
00075     status = driver_->getDeviceInfo(deviceInfo);
00076     if (Status_Ok != status) {
00077         ROS_ERROR("Reconfigure: failed to query device info: %s",
00078                   Channel::statusString(status));
00079         return;
00080     }
00081 
00082     //
00083     // Launch the correct reconfigure server for this device configuration.
00084 
00085     if (system::DeviceInfo::HARDWARE_REV_BCAM == deviceInfo.hardwareRevision) {
00086 
00087         server_bcam_imx104_ =
00088             boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::bcam_imx104Config> > (
00089                 new dynamic_reconfigure::Server<multisense_ros::bcam_imx104Config>(device_nh_));
00090         server_bcam_imx104_->setCallback(boost::bind(&Reconfigure::callback_bcam_imx104, this, _1, _2));
00091 
00092     } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_ST21 == deviceInfo.hardwareRevision) {
00093 
00094         server_st21_vga_ =
00095             boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::st21_sgm_vga_imuConfig> > (
00096                 new dynamic_reconfigure::Server<multisense_ros::st21_sgm_vga_imuConfig>(device_nh_));
00097         server_st21_vga_->setCallback(boost::bind(&Reconfigure::callback_st21_vga, this, _1, _2));
00098 
00099     } else if (system::DeviceInfo::HARDWARE_REV_MULTISENSE_M == deviceInfo.hardwareRevision) {
00100 
00101         switch(deviceInfo.imagerType) {
00102         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
00103         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
00104 
00105             server_mono_cmv2000_ =
00106                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv2000Config> > (
00107                     new dynamic_reconfigure::Server<multisense_ros::mono_cmv2000Config>(device_nh_));
00108             server_mono_cmv2000_->setCallback(boost::bind(&Reconfigure::callback_mono_cmv2000, this, _1, _2));
00109 
00110             break;
00111         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
00112         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
00113 
00114             server_mono_cmv4000_ =
00115                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv4000Config> > (
00116                     new dynamic_reconfigure::Server<multisense_ros::mono_cmv4000Config>(device_nh_));
00117             server_mono_cmv4000_->setCallback(boost::bind(&Reconfigure::callback_mono_cmv4000, this, _1, _2));
00118 
00119             break;
00120         }
00121 
00122     } else if (versionInfo.sensorFirmwareVersion <= 0x0202) {
00123 
00124         switch(deviceInfo.imagerType) {
00125         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
00126         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
00127 
00128             server_sl_bm_cmv2000_ =
00129                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000Config> > (
00130                     new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000Config>(device_nh_));
00131             server_sl_bm_cmv2000_->setCallback(boost::bind(&Reconfigure::callback_sl_bm_cmv2000, this, _1, _2));
00132 
00133             break;
00134         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
00135         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
00136 
00137             server_sl_bm_cmv4000_ =
00138                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000Config> > (
00139                     new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000Config>(device_nh_));
00140             server_sl_bm_cmv4000_->setCallback(boost::bind(&Reconfigure::callback_sl_bm_cmv4000, this, _1, _2));
00141 
00142             break;
00143         default:
00144 
00145             ROS_ERROR("Reconfigure: unsupported imager type \"%d\"", deviceInfo.imagerType);
00146             return;
00147         }
00148 
00149     } else if (versionInfo.sensorFirmwareVersion < 0x0300) {
00150 
00151         switch(deviceInfo.imagerType) {
00152         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
00153         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
00154 
00155             server_sl_bm_cmv2000_imu_ =
00156                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000_imuConfig> > (
00157                     new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000_imuConfig>(device_nh_));
00158             server_sl_bm_cmv2000_imu_->setCallback(boost::bind(&Reconfigure::callback_sl_bm_cmv2000_imu, this, _1, _2));
00159 
00160             break;
00161         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
00162         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
00163 
00164             server_sl_bm_cmv4000_imu_ =
00165                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000_imuConfig> > (
00166                     new dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000_imuConfig>(device_nh_));
00167             server_sl_bm_cmv4000_imu_->setCallback(boost::bind(&Reconfigure::callback_sl_bm_cmv4000_imu, this, _1, _2));
00168 
00169             break;
00170         default:
00171 
00172             ROS_ERROR("Reconfigure: unsupported imager type \"%d\"", deviceInfo.imagerType);
00173             return;
00174         }
00175 
00176     } else {
00177 
00178         switch(deviceInfo.imagerType) {
00179         case system::DeviceInfo::IMAGER_TYPE_CMV2000_GREY:
00180         case system::DeviceInfo::IMAGER_TYPE_CMV2000_COLOR:
00181 
00182             server_sl_sgm_cmv2000_imu_ =
00183                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv2000_imuConfig> > (
00184                     new dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv2000_imuConfig>(device_nh_));
00185             server_sl_sgm_cmv2000_imu_->setCallback(boost::bind(&Reconfigure::callback_sl_sgm_cmv2000_imu, this, _1, _2));
00186 
00187             break;
00188         case system::DeviceInfo::IMAGER_TYPE_CMV4000_GREY:
00189         case system::DeviceInfo::IMAGER_TYPE_CMV4000_COLOR:
00190 
00191             server_sl_sgm_cmv4000_imu_ =
00192                 boost::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv4000_imuConfig> > (
00193                     new dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv4000_imuConfig>(device_nh_));
00194             server_sl_sgm_cmv4000_imu_->setCallback(boost::bind(&Reconfigure::callback_sl_sgm_cmv4000_imu, this, _1, _2));
00195 
00196             break;
00197         default:
00198 
00199             ROS_ERROR("Reconfigure: unsupported imager type \"%d\"", deviceInfo.imagerType);
00200             return;
00201         }
00202     }
00203 }
00204 
00205 Reconfigure::~Reconfigure()
00206 {
00207 }
00208 
00209 //
00210 // Helper to change resolution. Will check against supported device modes
00211 
00212 bool Reconfigure::changeResolution(image::Config& cfg,
00213                                    int32_t        width,
00214                                    int32_t        height,
00215                                    int32_t        disparities)
00216 {
00217     //
00218     // See if we need to change resolutions
00219 
00220     if (width       == static_cast<int32_t>(cfg.width())   &&
00221         height      == static_cast<int32_t>(cfg.height())  &&
00222         disparities == static_cast<int32_t>(cfg.disparities()))
00223         return false;
00224 
00225     //
00226     // Query all supported resolutions from the sensor, if we haven't already
00227 
00228     if (device_modes_.empty()) {
00229 
00230         Status status = driver_->getDeviceModes(device_modes_);
00231         if (Status_Ok != status) {
00232             ROS_ERROR("Reconfigure: failed to query sensor modes: %s",
00233                       Channel::statusString(status));
00234             return false;
00235         }
00236     }
00237 
00238     //
00239     // Verify that this resolution is supported
00240 
00241     bool supported = false;
00242     std::vector<system::DeviceMode>::const_iterator it = device_modes_.begin();
00243     for(; it != device_modes_.end(); ++it) {
00244 
00245         const system::DeviceMode& m = *it;
00246 
00247         if (width       == static_cast<int32_t>(m.width)  &&
00248             height      == static_cast<int32_t>(m.height) &&
00249             disparities == static_cast<int32_t>(m.disparities)) {
00250 
00251             supported = true;
00252             break;
00253         }
00254     }
00255 
00256     if (false == supported) {
00257         ROS_ERROR("Reconfigure: sensor does not support a resolution of: %dx%d (%d disparities)",
00258                   width, height, disparities);
00259         return false;
00260     }
00261 
00262     ROS_WARN("Reconfigure: changing sensor resolution to %dx%d (%d disparities), from %dx%d "
00263              "(%d disparities): reconfiguration may take up to 30 seconds",
00264              width, height, disparities,
00265              cfg.width(), cfg.height(), cfg.disparities());
00266 
00267     cfg.setResolution(width, height);
00268     cfg.setDisparities(disparities);
00269 
00270     return true;
00271 }
00272 
00273 template<class T> void Reconfigure::configureSgm(image::Config& cfg, const T& dyn)
00274 {
00275     cfg.setStereoPostFilterStrength(dyn.stereo_post_filtering);
00276 }
00277 
00278 template<class T> void Reconfigure::configureCamera(image::Config& cfg, const T& dyn)
00279 {
00280     DataSource    streamsEnabled = 0;
00281     int32_t       width, height, disparities;
00282     bool          resolutionChange=false;
00283     Status        status=Status_Ok;
00284 
00285     //
00286     // Decode the resolution string
00287 
00288     if (3 != sscanf(dyn.resolution.c_str(), "%dx%dx%d", &width, &height, &disparities)) {
00289         ROS_ERROR("Reconfigure: malformed resolution string: \"%s\"", dyn.resolution.c_str());
00290         return;
00291     }
00292 
00293     //
00294     // If a resolution change is desired
00295 
00296     if ((resolutionChange = changeResolution(cfg, width, height, disparities))) {
00297 
00298         //
00299         // Halt streams during the resolution change
00300 
00301         status = driver_->getEnabledStreams(streamsEnabled);
00302         if (Status_Ok != status) {
00303             ROS_ERROR("Reconfigure: failed to get enabled streams: %s",
00304                       Channel::statusString(status));
00305             return;
00306         }
00307         status = driver_->stopStreams(streamsEnabled);
00308         if (Status_Ok != status) {
00309             ROS_ERROR("Reconfigure: failed to stop streams for a resolution change: %s",
00310                       Channel::statusString(status));
00311             return;
00312         }
00313     }
00314 
00315     //
00316     // Set all other image config from dynamic reconfigure
00317 
00318     cfg.setFps(dyn.fps);
00319     cfg.setGain(dyn.gain);
00320     cfg.setExposure(dyn.exposure_time * 1e6);
00321     cfg.setAutoExposure(dyn.auto_exposure);
00322     cfg.setAutoExposureMax(dyn.auto_exposure_max_time * 1e6);
00323     cfg.setAutoExposureDecay(dyn.auto_exposure_decay);
00324     cfg.setAutoExposureThresh(dyn.auto_exposure_thresh);
00325     cfg.setWhiteBalance(dyn.white_balance_red,
00326                         dyn.white_balance_blue);
00327     cfg.setAutoWhiteBalance(dyn.auto_white_balance);
00328     cfg.setAutoWhiteBalanceDecay(dyn.auto_white_balance_decay);
00329     cfg.setAutoWhiteBalanceThresh(dyn.auto_white_balance_thresh);
00330     cfg.setHdr(dyn.hdr_enable);
00331 
00332     //
00333     // Apply, sensor enforces limits per setting.
00334 
00335     status = driver_->setImageConfig(cfg);
00336     if (Status_Ok != status)
00337         ROS_ERROR("Reconfigure: failed to set image config: %s",
00338                   Channel::statusString(status));
00339 
00340     //
00341     // If we are changing the resolution, let others know about it
00342 
00343     if (resolutionChange) {
00344 
00345         if (false == resolution_change_callback_.empty())
00346             resolution_change_callback_();
00347 
00348         status = driver_->startStreams(streamsEnabled);
00349         if (Status_Ok != status)
00350             ROS_ERROR("Reconfigure: failed to restart streams after a resolution change: %s",
00351                       Channel::statusString(status));
00352     }
00353 
00354     //
00355     // Send the desired motor speed
00356 
00357     if (motor_supported_) {
00358 
00359         const float radiansPerSecondToRpm = 9.54929659643;
00360 
00361         status = driver_->setMotorSpeed(radiansPerSecondToRpm * dyn.motor_speed);
00362         if (Status_Ok != status) {
00363             if (Status_Unsupported == status)
00364                 motor_supported_ = false;
00365             else
00366                 ROS_ERROR("Reconfigure: failed to set motor speed: %s",
00367                           Channel::statusString(status));
00368         }
00369     }
00370 
00371     //
00372     // Send the desired lighting configuration
00373 
00374     if (lighting_supported_) {
00375 
00376         lighting::Config leds;
00377 
00378         if (false == dyn.lighting) {
00379             leds.setFlash(false);
00380             leds.setDutyCycle(0.0);
00381         } else {
00382             leds.setFlash(dyn.flash);
00383             leds.setDutyCycle(dyn.led_duty_cycle * 100.0);
00384         }
00385 
00386         status = driver_->setLightingConfig(leds);
00387         if (Status_Ok != status) {
00388             if (Status_Unsupported == status)
00389                 lighting_supported_ = false;
00390             else
00391                 ROS_ERROR("Reconfigure: failed to set lighting config: %s",
00392                           Channel::statusString(status));
00393         }
00394     }
00395 
00396     //
00397     // Enable/disable network-based time synchronization.
00398     //
00399     // If enabled, sensor timestamps will be reported in the local
00400     // system clock's frame, using a continuously updated offset from
00401     // the sensor's internal clock.
00402     //
00403     // If disabled, sensor timestamps will be reported in the sensor
00404     // clock's frame, which is free-running from zero on power up.
00405     //
00406     // Enabled by default.
00407 
00408     driver_->networkTimeSynchronization(dyn.network_time_sync);
00409 }
00410 
00411 template<class T> void Reconfigure::configureImu(const T& dyn)
00412 {
00413     if (imu_configs_.empty()) {
00414         Status status = driver_->getImuConfig(imu_samples_per_message_,
00415                                               imu_configs_);
00416         if (Status_Ok != status) {
00417             ROS_ERROR("Reconfigure: failed to query IMU config: %s",
00418                       Channel::statusString(status));
00419             return;
00420         }
00421     }
00422 
00423     std::vector<imu::Config> changedConfigs;
00424     std::vector<imu::Config>::iterator it = imu_configs_.begin();
00425     for(; it!=imu_configs_.end(); ++it) {
00426 
00427         imu::Config& c = *it;
00428 
00429         if ("accelerometer" == c.name &&
00430             (c.enabled      != dyn.accelerometer_enabled ||
00431              static_cast<int>(c.rateTableIndex)  != dyn.accelerometer_rate    ||
00432              static_cast<int>(c.rangeTableIndex) != dyn.accelerometer_range)) {
00433 
00434             c.enabled         = dyn.accelerometer_enabled;
00435             c.rateTableIndex  = dyn.accelerometer_rate;
00436             c.rangeTableIndex = dyn.accelerometer_range;
00437             changedConfigs.push_back(c);
00438         }
00439 
00440         if ("gyroscope" == c.name &&
00441             (c.enabled  != dyn.gyroscope_enabled ||
00442              static_cast<int>(c.rateTableIndex)  != dyn.gyroscope_rate    ||
00443              static_cast<int>(c.rangeTableIndex) != dyn.gyroscope_range)) {
00444 
00445             c.enabled         = dyn.gyroscope_enabled;
00446             c.rateTableIndex  = dyn.gyroscope_rate;
00447             c.rangeTableIndex = dyn.gyroscope_range;
00448             changedConfigs.push_back(c);
00449         }
00450 
00451         if ("magnetometer" == c.name &&
00452             (c.enabled     != dyn.magnetometer_enabled ||
00453              static_cast<int>(c.rateTableIndex)  != dyn.magnetometer_rate    ||
00454              static_cast<int>(c.rangeTableIndex) != dyn.magnetometer_range)) {
00455 
00456             c.enabled         = dyn.magnetometer_enabled;
00457             c.rateTableIndex  = dyn.magnetometer_rate;
00458             c.rangeTableIndex = dyn.magnetometer_range;
00459             changedConfigs.push_back(c);
00460         }
00461     }
00462 
00463     if (changedConfigs.size() > 0 ||
00464         static_cast<int>(imu_samples_per_message_) != dyn.imu_samples_per_message) {
00465 
00466         ROS_WARN("Reconfigure: IMU configuration changes will take effect after all IMU "
00467                  "topic subscriptions have been closed.");
00468 
00469         imu_samples_per_message_ = dyn.imu_samples_per_message;
00470 
00471         Status status = driver_->setImuConfig(false, // store in non-volatile flash
00472                                               imu_samples_per_message_,
00473                                               changedConfigs);  // can be empty
00474         if (Status_Ok != status) {
00475             ROS_ERROR("Reconfigure: failed to set IMU configuration: %s",
00476                       Channel::statusString(status));
00477             imu_configs_.clear();
00478         }
00479     }
00480 }
00481 
00482 template<class T> void Reconfigure::configureBorderClip(const T& dyn)
00483 {
00484     bool regenerate = false;
00485 
00486     if (dyn.border_clip_type != border_clip_type_)
00487     {
00488         border_clip_type_ = dyn.border_clip_type;
00489         regenerate = true;
00490     }
00491 
00492     if (dyn.border_clip_value != border_clip_value_)
00493     {
00494         border_clip_value_ = dyn.border_clip_value;
00495         regenerate = true;
00496     }
00497 
00498     if (regenerate)
00499     {
00500         if (false == border_clip_change_callback_.empty())
00501         {
00502             border_clip_change_callback_(dyn.border_clip_type, dyn.border_clip_value);
00503         }
00504     }
00505 }
00506 
00507 
00508 #define GET_CONFIG()                                                    \
00509     image::Config cfg;                                                  \
00510     Status status = driver_->getImageConfig(cfg);                       \
00511     if (Status_Ok != status) {                                          \
00512         ROS_ERROR("Reconfigure: failed to query image config: %s",      \
00513                   Channel::statusString(status));                       \
00514         return;                                                         \
00515     }                                                                   \
00516 
00517 #define SL_BM()  do {                                           \
00518         GET_CONFIG();                                           \
00519         configureCamera(cfg, dyn);                              \
00520         configureBorderClip(dyn);                               \
00521     } while(0)
00522 
00523 #define SL_BM_IMU()  do {                                       \
00524         GET_CONFIG();                                           \
00525         configureCamera(cfg, dyn);                              \
00526         configureImu(dyn);                                      \
00527         configureBorderClip(dyn);                               \
00528     } while(0)
00529 
00530 #define SL_SGM_IMU()  do {                                      \
00531         GET_CONFIG();                                           \
00532         configureSgm(cfg, dyn);                                 \
00533         configureCamera(cfg, dyn);                              \
00534         configureImu(dyn);                                      \
00535         configureBorderClip(dyn);                               \
00536     } while(0)
00537 
00538 
00539 
00540 //
00541 // The dynamic reconfigure callbacks (MultiSense S* variations)
00542 
00543 void Reconfigure::callback_sl_bm_cmv2000      (multisense_ros::sl_bm_cmv2000Config&      dyn, uint32_t level) { SL_BM();       };
00544 void Reconfigure::callback_sl_bm_cmv2000_imu  (multisense_ros::sl_bm_cmv2000_imuConfig&  dyn, uint32_t level) { SL_BM_IMU();   };
00545 void Reconfigure::callback_sl_bm_cmv4000      (multisense_ros::sl_bm_cmv4000Config&      dyn, uint32_t level) { SL_BM();       };
00546 void Reconfigure::callback_sl_bm_cmv4000_imu  (multisense_ros::sl_bm_cmv4000_imuConfig&  dyn, uint32_t level) { SL_BM_IMU();   };
00547 void Reconfigure::callback_sl_sgm_cmv2000_imu (multisense_ros::sl_sgm_cmv2000_imuConfig& dyn, uint32_t level) { SL_SGM_IMU();  };
00548 void Reconfigure::callback_sl_sgm_cmv4000_imu (multisense_ros::sl_sgm_cmv4000_imuConfig& dyn, uint32_t level) { SL_SGM_IMU();  };
00549 void Reconfigure::callback_mono_cmv2000       (multisense_ros::mono_cmv2000Config&       dyn, uint32_t level) { SL_BM_IMU();   };
00550 void Reconfigure::callback_mono_cmv4000       (multisense_ros::mono_cmv4000Config&       dyn, uint32_t level) { SL_BM_IMU();   };
00551 
00552 //
00553 // BCAM (Sony IMX104)
00554 
00555 void Reconfigure::callback_bcam_imx104(multisense_ros::bcam_imx104Config& dyn,
00556                                        uint32_t                           level)
00557 {
00558     GET_CONFIG();
00559     DataSource  streamsEnabled = 0;
00560     int32_t     width, height;
00561     bool        resolutionChange=false;
00562 
00563     //
00564     // Decode the resolution string
00565 
00566     if (2 != sscanf(dyn.resolution.c_str(), "%dx%dx", &width, &height)) {
00567         ROS_ERROR("Reconfigure: malformed resolution string: \"%s\"", dyn.resolution.c_str());
00568         return;
00569     }
00570 
00571     //
00572     // If a resolution change is desired
00573 
00574     if ((resolutionChange = changeResolution(cfg, width, height, 0))) {
00575 
00576         //
00577         // Halt streams during the resolution change
00578 
00579         status = driver_->getEnabledStreams(streamsEnabled);
00580         if (Status_Ok != status) {
00581             ROS_ERROR("Reconfigure: failed to get enabled streams: %s",
00582                       Channel::statusString(status));
00583             return;
00584         }
00585         status = driver_->stopStreams(streamsEnabled);
00586         if (Status_Ok != status) {
00587             ROS_ERROR("Reconfigure: failed to stop streams for a resolution change: %s",
00588                       Channel::statusString(status));
00589             return;
00590         }
00591     }
00592 
00593     //
00594     // Set all other image config from dynamic reconfigure
00595 
00596     cfg.setFps(static_cast<float>(dyn.fps));
00597     cfg.setGain(dyn.gain);
00598     cfg.setExposure(dyn.exposure_time * 1e6);
00599     cfg.setAutoExposure(dyn.auto_exposure);
00600     cfg.setAutoExposureMax(dyn.auto_exposure_max_time * 1e6);
00601     cfg.setAutoExposureDecay(dyn.auto_exposure_decay);
00602     cfg.setAutoExposureThresh(dyn.auto_exposure_thresh);
00603     cfg.setWhiteBalance(dyn.white_balance_red,
00604                         dyn.white_balance_blue);
00605     cfg.setAutoWhiteBalance(dyn.auto_white_balance);
00606     cfg.setAutoWhiteBalanceDecay(dyn.auto_white_balance_decay);
00607     cfg.setAutoWhiteBalanceThresh(dyn.auto_white_balance_thresh);
00608 
00609     //
00610     // Apply, sensor enforces limits per setting.
00611 
00612     status = driver_->setImageConfig(cfg);
00613     if (Status_Ok != status)
00614         ROS_ERROR("Reconfigure: failed to set image config: %s",
00615                   Channel::statusString(status));
00616 
00617     //
00618     // If we are changing the resolution, let others know about it
00619 
00620     if (resolutionChange) {
00621 
00622         if (false == resolution_change_callback_.empty())
00623             resolution_change_callback_();
00624 
00625         status = driver_->startStreams(streamsEnabled);
00626         if (Status_Ok != status)
00627             ROS_ERROR("Reconfigure: failed to restart streams after a resolution change: %s",
00628                       Channel::statusString(status));
00629     }
00630 }
00631 
00632 //
00633 // ST21 FLIR Thermal Imagers
00634 // Seperate callback required due to limited subset of dyn parameters
00635 // in st21_sgm_vga_imuConfig. configureCamera results in SFINAE errors
00636 
00637 void Reconfigure::callback_st21_vga(multisense_ros::st21_sgm_vga_imuConfig& dyn,
00638                                        uint32_t                           level)
00639 {
00640 
00641     DataSource    streamsEnabled = 0;
00642     int32_t       width, height, disparities;
00643     bool          resolutionChange=false;
00644 
00645     GET_CONFIG();
00646 
00647     //
00648     // Decode the resolution string
00649 
00650     if (3 != sscanf(dyn.resolution.c_str(), "%dx%dx%d", &width, &height, &disparities)) {
00651         ROS_ERROR("Reconfigure: malformed resolution string: \"%s\"", dyn.resolution.c_str());
00652         return;
00653     }
00654 
00655     //
00656     // If a resolution change is desired
00657 
00658     if ((resolutionChange = changeResolution(cfg, width, height, disparities))) {
00659 
00660         //
00661         // Halt streams during the resolution change
00662 
00663         status = driver_->getEnabledStreams(streamsEnabled);
00664         if (Status_Ok != status) {
00665             ROS_ERROR("Reconfigure: failed to get enabled streams: %s",
00666                       Channel::statusString(status));
00667             return;
00668         }
00669         status = driver_->stopStreams(streamsEnabled);
00670         if (Status_Ok != status) {
00671             ROS_ERROR("Reconfigure: failed to stop streams for a resolution change: %s",
00672                       Channel::statusString(status));
00673             return;
00674         }
00675     }
00676 
00677     cfg.setFps(dyn.fps);
00678 
00679     configureSgm(cfg, dyn);
00680     configureImu(dyn);
00681 
00682     //
00683     // Apply, sensor enforces limits per setting.
00684 
00685     status = driver_->setImageConfig(cfg);
00686     if (Status_Ok != status)
00687         ROS_ERROR("Reconfigure: failed to set image config: %s",
00688                   Channel::statusString(status));
00689 
00690     //
00691     // If we are changing the resolution, let others know about it
00692 
00693     if (resolutionChange) {
00694 
00695         if (false == resolution_change_callback_.empty())
00696             resolution_change_callback_();
00697 
00698         status = driver_->startStreams(streamsEnabled);
00699         if (Status_Ok != status)
00700             ROS_ERROR("Reconfigure: failed to restart streams after a resolution change: %s",
00701                       Channel::statusString(status));
00702     }
00703 
00704     configureBorderClip(dyn);
00705 }
00706 
00707 } // namespace


multisense_ros
Author(s):
autogenerated on Thu Aug 27 2015 14:01:22