reconfigure.h
Go to the documentation of this file.
1 
34 #ifndef MULTISENSE_ROS_RECONFIGURE_H
35 #define MULTISENSE_ROS_RECONFIGURE_H
36 
37 #include <ros/ros.h>
38 
39 #include <multisense_lib/MultiSenseChannel.hh>
40 
41 #include <dynamic_reconfigure/server.h>
42 #include <multisense_ros/sl_bm_cmv2000Config.h>
43 #include <multisense_ros/sl_bm_cmv2000_imuConfig.h>
44 #include <multisense_ros/sl_bm_cmv4000Config.h>
45 #include <multisense_ros/sl_bm_cmv4000_imuConfig.h>
46 #include <multisense_ros/sl_sgm_cmv2000_imuConfig.h>
47 #include <multisense_ros/sl_sgm_cmv4000_imuConfig.h>
48 #include <multisense_ros/bcam_imx104Config.h>
49 #include <multisense_ros/st21_sgm_vga_imuConfig.h>
50 #include <multisense_ros/mono_cmv2000Config.h>
51 #include <multisense_ros/mono_cmv4000Config.h>
52 #include <multisense_ros/s27_sgm_AR0234Config.h>
54 
55 namespace multisense_ros {
56 
57 class Reconfigure {
58 public:
59 
61  std::function<void (crl::multisense::image::Config)> resolutionChangeCallback,
62  std::function<void (BorderClip, double)> borderClipChangeCallback,
63  std::function<void (double)> maxPointCloudRangeCallback);
64 
65  ~Reconfigure();
66 
67  void imuCallback(const crl::multisense::imu::Header& header);
68 
69 private:
70 
71  //
72  // Dynamic reconfigure callback variations
73 
74  void callback_sl_bm_cmv2000 (multisense_ros::sl_bm_cmv2000Config& config, uint32_t level);
75  void callback_sl_bm_cmv2000_imu (multisense_ros::sl_bm_cmv2000_imuConfig& config, uint32_t level);
76  void callback_sl_bm_cmv4000 (multisense_ros::sl_bm_cmv4000Config& config, uint32_t level);
77  void callback_sl_bm_cmv4000_imu (multisense_ros::sl_bm_cmv4000_imuConfig& config, uint32_t level);
78  void callback_sl_sgm_cmv2000_imu(multisense_ros::sl_sgm_cmv2000_imuConfig& config, uint32_t level);
79  void callback_sl_sgm_cmv4000_imu(multisense_ros::sl_sgm_cmv4000_imuConfig& config, uint32_t level);
80  void callback_bcam_imx104 (multisense_ros::bcam_imx104Config& config, uint32_t level);
81  void callback_st21_vga (multisense_ros::st21_sgm_vga_imuConfig& config, uint32_t level);
82  void callback_mono_cmv2000 (multisense_ros::mono_cmv2000Config& config, uint32_t level);
83  void callback_mono_cmv4000 (multisense_ros::mono_cmv4000Config& config, uint32_t level);
84  void callback_s27_AR0234 (multisense_ros::s27_sgm_AR0234Config& config, uint32_t level);
85 
86  //
87  // Internal helper functions
88 
90  int32_t width, int32_t height, int32_t disparities);
91  template<class T> void configureSgm(crl::multisense::image::Config& cfg, const T& dyn);
92  template<class T> void configureCamera(crl::multisense::image::Config& cfg, const T& dyn);
93  template<class T> void configureCropMode(crl::multisense::image::Config& cfg, const T& dyn);
94  template<class T> void configureMotor(const T& dyn);
95  template<class T> void configureLeds(const T& dyn);
96  template<class T> void configureImu(const T& dyn);
97  template<class T> void configureBorderClip(const T& dyn);
98  template<class T> void configurePointCloudRange(const T& dyn);
99  template<class T> void configurePtp(const T& dyn);
100  template<class T> void configureStereoProfile(crl::multisense::image::Config &cfg, const T& dyn);
101 
102  //
103  // CRL sensor API
104 
106 
107  //
108  // Resolution change callback
109 
110  std::function<void (crl::multisense::image::Config)> resolution_change_callback_;
111 
112  //
113  // Driver nodes
114 
116 
117  //
118  // Cached modes from the sensor
119 
120  std::vector<crl::multisense::system::DeviceMode> device_modes_;
122  std::vector<crl::multisense::imu::Config> imu_configs_;
123 
124  //
125  // Dynamic reconfigure server variations
126 
127  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000Config> > server_sl_bm_cmv2000_;
128  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv2000_imuConfig> > server_sl_bm_cmv2000_imu_;
129  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000Config> > server_sl_bm_cmv4000_;
130  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_bm_cmv4000_imuConfig> > server_sl_bm_cmv4000_imu_;
131  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv2000_imuConfig> > server_sl_sgm_cmv2000_imu_;
132  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::sl_sgm_cmv4000_imuConfig> > server_sl_sgm_cmv4000_imu_;
133  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::bcam_imx104Config> > server_bcam_imx104_;
134  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::st21_sgm_vga_imuConfig> > server_st21_vga_;
135  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv2000Config> > server_mono_cmv2000_;
136  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::mono_cmv4000Config> > server_mono_cmv4000_;
137  std::shared_ptr< dynamic_reconfigure::Server<multisense_ros::s27_sgm_AR0234Config> > server_s27_AR0234_;
138 
139  //
140  // Cached values for supported sub-systems (these may be unavailable on
141  // certain hardware variations: S7, S7S, M, etc.)
142 
143  bool lighting_supported_ = false;
144  bool motor_supported_ = false;
145  bool crop_mode_changed_ = false;
146  bool ptp_supported_ = false;
147 
148  //
149  // Cached value for the boarder clip. These are used to determine if we
150  // should regenerate our border clipping mask
151 
153  double border_clip_value_ = 0.0;
154 
155  //
156  // Border clip change callback
157 
158  std::function<void (BorderClip, double)> border_clip_change_callback_;
159 
160  //
161  // Max point cloud range callback
162 
163  std::function<void (double)> max_point_cloud_range_callback_;
164 };
165 
166 } // multisense_ros
167 
168 #endif
void callback_sl_bm_cmv4000(multisense_ros::sl_bm_cmv4000Config &config, uint32_t level)
void callback_s27_AR0234(multisense_ros::s27_sgm_AR0234Config &config, uint32_t level)
void imuCallback(const crl::multisense::imu::Header &header)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv2000_imuConfig > > server_sl_bm_cmv2000_imu_
Definition: reconfigure.h:128
void configureCamera(crl::multisense::image::Config &cfg, const T &dyn)
std::function< void(BorderClip, double)> border_clip_change_callback_
Definition: reconfigure.h:158
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::mono_cmv4000Config > > server_mono_cmv4000_
Definition: reconfigure.h:136
void configureBorderClip(const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv4000_imuConfig > > server_sl_bm_cmv4000_imu_
Definition: reconfigure.h:130
std::vector< crl::multisense::system::DeviceMode > device_modes_
Definition: reconfigure.h:120
crl::multisense::Channel * driver_
Definition: reconfigure.h:105
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::bcam_imx104Config > > server_bcam_imx104_
Definition: reconfigure.h:133
void callback_mono_cmv4000(multisense_ros::mono_cmv4000Config &config, uint32_t level)
void callback_mono_cmv2000(multisense_ros::mono_cmv2000Config &config, uint32_t level)
void configurePointCloudRange(const T &dyn)
void callback_sl_sgm_cmv4000_imu(multisense_ros::sl_sgm_cmv4000_imuConfig &config, uint32_t level)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::st21_sgm_vga_imuConfig > > server_st21_vga_
Definition: reconfigure.h:134
void callback_st21_vga(multisense_ros::st21_sgm_vga_imuConfig &config, uint32_t level)
void callback_sl_sgm_cmv2000_imu(multisense_ros::sl_sgm_cmv2000_imuConfig &config, uint32_t level)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_sgm_cmv2000_imuConfig > > server_sl_sgm_cmv2000_imu_
Definition: reconfigure.h:131
ros::NodeHandle device_nh_
Definition: reconfigure.h:115
void callback_sl_bm_cmv4000_imu(multisense_ros::sl_bm_cmv4000_imuConfig &config, uint32_t level)
void configureMotor(const T &dyn)
void configureImu(const T &dyn)
void configureCropMode(crl::multisense::image::Config &cfg, const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv4000Config > > server_sl_bm_cmv4000_
Definition: reconfigure.h:129
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_bm_cmv2000Config > > server_sl_bm_cmv2000_
Definition: reconfigure.h:127
std::function< void(crl::multisense::image::Config)> resolution_change_callback_
Definition: reconfigure.h:110
void configureSgm(crl::multisense::image::Config &cfg, const T &dyn)
void configureStereoProfile(crl::multisense::image::Config &cfg, const T &dyn)
bool changeResolution(crl::multisense::image::Config &cfg, int32_t width, int32_t height, int32_t disparities)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::s27_sgm_AR0234Config > > server_s27_AR0234_
Definition: reconfigure.h:137
void callback_sl_bm_cmv2000(multisense_ros::sl_bm_cmv2000Config &config, uint32_t level)
void callback_bcam_imx104(multisense_ros::bcam_imx104Config &config, uint32_t level)
Reconfigure(crl::multisense::Channel *driver, std::function< void(crl::multisense::image::Config)> resolutionChangeCallback, std::function< void(BorderClip, double)> borderClipChangeCallback, std::function< void(double)> maxPointCloudRangeCallback)
Definition: reconfigure.cpp:40
void callback_sl_bm_cmv2000_imu(multisense_ros::sl_bm_cmv2000_imuConfig &config, uint32_t level)
void configurePtp(const T &dyn)
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::mono_cmv2000Config > > server_mono_cmv2000_
Definition: reconfigure.h:135
std::vector< crl::multisense::imu::Config > imu_configs_
Definition: reconfigure.h:122
std::function< void(double)> max_point_cloud_range_callback_
Definition: reconfigure.h:163
std::shared_ptr< dynamic_reconfigure::Server< multisense_ros::sl_sgm_cmv4000_imuConfig > > server_sl_sgm_cmv4000_imu_
Definition: reconfigure.h:132
void configureLeds(const T &dyn)


multisense_ros
Author(s):
autogenerated on Sun Mar 14 2021 02:34:55