allied_wide_configuration.cpp
Go to the documentation of this file.
1 /* Copyright (c) 2023, Beamagine
2 
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without modification,
6  are permitted provided that the following conditions are met:
7 
8  - Redistributions of source code must retain the above copyright notice,
9  this list of conditions and the following disclaimer.
10  - Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation and/or
12  other materials provided with the distribution.
13  - Neither the name of copyright holders nor the names of its contributors may be
14  used to endorse or promote products derived from this software without specific
15  prior written permission.
16 
17  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND ANY
18  EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
19  MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
20  COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
21  EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22  SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
23  HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR
24  TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
25  EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <iostream>
29 #include <ros/ros.h>
30 
31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/AlliedWideConfig.h"
33 
34 #include <libL3Cam.h>
35 #include <beamagine.h>
36 #include <beamErrors.h>
37 
38 #include "l3cam_ros/GetSensorsAvailable.h"
39 #include "l3cam_ros/ChangeAlliedCameraExposureTime.h"
40 #include "l3cam_ros/EnableAlliedCameraAutoExposureTime.h"
41 #include "l3cam_ros/ChangeAlliedCameraAutoExposureTimeRange.h"
42 #include "l3cam_ros/ChangeAlliedCameraGain.h"
43 #include "l3cam_ros/EnableAlliedCameraAutoGain.h"
44 #include "l3cam_ros/ChangeAlliedCameraAutoGainRange.h"
45 #include "l3cam_ros/ChangeAlliedCameraGamma.h"
46 #include "l3cam_ros/ChangeAlliedCameraSaturation.h"
47 #include "l3cam_ros/ChangeAlliedCameraHue.h"
48 #include "l3cam_ros/ChangeAlliedCameraIntensityAutoPrecedence.h"
49 #include "l3cam_ros/EnableAlliedCameraAutoWhiteBalance.h"
50 #include "l3cam_ros/ChangeAlliedCameraBalanceRatioSelector.h"
51 #include "l3cam_ros/ChangeAlliedCameraBalanceRatio.h"
52 #include "l3cam_ros/ChangeAlliedCameraBalanceWhiteAutoRate.h"
53 #include "l3cam_ros/ChangeAlliedCameraBalanceWhiteAutoTolerance.h"
54 #include "l3cam_ros/ChangeAlliedCameraIntensityControllerRegion.h"
55 #include "l3cam_ros/ChangeAlliedCameraIntensityControllerTarget.h"
56 #include "l3cam_ros/ChangeStreamingProtocol.h"
57 #include "l3cam_ros/GetRtspPipeline.h"
58 #include "l3cam_ros/GetAlliedCameraExposureTime.h"
59 #include "l3cam_ros/GetAlliedCameraGain.h"
60 
61 #include "l3cam_ros/SensorDisconnected.h"
62 
63 #include "l3cam_ros_utils.hpp"
64 
65 namespace l3cam_ros
66 {
68  {
69  public:
71  {
72  // Create service clients
73  client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>("/L3Cam/l3cam_ros_node/get_sensors_available");
74  client_exposure_time_ = serviceClient<l3cam_ros::ChangeAlliedCameraExposureTime>("/L3Cam/l3cam_ros_node/change_allied_exposure_time");
75  client_enable_auto_exposure_time_ = serviceClient<l3cam_ros::EnableAlliedCameraAutoExposureTime>("/L3Cam/l3cam_ros_node/enable_allied_auto_exposure_time");
76  client_auto_exposure_time_range_ = serviceClient<l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange>("/L3Cam/l3cam_ros_node/change_allied_auto_exposure_time_range");
77  client_gain_ = serviceClient<l3cam_ros::ChangeAlliedCameraGain>("/L3Cam/l3cam_ros_node/change_allied_gain");
78  client_enable_auto_gain_ = serviceClient<l3cam_ros::EnableAlliedCameraAutoGain>("/L3Cam/l3cam_ros_node/enable_allied_auto_gain");
79  client_auto_gain_range_ = serviceClient<l3cam_ros::ChangeAlliedCameraAutoGainRange>("/L3Cam/l3cam_ros_node/change_allied_auto_gain_range");
80  client_gamma_ = serviceClient<l3cam_ros::ChangeAlliedCameraGamma>("/L3Cam/l3cam_ros_node/change_allied_gamma");
81  client_saturation_ = serviceClient<l3cam_ros::ChangeAlliedCameraSaturation>("/L3Cam/l3cam_ros_node/change_allied_saturation");
82  client_hue_ = serviceClient<l3cam_ros::ChangeAlliedCameraHue>("/L3Cam/l3cam_ros_node/change_allied_hue");
83  client_intensity_auto_precedence_ = serviceClient<l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence>("/L3Cam/l3cam_ros_node/change_allied_intensity_auto_precedence");
84  client_enable_auto_white_balance_ = serviceClient<l3cam_ros::EnableAlliedCameraAutoWhiteBalance>("/L3Cam/l3cam_ros_node/enable_allied_auto_white_balance");
85  client_balance_ratio_selector_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceRatioSelector>("/L3Cam/l3cam_ros_node/change_allied_balance_ratio_selector");
86  client_balance_ratio_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceRatio>("/L3Cam/l3cam_ros_node/change_allied_balance_ratio");
87  client_balance_white_auto_rate_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate>("/L3Cam/l3cam_ros_node/change_allied_balance_white_auto_rate");
88  client_balance_white_auto_tolerance_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance>("/L3Cam/l3cam_ros_node/change_allied_balance_white_auto_tolerance");
89  client_intensity_controller_region_ = serviceClient<l3cam_ros::ChangeAlliedCameraIntensityControllerRegion>("/L3Cam/l3cam_ros_node/change_allied_intensity_controller_region");
90  client_intensity_controller_target_ = serviceClient<l3cam_ros::ChangeAlliedCameraIntensityControllerTarget>("/L3Cam/l3cam_ros_node/change_allied_intensity_controller_target");
91  client_change_streaming_protocol_ = serviceClient<l3cam_ros::ChangeStreamingProtocol>("/L3Cam/l3cam_ros_node/change_streaming_protocol");
92  client_get_rtsp_pipeline_ = serviceClient<l3cam_ros::GetRtspPipeline>("/L3Cam/l3cam_ros_node/get_rtsp_pipeline");
93  client_get_exposure_time_ = serviceClient<l3cam_ros::GetAlliedCameraExposureTime>("/L3Cam/l3cam_ros_node/get_allied_exposure_time");
94  client_get_gain_ = serviceClient<l3cam_ros::GetAlliedCameraGain>("/L3Cam/l3cam_ros_node/get_allied_gain");
95 
97 
98  // Create service server
99  srv_sensor_disconnected_ = advertiseService("allied_wide_configuration_disconnected", &AlliedWideConfiguration::sensorDisconnectedCallback, this);
100 
101  m_default_configured = false;
102  m_shutdown_requested = false;
103  }
104 
106  {
107  // Dynamic reconfigure callback
108  // server_ is a pointer so we only declare it if sensor is available and reconfigure should be available
109  server_ = new dynamic_reconfigure::Server<l3cam_ros::AlliedWideConfig>;
110  server_->setCallback(std::bind(&AlliedWideConfiguration::parametersCallback, this, std::placeholders::_1, std::placeholders::_2));
111  }
112 
113  void spin()
114  {
115  while (ros::ok() && !m_shutdown_requested)
116  {
117  ros::spinOnce();
118  ros::Duration(0.1).sleep();
119  }
120 
121  ros::shutdown();
122  }
123 
125  l3cam_ros::GetSensorsAvailable srv_get_sensors_;
126 
128 
129  private:
130  template <typename T>
131  void loadParam(const std::string &param_name, T &param_var, const T &default_val)
132  {
133  std::string full_param_name;
134 
135  if (searchParam(param_name, full_param_name))
136  {
137  if (!getParam(full_param_name, param_var))
138  {
139  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
140  }
141  }
142  else
143  {
144  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
145  param_var = default_val;
146  }
147  }
148 
150  {
151  // Get and save parameters
152  loadParam("timeout_secs", timeout_secs_, 60);
153  loadParam("allied_wide_exposure_time", allied_wide_exposure_time_, 4992.32);
154  loadParam("allied_wide_auto_exposure_time", allied_wide_auto_exposure_time_, false);
155  loadParam("allied_wide_auto_exposure_time_range_min", allied_wide_auto_exposure_time_range_min_, 87.596);
156  loadParam("allied_wide_auto_exposure_time_range_max", allied_wide_auto_exposure_time_range_max_, 87.596);
157  loadParam("allied_wide_gain", allied_wide_gain_, 0.);
158  loadParam("allied_wide_auto_gain", allied_wide_auto_gain_, false);
159  loadParam("allied_wide_auto_gain_range_min", allied_wide_auto_gain_range_min_, 0.);
160  loadParam("allied_wide_auto_gain_range_max", allied_wide_auto_gain_range_max_, 48.);
161  loadParam("allied_wide_gamma", allied_wide_gamma_, 1.);
162  loadParam("allied_wide_saturation", allied_wide_saturation_, 1.);
163  loadParam("allied_wide_hue", allied_wide_hue_, 0.);
164  loadParam("allied_wide_intensity_auto_precedence", allied_wide_intensity_auto_precedence_, 1);
165  loadParam("allied_wide_auto_white_balance", allied_wide_auto_white_balance_, false);
166  loadParam("allied_wide_balance_ratio_selector", allied_wide_balance_ratio_selector_, 1);
167  loadParam("allied_wide_balance_ratio", allied_wide_balance_ratio_, 2.35498);
168  loadParam("allied_wide_balance_white_auto_rate", allied_wide_balance_white_auto_rate_, 100.);
169  loadParam("allied_wide_balance_white_auto_tolerance", allied_wide_balance_white_auto_tolerance_, 5.);
170  loadParam("allied_wide_intensity_controller_region", allied_wide_intensity_controller_region_, 1);
171  loadParam("allied_wide_intensity_controller_target", allied_wide_intensity_controller_target_, 50.);
172  loadParam("allied_wide_streaming_protocol", allied_wide_streaming_protocol_, 0);
173  }
174 
175  void configureDefault(l3cam_ros::AlliedWideConfig &config)
176  {
177  // Configure default params to dynamix reconfigure if inside range
179  {
180  config.allied_wide_exposure_time = allied_wide_exposure_time_;
181  }
182  else
183  {
184  allied_wide_exposure_time_ = config.allied_wide_exposure_time;
185  }
186 
188  {
189  config.allied_wide_auto_exposure_time = allied_wide_auto_exposure_time_;
190  }
191  else
192  {
193  allied_wide_auto_exposure_time_ = config.allied_wide_auto_exposure_time;
194  }
195 
197  {
198  config.allied_wide_auto_exposure_time_range_min = allied_wide_auto_exposure_time_range_min_;
199  }
200  else
201  {
202  allied_wide_auto_exposure_time_range_min_ = config.allied_wide_auto_exposure_time_range_min;
203  }
204 
206  {
207  config.allied_wide_auto_exposure_time_range_max = allied_wide_auto_exposure_time_range_max_;
208  }
209  else
210  {
211  allied_wide_auto_exposure_time_range_max_ = config.allied_wide_auto_exposure_time_range_max;
212  }
213 
214  if (allied_wide_gain_ >= 0 && allied_wide_gain_ <= 48)
215  {
216  config.allied_wide_gain = allied_wide_gain_;
217  }
218  else
219  {
220  allied_wide_gain_ = config.allied_wide_gain;
221  }
222 
223  config.allied_wide_auto_gain = allied_wide_auto_gain_;
224 
226  {
227  config.allied_wide_auto_gain_range_min = allied_wide_auto_gain_range_min_;
228  }
229  else
230  {
231  allied_wide_auto_gain_range_min_ = config.allied_wide_auto_gain_range_min;
232  }
233 
235  {
236  config.allied_wide_auto_gain_range_max = allied_wide_auto_gain_range_max_;
237  }
238  else
239  {
240  allied_wide_auto_gain_range_max_ = config.allied_wide_auto_gain_range_max;
241  }
242 
243  if (allied_wide_gamma_ >= 0.4 && allied_wide_gamma_ <= 2.4)
244  {
245  config.allied_wide_gamma = allied_wide_gamma_;
246  }
247  else
248  {
249  allied_wide_gamma_ = config.allied_wide_gamma;
250  }
251 
253  {
254  config.allied_wide_saturation = allied_wide_saturation_;
255  }
256  else
257  {
258  allied_wide_saturation_ = config.allied_wide_saturation;
259  }
260 
261  if (allied_wide_hue_ >= -40 && allied_wide_hue_ <= 40)
262  {
263  config.allied_wide_hue = allied_wide_hue_;
264  }
265  else
266  {
267  allied_wide_hue_ = config.allied_wide_hue;
268  }
269 
271  {
272  config.allied_wide_intensity_auto_precedence = allied_wide_intensity_auto_precedence_;
273  }
274  else
275  {
276  allied_wide_intensity_auto_precedence_ = config.allied_wide_intensity_auto_precedence;
277  }
278 
279  config.allied_wide_auto_white_balance = allied_wide_auto_white_balance_;
280 
282  {
283  config.allied_wide_white_balance_ratio_selector = allied_wide_balance_ratio_selector_;
284  }
285  else
286  {
287  allied_wide_balance_ratio_selector_ = config.allied_wide_white_balance_ratio_selector;
288  }
289 
291  {
292  config.allied_wide_balance_ratio = allied_wide_balance_ratio_;
293  }
294  else
295  {
296  allied_wide_balance_ratio_ = config.allied_wide_balance_ratio;
297  }
298 
300  {
301  config.allied_wide_white_balance_auto_rate = allied_wide_balance_white_auto_rate_;
302  }
303  else
304  {
305  allied_wide_balance_white_auto_rate_ = config.allied_wide_white_balance_auto_rate;
306  }
307 
309  {
310  config.allied_wide_white_balance_auto_tolerance = allied_wide_balance_white_auto_tolerance_;
311  }
312  else
313  {
314  allied_wide_balance_white_auto_tolerance_ = config.allied_wide_white_balance_auto_tolerance;
315  }
316 
318  {
319  config.allied_wide_intensity_controller_region = allied_wide_intensity_controller_region_;
320  }
321  else
322  {
323  allied_wide_intensity_controller_region_ = config.allied_wide_intensity_controller_region;
324  }
325 
327  {
328  config.allied_wide_intensity_controller_target = allied_wide_intensity_controller_target_;
329  }
330  else
331  {
332  allied_wide_intensity_controller_target_ = config.allied_wide_intensity_controller_target;
333  }
334 
336  {
337  config.allied_wide_streaming_protocol = allied_wide_streaming_protocol_;
338  }
339  else
340  {
341  allied_wide_streaming_protocol_ = config.allied_wide_streaming_protocol;
342  }
343 
344  // Get pipeline
345  int error = L3CAM_OK;
346  ros::Duration timeout_duration(timeout_secs_);
347  if (!client_get_rtsp_pipeline_.waitForExistence(timeout_duration))
348  {
349  ROS_ERROR_STREAM(this->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
350  }
351  else
352  {
353  srv_get_rtsp_pipeline_.request.sensor_type = (int)sensorTypes::sensor_allied_wide;
355  {
356  error = srv_get_rtsp_pipeline_.response.error;
357  if (!error)
358  {
360  config.allied_wide_rtsp_pipeline = srv_get_rtsp_pipeline_.response.pipeline;
361  }
362  else
363  {
364  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting RTSP pipeline: " << getErrorDescription(error));
365  config.allied_wide_rtsp_pipeline = "";
367  }
368  }
369  else
370  {
371  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service get_rtsp_pipeline");
372  config.allied_wide_rtsp_pipeline = "";
374  }
375  }
376 
377  m_default_configured = true;
378  }
379 
380  void parametersCallback(AlliedWideConfig &config, uint32_t level)
381  {
382  int error = L3CAM_OK;
383 
385  {
386  configureDefault(config);
387  }
388  else
389  {
390  // Filter by parameter and call service
391  switch (level)
392  {
393  case 0: // allied_wide_exposure_time
394  error = callExposureTime(config);
395  break;
396  case 1: // allied_wide_auto_exposure_time
397  error = callAutoExposureTime(config);
398  break;
399  case 2: // allied_wide_auto_exposure_time_range_min
400  error = callAutoExposureTimeRange(config);
401  break;
402  case 3: // allied_wide_auto_exposure_time_range_max
403  error = callAutoExposureTimeRange(config);
404  break;
405  case 4: // allied_wide_gain
406  error = callGain(config);
407  break;
408  case 5: // allied_wide_auto_gain
409  error = callAutoGain(config);
410  break;
411  case 6: // allied_wide_auto_gain_range_min
412  error = callAutoGainRange(config);
413  break;
414  case 7: // allied_wide_auto_gain_range_max
415  error = callAutoGainRange(config);
416  break;
417  case 8: // allied_wide_gamma
418  error = callGamma(config);
419  break;
420  case 9: // allied_wide_saturation
421  error = callSaturation(config);
422  break;
423  case 10: // allied_wide_hue
424  error = callHue(config);
425  break;
426  case 11: // allied_wide_intensity_auto_precedence
427  error = callIntensityAutoPrecedence(config);
428  break;
429  case 12: // allied_wide_auto_white_balance
430  error = callAutoWhiteBalance(config);
431  break;
432  case 13: // allied_wide_white_balance_ratio_selector
433  error = callBalanceRatioSelector(config);
434  break;
435  case 14: // allied_wide_balance_ratio
436  error = callBalanceRatio(config);
437  break;
438  case 15: // allied_wide_white_balance_auto_rate
439  error = callBalanceWhiteAutoRate(config);
440  break;
441  case 16: // allied_wide_white_balance_auto_tolerance
442  error = callBalanceWhiteAutoTolerance(config);
443  break;
444  case 17: // allied_wide_intensity_controller_region
445  error = callIntensityControllerRegion(config);
446  break;
447  case 18: // allied_wide_intensity_controller_target
448  error = callIntensityControllerTarget(config);
449  break;
450  case 19: // allied_wide_streaming_protocol
451  error = callStreamingProtocol(config);
452  break;
453  case 20: // allied_wide_rtsp_pipeline
454  error = callRtspPipeline(config);
455  break;
456  }
457  }
458 
459  if (error)
460  {
461  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while changing parameter: " << getErrorDescription(error));
462  }
463  }
464 
465  // Service calls
466  int callExposureTime(l3cam_ros::AlliedWideConfig &config)
467  {
468  int error = L3CAM_OK;
469 
470  if (!config.allied_wide_auto_exposure_time)
471  {
472  srv_exposure_time_.request.exposure_time = config.allied_wide_exposure_time;
473  srv_exposure_time_.request.allied_type = alliedCamerasIds::wide_camera;
475  {
476  error = srv_exposure_time_.response.error;
477  if (!error)
478  {
479  // Parameter changed successfully, save value
480  allied_wide_exposure_time_ = config.allied_wide_exposure_time;
481  }
482  else
483  {
484  // Parameter could not be changed, reset parameter to value before change
485  config.allied_wide_exposure_time = allied_wide_exposure_time_;
486  }
487  }
488  else
489  {
490  // Service could not be called, reset parameter to value before change
491  config.allied_wide_exposure_time = allied_wide_exposure_time_;
493  }
494  }
495  else
496  {
497  ROS_WARN_STREAM(this->getNamespace() << " Allied Wide camera auto exposure time must be disabled to change exposure time");
498  config.allied_wide_exposure_time = allied_wide_exposure_time_;
499  }
500 
501  return error;
502  }
503 
504  int callAutoExposureTime(l3cam_ros::AlliedWideConfig &config)
505  {
506  int error = L3CAM_OK;
507 
508  srv_enable_auto_exposure_time_.request.enabled = config.allied_wide_auto_exposure_time;
509  srv_enable_auto_exposure_time_.request.allied_type = alliedCamerasIds::wide_camera;
511  {
512  error = srv_enable_auto_exposure_time_.response.error;
513  if (!error)
514  {
515  // Parameter changed successfully, save value
516  allied_wide_auto_exposure_time_ = config.allied_wide_auto_exposure_time;
517 
518  // If auto exposure time deactivated we have to get the actual exposure time to know its value
519  srv_get_exposure_time_.request.allied_type = alliedCamerasIds::wide_camera;
521  {
522  error = srv_get_exposure_time_.response.error;
523  if (!error)
524  {
525  // Got parameter successfully
526  allied_wide_exposure_time_ = srv_get_exposure_time_.response.exposure_time;
527  config.allied_wide_exposure_time = srv_get_exposure_time_.response.exposure_time;
528  }
529  else
530  {
531  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting parameter in " << __func__ << ": " << getErrorDescription(error));
532  }
533  }
534  else
535  {
537  }
538  }
539  else
540  {
541  // Parameter could not be changed, reset parameter to value before change
542  config.allied_wide_auto_exposure_time = allied_wide_auto_exposure_time_;
543  }
544  }
545  else
546  {
547  // Service could not be called, reset parameter to value before change
548  config.allied_wide_auto_exposure_time = allied_wide_auto_exposure_time_;
550  }
551 
552  return error;
553  }
554 
555  int callAutoExposureTimeRange(l3cam_ros::AlliedWideConfig &config)
556  {
557  int error = L3CAM_OK;
558 
559  if (config.allied_wide_auto_exposure_time)
560  {
561  srv_auto_exposure_time_range_.request.auto_exposure_time_range_min = config.allied_wide_auto_exposure_time_range_min;
562  srv_auto_exposure_time_range_.request.allied_type = alliedCamerasIds::wide_camera;
563  srv_auto_exposure_time_range_.request.auto_exposure_time_range_max = config.allied_wide_auto_exposure_time_range_max;
565  {
566  error = srv_auto_exposure_time_range_.response.error;
567  if (!error)
568  {
569  // Parameter changed successfully, save value
570  allied_wide_auto_exposure_time_range_min_ = config.allied_wide_auto_exposure_time_range_min;
571  allied_wide_auto_exposure_time_range_max_ = config.allied_wide_auto_exposure_time_range_max;
572  }
573  else
574  {
575  // Parameter could not be changed, reset parameter to value before change
576  config.allied_wide_auto_exposure_time_range_min = allied_wide_auto_exposure_time_range_min_;
577  config.allied_wide_auto_exposure_time_range_max = allied_wide_auto_exposure_time_range_max_;
578  }
579  }
580  else
581  {
582  // Service could not be called, reset parameter to value before change
583  config.allied_wide_auto_exposure_time_range_min = allied_wide_auto_exposure_time_range_min_;
584  config.allied_wide_auto_exposure_time_range_max = allied_wide_auto_exposure_time_range_max_;
586  }
587  }
588  else
589  {
590  ROS_WARN_STREAM(this->getNamespace() << " Allied Wide camera auto exposure time must be enabled to change auto exposure time range");
591  config.allied_wide_auto_exposure_time_range_min = allied_wide_auto_exposure_time_range_min_;
592  config.allied_wide_auto_exposure_time_range_max = allied_wide_auto_exposure_time_range_max_;
593  }
594 
595  return error;
596  }
597 
598  int callGain(l3cam_ros::AlliedWideConfig &config)
599  {
600  int error = L3CAM_OK;
601 
602  if (!config.allied_wide_auto_gain)
603  {
604  srv_gain_.request.gain = config.allied_wide_gain;
605  srv_gain_.request.allied_type = alliedCamerasIds::wide_camera;
607  {
608  error = srv_gain_.response.error;
609  if (!error)
610  {
611  // Parameter changed successfully, save value
612  allied_wide_gain_ = config.allied_wide_gain;
613  }
614  else
615  {
616  // Parameter could not be changed, reset parameter to value before change
617  config.allied_wide_gain = allied_wide_gain_;
618  }
619  }
620  else
621  {
622  // Service could not be called, reset parameter to value before change
623  config.allied_wide_gain = allied_wide_gain_;
625  }
626  }
627  else
628  {
629  ROS_WARN_STREAM(this->getNamespace() << " Allied Wide camera auto gain must be disabled to change gain");
630  config.allied_wide_gain = allied_wide_gain_;
631  }
632 
633  return error;
634  }
635 
636  int callAutoGain(l3cam_ros::AlliedWideConfig &config)
637  {
638  int error = L3CAM_OK;
639 
640  srv_enable_auto_gain_.request.enabled = config.allied_wide_auto_gain;
641  srv_enable_auto_gain_.request.allied_type = alliedCamerasIds::wide_camera;
643  {
644  error = srv_enable_auto_gain_.response.error;
645  if (!error)
646  {
647  // Parameter changed successfully, save value
648  allied_wide_auto_gain_ = config.allied_wide_auto_gain;
649 
650  // If auto gain deactivated we have to get the actual gain to know its value
651  srv_get_gain_.request.allied_type = alliedCamerasIds::wide_camera;
653  {
654  error = srv_get_gain_.response.error;
655  if (!error)
656  {
657  // Got parameter successfully
658  allied_wide_gain_ = srv_get_gain_.response.gain;
659  config.allied_wide_gain = srv_get_gain_.response.gain;
660  }
661  else
662  {
663  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting parameter in " << __func__ << ": " << getErrorDescription(error));
664  }
665  }
666  else
667  {
669  }
670  }
671  else
672  {
673  // Parameter could not be changed, reset parameter to value before change
674  config.allied_wide_auto_gain = allied_wide_auto_gain_;
675  }
676  }
677  else
678  {
679  // Service could not be called, reset parameter to value before change
680  config.allied_wide_auto_gain = allied_wide_auto_gain_;
682  }
683 
684  return error;
685  }
686 
687  int callAutoGainRange(l3cam_ros::AlliedWideConfig &config)
688  {
689  int error = L3CAM_OK;
690 
691  if (config.allied_wide_auto_gain)
692  {
693  srv_auto_gain_range_.request.auto_gain_range_min = config.allied_wide_auto_gain_range_min;
694  srv_auto_gain_range_.request.allied_type = alliedCamerasIds::wide_camera;
695  srv_auto_gain_range_.request.auto_gain_range_max = config.allied_wide_auto_gain_range_max;
697  {
698  error = srv_auto_gain_range_.response.error;
699  if (!error)
700  {
701  // Parameter changed successfully, save value
702  allied_wide_auto_gain_range_min_ = config.allied_wide_auto_gain_range_min;
703  allied_wide_auto_gain_range_max_ = config.allied_wide_auto_gain_range_max;
704  }
705  else
706  {
707  // Parameter could not be changed, reset parameter to value before change
708  config.allied_wide_auto_gain_range_min = allied_wide_auto_gain_range_min_;
709  config.allied_wide_auto_gain_range_max = allied_wide_auto_gain_range_max_;
710  }
711  }
712  else
713  {
714  // Service could not be called, reset parameter to value before change
715  config.allied_wide_auto_gain_range_min = allied_wide_auto_gain_range_min_;
716  config.allied_wide_auto_gain_range_max = allied_wide_auto_gain_range_max_;
718  }
719  }
720  else
721  {
722  ROS_WARN_STREAM(this->getNamespace() << " Allied Wide camera auto gain must be enabled to change auto gain range");
723  config.allied_wide_auto_gain_range_min = allied_wide_auto_gain_range_min_;
724  config.allied_wide_auto_gain_range_max = allied_wide_auto_gain_range_max_;
725  }
726 
727  return error;
728  }
729 
730  int callGamma(l3cam_ros::AlliedWideConfig &config)
731  {
732  int error = L3CAM_OK;
733 
734  srv_gamma_.request.gamma = config.allied_wide_gamma;
735  srv_gamma_.request.allied_type = alliedCamerasIds::wide_camera;
737  {
738  error = srv_gamma_.response.error;
739  if (!error)
740  {
741  // Parameter changed successfully, save value
742  allied_wide_gamma_ = config.allied_wide_gamma;
743  }
744  else
745  {
746  // Parameter could not be changed, reset parameter to value before change
747  config.allied_wide_gamma = allied_wide_gamma_;
748  }
749  }
750  else
751  {
752  // Service could not be called, reset parameter to value before change
753  config.allied_wide_gamma = allied_wide_gamma_;
755  }
756 
757  return error;
758  }
759 
760  int callSaturation(l3cam_ros::AlliedWideConfig &config)
761  {
762  int error = L3CAM_OK;
763 
764  srv_saturation_.request.saturation = config.allied_wide_saturation;
765  srv_saturation_.request.allied_type = alliedCamerasIds::wide_camera;
767  {
768  error = srv_saturation_.response.error;
769  if (!error)
770  {
771  // Parameter changed successfully, save value
772  allied_wide_saturation_ = config.allied_wide_saturation;
773  }
774  else
775  {
776  // Parameter could not be changed, reset parameter to value before change
777  config.allied_wide_saturation = allied_wide_saturation_;
778  }
779  }
780  else
781  {
782  // Service could not be called, reset parameter to value before change
783  config.allied_wide_saturation = allied_wide_saturation_;
785  }
786 
787  return error;
788  }
789 
790  int callHue(l3cam_ros::AlliedWideConfig &config)
791  {
792  int error = L3CAM_OK;
793 
794  srv_hue_.request.hue = config.allied_wide_hue;
795  srv_hue_.request.allied_type = alliedCamerasIds::wide_camera;
797  {
798  error = srv_hue_.response.error;
799  if (!error)
800  {
801  // Parameter changed successfully, save value
802  allied_wide_hue_ = config.allied_wide_hue;
803  }
804  else
805  {
806  // Parameter could not be changed, reset parameter to value before change
807  config.allied_wide_hue = allied_wide_hue_;
808  }
809  }
810  else
811  {
812  // Service could not be called, reset parameter to value before change
813  config.allied_wide_hue = allied_wide_hue_;
815  }
816 
817  return error;
818  }
819 
820  int callIntensityAutoPrecedence(l3cam_ros::AlliedWideConfig &config)
821  {
822  int error = L3CAM_OK;
823 
824  srv_intensity_auto_precedence_.request.intensity_auto_precedence = config.allied_wide_intensity_auto_precedence;
825  srv_intensity_auto_precedence_.request.allied_type = alliedCamerasIds::wide_camera;
827  {
828  error = srv_intensity_auto_precedence_.response.error;
829  if (!error)
830  {
831  // Parameter changed successfully, save value
832  allied_wide_intensity_auto_precedence_ = config.allied_wide_intensity_auto_precedence;
833  }
834  else
835  {
836  // Parameter could not be changed, reset parameter to value before change
837  config.allied_wide_intensity_auto_precedence = allied_wide_intensity_auto_precedence_;
838  }
839  }
840  else
841  {
842  // Service could not be called, reset parameter to value before change
843  config.allied_wide_intensity_auto_precedence = allied_wide_intensity_auto_precedence_;
845  }
846 
847  return error;
848  }
849 
850  int callAutoWhiteBalance(l3cam_ros::AlliedWideConfig &config)
851  {
852  int error = L3CAM_OK;
853 
854  srv_enable_auto_white_balance_.request.enabled = config.allied_wide_intensity_auto_precedence;
855  srv_enable_auto_white_balance_.request.allied_type = alliedCamerasIds::wide_camera;
857  {
858  error = srv_enable_auto_white_balance_.response.error;
859  if (!error)
860  {
861  // Parameter changed successfully, save value
862  allied_wide_intensity_auto_precedence_ = config.allied_wide_intensity_auto_precedence;
863  }
864  else
865  {
866  // Parameter could not be changed, reset parameter to value before change
867  config.allied_wide_intensity_auto_precedence = allied_wide_intensity_auto_precedence_;
868  }
869  }
870  else
871  {
872  // Service could not be called, reset parameter to value before change
873  config.allied_wide_intensity_auto_precedence = allied_wide_intensity_auto_precedence_;
875  }
876 
877  return error;
878  }
879 
880  int callBalanceRatioSelector(l3cam_ros::AlliedWideConfig &config)
881  {
882  int error = L3CAM_OK;
883 
884  srv_balance_ratio_selector_.request.white_balance_ratio_selector = config.allied_wide_white_balance_ratio_selector;
885  srv_balance_ratio_selector_.request.allied_type = alliedCamerasIds::wide_camera;
887  {
888  error = srv_balance_ratio_selector_.response.error;
889  if (!error)
890  {
891  // Parameter changed successfully, save value
892  allied_wide_balance_ratio_selector_ = config.allied_wide_white_balance_ratio_selector;
893  }
894  else
895  {
896  // Parameter could not be changed, reset parameter to value before change
897  config.allied_wide_white_balance_ratio_selector = allied_wide_balance_ratio_selector_;
898  }
899  }
900  else
901  {
902  // Service could not be called, reset parameter to value before change
903  config.allied_wide_white_balance_ratio_selector = allied_wide_balance_ratio_selector_;
905  }
906 
907  return error;
908  }
909 
910  int callBalanceRatio(l3cam_ros::AlliedWideConfig &config)
911  {
912  int error = L3CAM_OK;
913 
914  srv_balance_ratio_.request.balance_ratio = config.allied_wide_balance_ratio;
915  srv_balance_ratio_.request.allied_type = alliedCamerasIds::wide_camera;
917  {
918  error = srv_balance_ratio_.response.error;
919  if (!error)
920  {
921  // Parameter changed successfully, save value
922  allied_wide_balance_ratio_ = config.allied_wide_balance_ratio;
923  }
924  else
925  {
926  // Parameter could not be changed, reset parameter to value before change
927  config.allied_wide_balance_ratio = allied_wide_balance_ratio_;
928  }
929  }
930  else
931  {
932  // Service could not be called, reset parameter to value before change
933  config.allied_wide_balance_ratio = allied_wide_balance_ratio_;
935  }
936 
937  return error;
938  }
939 
940  int callBalanceWhiteAutoRate(l3cam_ros::AlliedWideConfig &config)
941  {
942  int error = L3CAM_OK;
943 
944  srv_balance_white_auto_rate_.request.white_balance_auto_rate = config.allied_wide_white_balance_auto_rate;
945  srv_balance_white_auto_rate_.request.allied_type = alliedCamerasIds::wide_camera;
947  {
948  error = srv_balance_white_auto_rate_.response.error;
949  if (!error)
950  {
951  // Parameter changed successfully, save value
952  allied_wide_balance_white_auto_rate_ = config.allied_wide_white_balance_auto_rate;
953  }
954  else
955  {
956  // Parameter could not be changed, reset parameter to value before change
957  config.allied_wide_white_balance_auto_rate = allied_wide_balance_white_auto_rate_;
958  }
959  }
960  else
961  {
962  // Service could not be called, reset parameter to value before change
963  config.allied_wide_white_balance_auto_rate = allied_wide_balance_white_auto_rate_;
965  }
966 
967  return error;
968  }
969 
970  int callBalanceWhiteAutoTolerance(l3cam_ros::AlliedWideConfig &config)
971  {
972  int error = L3CAM_OK;
973 
974  srv_balance_white_auto_tolerance_.request.white_balance_auto_tolerance = config.allied_wide_white_balance_auto_tolerance;
975  srv_balance_white_auto_tolerance_.request.allied_type = alliedCamerasIds::wide_camera;
977  {
978  error = srv_balance_white_auto_tolerance_.response.error;
979  if (!error)
980  {
981  // Parameter changed successfully, save value
982  allied_wide_balance_white_auto_tolerance_ = config.allied_wide_white_balance_auto_tolerance;
983  }
984  else
985  {
986  // Parameter could not be changed, reset parameter to value before change
987  config.allied_wide_white_balance_auto_tolerance = allied_wide_balance_white_auto_tolerance_;
988  }
989  }
990  else
991  {
992  // Service could not be called, reset parameter to value before change
993  config.allied_wide_white_balance_auto_tolerance = allied_wide_balance_white_auto_tolerance_;
995  }
996 
997  return error;
998  }
999 
1000  int callIntensityControllerRegion(l3cam_ros::AlliedWideConfig &config)
1001  {
1002  int error = L3CAM_OK;
1003 
1004  srv_intensity_controller_region_.request.intensity_controller_region = config.allied_wide_intensity_controller_region;
1005  srv_intensity_controller_region_.request.allied_type = alliedCamerasIds::wide_camera;
1007  {
1008  error = srv_intensity_controller_region_.response.error;
1009  if (!error)
1010  {
1011  // Parameter changed successfully, save value
1012  allied_wide_intensity_controller_region_ = config.allied_wide_intensity_controller_region;
1013  }
1014  else
1015  {
1016  // Parameter could not be changed, reset parameter to value before change
1017  config.allied_wide_intensity_controller_region = allied_wide_intensity_controller_region_;
1018  }
1019  }
1020  else
1021  {
1022  // Service could not be called, reset parameter to value before change
1023  config.allied_wide_intensity_controller_region = allied_wide_intensity_controller_region_;
1025  }
1026 
1027  return error;
1028  }
1029 
1030  int callIntensityControllerTarget(l3cam_ros::AlliedWideConfig &config)
1031  {
1032  int error = L3CAM_OK;
1033 
1034  srv_intensity_controller_target_.request.intensity_controller_target = config.allied_wide_intensity_controller_target;
1035  srv_intensity_controller_target_.request.allied_type = alliedCamerasIds::wide_camera;
1037  {
1038  error = srv_intensity_controller_target_.response.error;
1039  if (!error)
1040  {
1041  // Parameter changed successfully, save value
1042  allied_wide_intensity_controller_target_ = config.allied_wide_intensity_controller_target;
1043  }
1044  else
1045  {
1046  // Parameter could not be changed, reset parameter to value before change
1047  config.allied_wide_intensity_controller_target = allied_wide_intensity_controller_target_;
1048  }
1049  }
1050  else
1051  {
1052  // Service could not be called, reset parameter to value before change
1053  config.allied_wide_intensity_controller_target = allied_wide_intensity_controller_target_;
1055  }
1056 
1057  return error;
1058  }
1059 
1060  int callStreamingProtocol(l3cam_ros::AlliedWideConfig &config)
1061  {
1062  int error = L3CAM_OK;
1063 
1064  srv_change_streaming_protocol_.request.protocol = config.allied_wide_streaming_protocol;
1065  srv_change_streaming_protocol_.request.sensor_type = (int)sensorTypes::sensor_allied_wide;
1067  {
1068  error = srv_change_streaming_protocol_.response.error;
1069  if (!error)
1070  {
1071  // Parameter changed successfully, save value
1072  allied_wide_streaming_protocol_ = config.allied_wide_streaming_protocol;
1073  }
1074  else
1075  {
1076  // Parameter could not be changed, reset parameter to value before change
1077  config.allied_wide_streaming_protocol = allied_wide_streaming_protocol_;
1078  }
1079  }
1080  else
1081  {
1082  // Service could not be called, reset parameter to value before change
1083  config.allied_wide_streaming_protocol = allied_wide_streaming_protocol_;
1085  }
1086 
1087  return error;
1088  }
1089 
1090  int callRtspPipeline(l3cam_ros::AlliedWideConfig &config)
1091  {
1092  // Read-only
1093  ROS_WARN_STREAM(this->getNamespace() << " The RTSP Pipeline parameter is read-only, only changeable at launch");
1094  config.allied_wide_rtsp_pipeline = allied_wide_rtsp_pipeline_;
1095 
1096  return L3CAM_OK;
1097  }
1098 
1099  bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
1100  {
1101  ROS_BMG_UNUSED(res);
1102  if (req.code == 0)
1103  {
1104  ROS_INFO_STREAM("Exiting " << this->getNamespace() << " cleanly.");
1105  }
1106  else
1107  {
1108  ROS_WARN_STREAM("Exiting " << this->getNamespace() << ". Sensor got disconnected with error " << req.code << ": " << getErrorDescription(req.code));
1109  }
1110 
1111  m_shutdown_requested = true;
1112  return true;
1113  }
1114 
1115  dynamic_reconfigure::Server<l3cam_ros::AlliedWideConfig> *server_;
1116 
1118  l3cam_ros::ChangeAlliedCameraExposureTime srv_exposure_time_;
1120  l3cam_ros::EnableAlliedCameraAutoExposureTime srv_enable_auto_exposure_time_;
1122  l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange srv_auto_exposure_time_range_;
1124  l3cam_ros::ChangeAlliedCameraGain srv_gain_;
1126  l3cam_ros::EnableAlliedCameraAutoGain srv_enable_auto_gain_;
1128  l3cam_ros::ChangeAlliedCameraAutoGainRange srv_auto_gain_range_;
1130  l3cam_ros::ChangeAlliedCameraGamma srv_gamma_;
1132  l3cam_ros::ChangeAlliedCameraSaturation srv_saturation_;
1134  l3cam_ros::ChangeAlliedCameraHue srv_hue_;
1136  l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence srv_intensity_auto_precedence_;
1138  l3cam_ros::EnableAlliedCameraAutoWhiteBalance srv_enable_auto_white_balance_;
1140  l3cam_ros::ChangeAlliedCameraBalanceRatioSelector srv_balance_ratio_selector_;
1142  l3cam_ros::ChangeAlliedCameraBalanceRatio srv_balance_ratio_;
1144  l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate srv_balance_white_auto_rate_;
1146  l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance srv_balance_white_auto_tolerance_;
1148  l3cam_ros::ChangeAlliedCameraIntensityControllerRegion srv_intensity_controller_region_;
1150  l3cam_ros::ChangeAlliedCameraIntensityControllerTarget srv_intensity_controller_target_;
1152  l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_;
1154  l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_;
1156  l3cam_ros::GetAlliedCameraExposureTime srv_get_exposure_time_;
1158  l3cam_ros::GetAlliedCameraGain srv_get_gain_;
1159 
1161 
1183 
1186 
1187  }; // class AlliedWideConfiguration
1188 
1189 } // namespace l3cam_ros
1190 
1191 int main(int argc, char **argv)
1192 {
1193  ros::init(argc, argv, "allied_wide_configuration");
1194 
1196 
1197  // Check if service is available
1198  ros::Duration timeout_duration(node->timeout_secs_);
1199  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
1200  {
1201  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
1203  }
1204 
1205  int error = L3CAM_OK;
1206  bool sensor_is_available = false;
1207  // Shutdown if sensor is not available or if error returned
1208  if (node->client_get_sensors_.call(node->srv_get_sensors_))
1209  {
1210  error = node->srv_get_sensors_.response.error;
1211 
1212  if (!error)
1213  {
1214  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
1215  {
1216  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_allied_wide && node->srv_get_sensors_.response.sensors[i].sensor_available)
1217  {
1218  sensor_is_available = true;
1219  }
1220  }
1221  }
1222  else
1223  {
1224  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability: " << getErrorDescription(error));
1225  return error;
1226  }
1227  }
1228  else
1229  {
1230  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
1232  }
1233 
1234  if (sensor_is_available)
1235  {
1236  ROS_INFO("Allied Wide camera configuration is available");
1237  }
1238  else
1239  {
1240  return 0;
1241  }
1242 
1243  node->setDynamicReconfigure();
1244 
1245  node->spin();
1246 
1247  ros::shutdown();
1248  return 0;
1249 }
l3cam_ros::AlliedWideConfiguration::client_get_sensors_
ros::ServiceClient client_get_sensors_
Definition: allied_wide_configuration.cpp:124
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
l3cam_ros::AlliedWideConfiguration::srv_get_exposure_time_
l3cam_ros::GetAlliedCameraExposureTime srv_get_exposure_time_
Definition: allied_wide_configuration.cpp:1156
l3cam_ros::AlliedWideConfiguration
Definition: allied_wide_configuration.cpp:67
l3cam_ros::AlliedWideConfiguration::allied_wide_auto_white_balance_
bool allied_wide_auto_white_balance_
Definition: allied_wide_configuration.cpp:1174
l3cam_ros::AlliedWideConfiguration::client_saturation_
ros::ServiceClient client_saturation_
Definition: allied_wide_configuration.cpp:1131
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::AlliedWideConfiguration::allied_wide_auto_exposure_time_range_min_
double allied_wide_auto_exposure_time_range_min_
Definition: allied_wide_configuration.cpp:1164
l3cam_ros::AlliedWideConfiguration::client_gamma_
ros::ServiceClient client_gamma_
Definition: allied_wide_configuration.cpp:1129
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
l3cam_ros::AlliedWideConfiguration::allied_wide_streaming_protocol_
int allied_wide_streaming_protocol_
Definition: allied_wide_configuration.cpp:1181
l3cam_ros::AlliedWideConfiguration::allied_wide_auto_gain_range_max_
double allied_wide_auto_gain_range_max_
Definition: allied_wide_configuration.cpp:1169
l3cam_ros::AlliedWideConfiguration::srv_balance_white_auto_rate_
l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate srv_balance_white_auto_rate_
Definition: allied_wide_configuration.cpp:1144
ros
l3cam_ros::AlliedWideConfiguration::allied_wide_gamma_
double allied_wide_gamma_
Definition: allied_wide_configuration.cpp:1170
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
l3cam_ros::AlliedWideConfiguration::loadDefaultParams
void loadDefaultParams()
Definition: allied_wide_configuration.cpp:149
ros.h
l3cam_ros::AlliedWideConfiguration::allied_wide_auto_gain_
bool allied_wide_auto_gain_
Definition: allied_wide_configuration.cpp:1167
l3cam_ros::AlliedWideConfiguration::srv_auto_exposure_time_range_
l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange srv_auto_exposure_time_range_
Definition: allied_wide_configuration.cpp:1122
l3cam_ros::AlliedWideConfiguration::client_intensity_controller_target_
ros::ServiceClient client_intensity_controller_target_
Definition: allied_wide_configuration.cpp:1149
l3cam_ros::AlliedWideConfiguration::callExposureTime
int callExposureTime(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:466
l3cam_ros::AlliedWideConfiguration::client_exposure_time_
ros::ServiceClient client_exposure_time_
Definition: allied_wide_configuration.cpp:1117
l3cam_ros::AlliedWideConfiguration::client_balance_white_auto_rate_
ros::ServiceClient client_balance_white_auto_rate_
Definition: allied_wide_configuration.cpp:1143
ros::spinOnce
ROSCPP_DECL void spinOnce()
l3cam_ros::AlliedWideConfiguration::srv_balance_ratio_
l3cam_ros::ChangeAlliedCameraBalanceRatio srv_balance_ratio_
Definition: allied_wide_configuration.cpp:1142
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
l3cam_ros::AlliedWideConfiguration::client_enable_auto_exposure_time_
ros::ServiceClient client_enable_auto_exposure_time_
Definition: allied_wide_configuration.cpp:1119
l3cam_ros::AlliedWideConfiguration::setDynamicReconfigure
void setDynamicReconfigure()
Definition: allied_wide_configuration.cpp:105
l3cam_ros::AlliedWideConfiguration::srv_get_rtsp_pipeline_
l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_
Definition: allied_wide_configuration.cpp:1154
l3cam_ros::AlliedWideConfiguration::callStreamingProtocol
int callStreamingProtocol(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:1060
l3cam_ros::AlliedWideConfiguration::srv_get_gain_
l3cam_ros::GetAlliedCameraGain srv_get_gain_
Definition: allied_wide_configuration.cpp:1158
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros::AlliedWideConfiguration::srv_intensity_controller_region_
l3cam_ros::ChangeAlliedCameraIntensityControllerRegion srv_intensity_controller_region_
Definition: allied_wide_configuration.cpp:1148
l3cam_ros
Definition: l3cam_ros_node.hpp:133
l3cam_ros::AlliedWideConfiguration::allied_wide_auto_gain_range_min_
double allied_wide_auto_gain_range_min_
Definition: allied_wide_configuration.cpp:1168
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
l3cam_ros::AlliedWideConfiguration::AlliedWideConfiguration
AlliedWideConfiguration()
Definition: allied_wide_configuration.cpp:70
l3cam_ros::AlliedWideConfiguration::srv_balance_white_auto_tolerance_
l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance srv_balance_white_auto_tolerance_
Definition: allied_wide_configuration.cpp:1146
ros::ok
ROSCPP_DECL bool ok()
l3cam_ros::AlliedWideConfiguration::callAutoExposureTimeRange
int callAutoExposureTimeRange(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:555
l3cam_ros::L3Cam::timeout_secs_
int timeout_secs_
Definition: l3cam_ros_node.hpp:404
l3cam_ros::AlliedWideConfiguration::client_change_streaming_protocol_
ros::ServiceClient client_change_streaming_protocol_
Definition: allied_wide_configuration.cpp:1151
ros::ServiceServer
l3cam_ros::AlliedWideConfiguration::srv_enable_auto_gain_
l3cam_ros::EnableAlliedCameraAutoGain srv_enable_auto_gain_
Definition: allied_wide_configuration.cpp:1126
l3cam_ros::AlliedWideConfiguration::callBalanceRatio
int callBalanceRatio(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:910
l3cam_ros::AlliedWideConfiguration::allied_wide_hue_
double allied_wide_hue_
Definition: allied_wide_configuration.cpp:1172
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros::AlliedWideConfiguration::spin
void spin()
Definition: allied_wide_configuration.cpp:113
l3cam_ros::AlliedWideConfiguration::srv_auto_gain_range_
l3cam_ros::ChangeAlliedCameraAutoGainRange srv_auto_gain_range_
Definition: allied_wide_configuration.cpp:1128
l3cam_ros::AlliedWideConfiguration::client_hue_
ros::ServiceClient client_hue_
Definition: allied_wide_configuration.cpp:1133
l3cam_ros::AlliedWideConfiguration::allied_wide_intensity_auto_precedence_
int allied_wide_intensity_auto_precedence_
Definition: allied_wide_configuration.cpp:1173
l3cam_ros::AlliedWideConfiguration::callRtspPipeline
int callRtspPipeline(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:1090
l3cam_ros::AlliedWideConfiguration::srv_sensor_disconnected_
ros::ServiceServer srv_sensor_disconnected_
Definition: allied_wide_configuration.cpp:1160
l3cam_ros::AlliedWideConfiguration::allied_wide_intensity_controller_target_
double allied_wide_intensity_controller_target_
Definition: allied_wide_configuration.cpp:1180
l3cam_ros_utils.hpp
l3cam_ros::AlliedWideConfiguration::client_gain_
ros::ServiceClient client_gain_
Definition: allied_wide_configuration.cpp:1123
l3cam_ros::AlliedWideConfiguration::client_auto_exposure_time_range_
ros::ServiceClient client_auto_exposure_time_range_
Definition: allied_wide_configuration.cpp:1121
l3cam_ros::AlliedWideConfiguration::client_enable_auto_white_balance_
ros::ServiceClient client_enable_auto_white_balance_
Definition: allied_wide_configuration.cpp:1137
l3cam_ros::AlliedWideConfiguration::server_
dynamic_reconfigure::Server< l3cam_ros::AlliedWideConfig > * server_
Definition: allied_wide_configuration.cpp:1115
l3cam_ros::AlliedWideConfiguration::allied_wide_auto_exposure_time_
bool allied_wide_auto_exposure_time_
Definition: allied_wide_configuration.cpp:1163
l3cam_ros::AlliedWideConfiguration::callAutoExposureTime
int callAutoExposureTime(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:504
l3cam_ros::AlliedWideConfiguration::callAutoGainRange
int callAutoGainRange(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:687
l3cam_ros::AlliedWideConfiguration::allied_wide_balance_white_auto_tolerance_
double allied_wide_balance_white_auto_tolerance_
Definition: allied_wide_configuration.cpp:1178
l3cam_ros::AlliedWideConfiguration::callGamma
int callGamma(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:730
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::AlliedWideConfiguration::srv_get_sensors_
l3cam_ros::GetSensorsAvailable srv_get_sensors_
Definition: allied_wide_configuration.cpp:125
l3cam_ros::AlliedWideConfiguration::client_balance_white_auto_tolerance_
ros::ServiceClient client_balance_white_auto_tolerance_
Definition: allied_wide_configuration.cpp:1145
l3cam_ros::AlliedWideConfiguration::srv_intensity_auto_precedence_
l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence srv_intensity_auto_precedence_
Definition: allied_wide_configuration.cpp:1136
main
int main(int argc, char **argv)
Definition: allied_wide_configuration.cpp:1191
l3cam_ros::AlliedWideConfiguration::client_intensity_controller_region_
ros::ServiceClient client_intensity_controller_region_
Definition: allied_wide_configuration.cpp:1147
l3cam_ros::AlliedWideConfiguration::client_balance_ratio_selector_
ros::ServiceClient client_balance_ratio_selector_
Definition: allied_wide_configuration.cpp:1139
ros::ServiceClient
l3cam_ros::AlliedWideConfiguration::srv_hue_
l3cam_ros::ChangeAlliedCameraHue srv_hue_
Definition: allied_wide_configuration.cpp:1134
l3cam_ros::AlliedWideConfiguration::callAutoGain
int callAutoGain(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:636
l3cam_ros::AlliedWideConfiguration::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: allied_wide_configuration.cpp:1099
l3cam_ros::AlliedWideConfiguration::srv_intensity_controller_target_
l3cam_ros::ChangeAlliedCameraIntensityControllerTarget srv_intensity_controller_target_
Definition: allied_wide_configuration.cpp:1150
l3cam_ros::AlliedWideConfiguration::srv_balance_ratio_selector_
l3cam_ros::ChangeAlliedCameraBalanceRatioSelector srv_balance_ratio_selector_
Definition: allied_wide_configuration.cpp:1140
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
l3cam_ros::AlliedWideConfiguration::client_intensity_auto_precedence_
ros::ServiceClient client_intensity_auto_precedence_
Definition: allied_wide_configuration.cpp:1135
l3cam_ros::AlliedWideConfiguration::callIntensityControllerTarget
int callIntensityControllerTarget(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:1030
l3cam_ros::AlliedWideConfiguration::client_enable_auto_gain_
ros::ServiceClient client_enable_auto_gain_
Definition: allied_wide_configuration.cpp:1125
l3cam_ros::AlliedWideConfiguration::m_shutdown_requested
bool m_shutdown_requested
Definition: allied_wide_configuration.cpp:1185
l3cam_ros::AlliedWideConfiguration::allied_wide_balance_white_auto_rate_
double allied_wide_balance_white_auto_rate_
Definition: allied_wide_configuration.cpp:1177
l3cam_ros::AlliedWideConfiguration::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: allied_wide_configuration.cpp:131
ros::NodeHandle::NodeHandle
NodeHandle(const NodeHandle &parent, const std::string &ns)
l3cam_ros::AlliedWideConfiguration::allied_wide_intensity_controller_region_
int allied_wide_intensity_controller_region_
Definition: allied_wide_configuration.cpp:1179
l3cam_ros::AlliedWideConfiguration::srv_enable_auto_white_balance_
l3cam_ros::EnableAlliedCameraAutoWhiteBalance srv_enable_auto_white_balance_
Definition: allied_wide_configuration.cpp:1138
l3cam_ros::AlliedWideConfiguration::srv_saturation_
l3cam_ros::ChangeAlliedCameraSaturation srv_saturation_
Definition: allied_wide_configuration.cpp:1132
l3cam_ros::AlliedWideConfiguration::allied_wide_saturation_
double allied_wide_saturation_
Definition: allied_wide_configuration.cpp:1171
l3cam_ros::AlliedWideConfiguration::allied_wide_auto_exposure_time_range_max_
double allied_wide_auto_exposure_time_range_max_
Definition: allied_wide_configuration.cpp:1165
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::AlliedWideConfiguration::client_get_gain_
ros::ServiceClient client_get_gain_
Definition: allied_wide_configuration.cpp:1157
l3cam_ros::AlliedWideConfiguration::callSaturation
int callSaturation(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:760
l3cam_ros::AlliedWideConfiguration::client_get_rtsp_pipeline_
ros::ServiceClient client_get_rtsp_pipeline_
Definition: allied_wide_configuration.cpp:1153
l3cam_ros::AlliedWideConfiguration::callAutoWhiteBalance
int callAutoWhiteBalance(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:850
l3cam_ros::AlliedWideConfiguration::configureDefault
void configureDefault(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:175
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
l3cam_ros::AlliedWideConfiguration::callBalanceWhiteAutoTolerance
int callBalanceWhiteAutoTolerance(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:970
l3cam_ros::AlliedWideConfiguration::client_auto_gain_range_
ros::ServiceClient client_auto_gain_range_
Definition: allied_wide_configuration.cpp:1127
l3cam_ros::AlliedWideConfiguration::callBalanceRatioSelector
int callBalanceRatioSelector(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:880
l3cam_ros::AlliedWideConfiguration::timeout_secs_
int timeout_secs_
Definition: allied_wide_configuration.cpp:127
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
l3cam_ros::AlliedWideConfiguration::callIntensityAutoPrecedence
int callIntensityAutoPrecedence(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:820
l3cam_ros::AlliedWideConfiguration::client_balance_ratio_
ros::ServiceClient client_balance_ratio_
Definition: allied_wide_configuration.cpp:1141
l3cam_ros::AlliedWideConfiguration::allied_wide_exposure_time_
double allied_wide_exposure_time_
Definition: allied_wide_configuration.cpp:1162
l3cam_ros::AlliedWideConfiguration::srv_gamma_
l3cam_ros::ChangeAlliedCameraGamma srv_gamma_
Definition: allied_wide_configuration.cpp:1130
l3cam_ros::AlliedWideConfiguration::parametersCallback
void parametersCallback(AlliedWideConfig &config, uint32_t level)
Definition: allied_wide_configuration.cpp:380
l3cam_ros::AlliedWideConfiguration::callHue
int callHue(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:790
ros::Duration::sleep
bool sleep() const
l3cam_ros::AlliedWideConfiguration::srv_enable_auto_exposure_time_
l3cam_ros::EnableAlliedCameraAutoExposureTime srv_enable_auto_exposure_time_
Definition: allied_wide_configuration.cpp:1120
l3cam_ros::AlliedWideConfiguration::callBalanceWhiteAutoRate
int callBalanceWhiteAutoRate(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:940
l3cam_ros::AlliedWideConfiguration::srv_exposure_time_
l3cam_ros::ChangeAlliedCameraExposureTime srv_exposure_time_
Definition: allied_wide_configuration.cpp:1118
l3cam_ros::AlliedWideConfiguration::allied_wide_rtsp_pipeline_
std::string allied_wide_rtsp_pipeline_
Definition: allied_wide_configuration.cpp:1182
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
l3cam_ros::AlliedWideConfiguration::client_get_exposure_time_
ros::ServiceClient client_get_exposure_time_
Definition: allied_wide_configuration.cpp:1155
ROS_INFO
#define ROS_INFO(...)
ros::Duration
l3cam_ros::AlliedWideConfiguration::allied_wide_balance_ratio_selector_
int allied_wide_balance_ratio_selector_
Definition: allied_wide_configuration.cpp:1175
l3cam_ros::AlliedWideConfiguration::callIntensityControllerRegion
int callIntensityControllerRegion(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:1000
l3cam_ros::AlliedWideConfiguration::srv_gain_
l3cam_ros::ChangeAlliedCameraGain srv_gain_
Definition: allied_wide_configuration.cpp:1124
l3cam_ros::AlliedWideConfiguration::callGain
int callGain(l3cam_ros::AlliedWideConfig &config)
Definition: allied_wide_configuration.cpp:598
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
ros::NodeHandle
l3cam_ros::AlliedWideConfiguration::allied_wide_balance_ratio_
double allied_wide_balance_ratio_
Definition: allied_wide_configuration.cpp:1176
l3cam_ros::AlliedWideConfiguration::srv_change_streaming_protocol_
l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_
Definition: allied_wide_configuration.cpp:1152
l3cam_ros::AlliedWideConfiguration::m_default_configured
bool m_default_configured
Definition: allied_wide_configuration.cpp:1184
l3cam_ros::AlliedWideConfiguration::allied_wide_gain_
double allied_wide_gain_
Definition: allied_wide_configuration.cpp:1166


l3cam_ros
Author(s): Beamagine
autogenerated on Wed May 28 2025 02:53:15