rgb_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/RgbConfig.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/ChangeRgbCameraBrightness.h"
40 #include "l3cam_ros/ChangeRgbCameraContrast.h"
41 #include "l3cam_ros/ChangeRgbCameraSaturation.h"
42 #include "l3cam_ros/ChangeRgbCameraSharpness.h"
43 #include "l3cam_ros/ChangeRgbCameraGamma.h"
44 #include "l3cam_ros/ChangeRgbCameraGain.h"
45 #include "l3cam_ros/EnableRgbCameraAutoWhiteBalance.h"
46 #include "l3cam_ros/ChangeRgbCameraWhiteBalance.h"
47 #include "l3cam_ros/EnableRgbCameraAutoExposureTime.h"
48 #include "l3cam_ros/ChangeRgbCameraExposureTime.h"
49 #include "l3cam_ros/ChangeStreamingProtocol.h"
50 #include "l3cam_ros/GetRtspPipeline.h"
51 
52 #include "l3cam_ros/SensorDisconnected.h"
53 
54 #include "l3cam_ros_utils.hpp"
55 
56 namespace l3cam_ros
57 {
59  {
60  public:
61  explicit RgbConfiguration() : ros::NodeHandle("~")
62  {
63  client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>("/L3Cam/l3cam_ros_node/get_sensors_available");
64  client_brightness_ = serviceClient<l3cam_ros::ChangeRgbCameraBrightness>("/L3Cam/l3cam_ros_node/change_rgb_brightness");
65  client_contrast_ = serviceClient<l3cam_ros::ChangeRgbCameraContrast>("/L3Cam/l3cam_ros_node/change_rgb_contrast");
66  client_saturation_ = serviceClient<l3cam_ros::ChangeRgbCameraSaturation>("/L3Cam/l3cam_ros_node/change_rgb_saturation");
67  client_sharpness_ = serviceClient<l3cam_ros::ChangeRgbCameraSharpness>("/L3Cam/l3cam_ros_node/change_rgb_sharpness");
68  client_gamma_ = serviceClient<l3cam_ros::ChangeRgbCameraGamma>("/L3Cam/l3cam_ros_node/change_rgb_gamma");
69  client_gain_ = serviceClient<l3cam_ros::ChangeRgbCameraGain>("/L3Cam/l3cam_ros_node/change_rgb_gain");
70  client_enable_auto_white_balance_ = serviceClient<l3cam_ros::EnableRgbCameraAutoWhiteBalance>("/L3Cam/l3cam_ros_node/enable_rgb_auto_white_balance");
71  client_white_balance_ = serviceClient<l3cam_ros::ChangeRgbCameraWhiteBalance>("/L3Cam/l3cam_ros_node/change_rgb_white_balance");
72  client_enable_auto_exposure_time_ = serviceClient<l3cam_ros::EnableRgbCameraAutoExposureTime>("/L3Cam/l3cam_ros_node/enable_rgb_auto_exposure_time");
73  client_exposure_time_ = serviceClient<l3cam_ros::ChangeRgbCameraExposureTime>("/L3Cam/l3cam_ros_node/change_rgb_exposure_time");
74  client_change_streaming_protocol_ = serviceClient<l3cam_ros::ChangeStreamingProtocol>("/L3Cam/l3cam_ros_node/change_streaming_protocol");
75  client_get_rtsp_pipeline_ = serviceClient<l3cam_ros::GetRtspPipeline>("/L3Cam/l3cam_ros_node/get_rtsp_pipeline");
76 
78 
79  // Create service server
81 
82  m_default_configured = false;
83  m_shutdown_requested = false;
84  }
85 
87  {
88  // Dynamic reconfigure callback
89  // server_ is a pointer so we only declare it if sensor is available and reconfigure should be available
90  server_ = new dynamic_reconfigure::Server<l3cam_ros::RgbConfig>;
91  server_->setCallback(std::bind(&RgbConfiguration::parametersCallback, this, std::placeholders::_1, std::placeholders::_2));
92  }
93 
94  void spin()
95  {
96  while (ros::ok() && !m_shutdown_requested)
97  {
98  ros::spinOnce();
99  ros::Duration(0.1).sleep();
100  }
101 
102  ros::shutdown();
103  }
104 
106  l3cam_ros::GetSensorsAvailable srv_get_sensors_;
107 
109 
110  private:
111  template <typename T>
112  void loadParam(const std::string &param_name, T &param_var, const T &default_val)
113  {
114  std::string full_param_name;
115 
116  if (searchParam(param_name, full_param_name))
117  {
118  if (!getParam(full_param_name, param_var))
119  {
120  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
121  }
122  }
123  else
124  {
125  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
126  param_var = default_val;
127  }
128  }
129 
131  {
132  // Get and save parameters
133  loadParam("timeout_secs", timeout_secs_, 60);
134  loadParam("rgb_brightness", rgb_brightness_, 0);
135  loadParam("rgb_contrast", rgb_contrast_, 10);
136  loadParam("rgb_saturation", rgb_saturation_, 16);
137  loadParam("rgb_sharpness", rgb_sharpness_, 16);
138  loadParam("rgb_gamma", rgb_gamma_, 220);
139  loadParam("rgb_gain", rgb_gain_, 0);
140  loadParam("rgb_auto_white_balance", rgb_auto_white_balance_, true);
141  loadParam("rgb_white_balance", rgb_white_balance_, 5000);
142  loadParam("rgb_auto_exposure_time", rgb_auto_exposure_time_, true);
143  loadParam("rgb_exposure_time", rgb_exposure_time_, 156);
144  loadParam("rgb_streaming_protocol", rgb_streaming_protocol_, 0);
145  }
146 
147  void configureDefault(l3cam_ros::RgbConfig &config)
148  {
149  // Configure default params to dynamix reconfigure if inside range
150  if (rgb_brightness_ >= -15 && rgb_brightness_ <= 15)
151  {
152  config.rgb_brightness = rgb_brightness_;
153  }
154  else
155  {
156  rgb_brightness_ = config.rgb_brightness;
157  }
158 
159  if (rgb_contrast_ >= 0 && rgb_contrast_ <= 30)
160  {
161  config.rgb_contrast = rgb_contrast_;
162  }
163  else
164  {
165  rgb_contrast_ = config.rgb_contrast;
166  }
167 
168  if (rgb_saturation_ >= 0 && rgb_saturation_ <= 60)
169  {
170  config.rgb_saturation = rgb_saturation_;
171  }
172  else
173  {
174  rgb_saturation_ = config.rgb_saturation;
175  }
176 
177  if (rgb_sharpness_ >= 0 && rgb_sharpness_ <= 127)
178  {
179  config.rgb_sharpness = rgb_sharpness_;
180  }
181  else
182  {
183  rgb_sharpness_ = config.rgb_sharpness;
184  }
185 
186  if (rgb_gamma_ >= 40 && rgb_gamma_ <= 500)
187  {
188  config.rgb_gamma = rgb_gamma_;
189  }
190  else
191  {
192  rgb_gamma_ = config.rgb_gamma;
193  }
194 
195  if (rgb_gain_ >= 0 && rgb_gain_ <= 63)
196  {
197  config.rgb_gain = rgb_gain_;
198  }
199  else
200  {
201  rgb_gain_ = config.rgb_gain;
202  }
203 
204  config.rgb_auto_white_balance = rgb_auto_white_balance_;
205 
206  if (rgb_white_balance_ >= 1000 && rgb_white_balance_ <= 10000)
207  {
208  config.rgb_white_balance = rgb_white_balance_;
209  }
210  else
211  {
212  rgb_white_balance_ = config.rgb_white_balance;
213  }
214 
215  config.rgb_auto_exposure_time = rgb_auto_exposure_time_;
216 
217  if (rgb_exposure_time_ >= 1 && rgb_exposure_time_ <= 10000)
218  {
219  config.rgb_exposure_time = rgb_exposure_time_;
220  }
221  else
222  {
223  rgb_exposure_time_ = config.rgb_exposure_time;
224  }
225 
227  {
228  config.rgb_streaming_protocol = rgb_streaming_protocol_;
229  }
230  else
231  {
232  rgb_streaming_protocol_ = config.rgb_streaming_protocol;
233  }
234 
235  // Get pipeline
236  int error = L3CAM_OK;
237  ros::Duration timeout_duration(timeout_secs_);
238  if (!client_get_rtsp_pipeline_.waitForExistence(timeout_duration))
239  {
240  ROS_ERROR_STREAM(this->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
241  }
242  else
243  {
244  srv_get_rtsp_pipeline_.request.sensor_type = (int)sensorTypes::sensor_econ_rgb;
246  {
247  error = srv_get_rtsp_pipeline_.response.error;
248  if (!error)
249  {
250  rgb_rtsp_pipeline_ = srv_get_rtsp_pipeline_.response.pipeline;
251  config.rgb_rtsp_pipeline = srv_get_rtsp_pipeline_.response.pipeline;
252  }
253  else
254  {
255  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting RTSP pipeline: " << getErrorDescription(error));
256  config.rgb_rtsp_pipeline = "";
257  rgb_rtsp_pipeline_ = "";
258  }
259  }
260  else
261  {
262  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service get_rtsp_pipeline");
263  config.rgb_rtsp_pipeline = "";
264  rgb_rtsp_pipeline_ = "";
265  }
266  }
267 
268  m_default_configured = true;
269  }
270 
271  void parametersCallback(l3cam_ros::RgbConfig &config, uint32_t level)
272  {
273  int error = L3CAM_OK;
274 
276  {
277  configureDefault(config);
278  }
279  else
280  {
281  // Filter by parameter and call service
282  switch (level)
283  {
284  case 0: // rgb_brightness
285  error = callRgbBrightness(config);
286  break;
287  case 1: // rgb_contrast
288  error = callRgbContrast(config);
289  break;
290  case 2: // rgb_saturation
291  error = callRgbSaturation(config);
292  break;
293  case 3: // rgb_sharpness
294  error = callRgbSharpness(config);
295  break;
296  case 4: // rgb_gamma
297  error = callRgbGamma(config);
298  break;
299  case 5: // rgb_gain
300  error = callRgbGain(config);
301  break;
302  case 6: // rgb_auto_white_balance
303  error = callRgbAutoWhiteBalance(config);
304  break;
305  case 7: // rgb_white_balance
306  error = callRgbWhiteBalance(config);
307  break;
308  case 8: // rgb_auto_exposure_time
309  error = callRgbAutoExposureTime(config);
310  break;
311  case 9: // rgb_exposure_time
312  error = callRgbExposureTime(config);
313  break;
314  case 10: // rgb_streaming_protocol
315  error = callRgbStreamingProtocol(config);
316  break;
317  case 11: // rgb_rtsp_pipeline
318  error = callRgbRtspPipeline(config);
319  break;
320  }
321  }
322 
323  if (error)
324  {
325  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while changing parameter: " << getErrorDescription(error));
326  }
327  }
328 
329  // Service calls
330  int callRgbBrightness(l3cam_ros::RgbConfig &config)
331  {
332  int error = L3CAM_OK;
333 
334  srv_brightness_.request.brightness = config.rgb_brightness;
336  {
337  error = srv_brightness_.response.error;
338  if (!error)
339  {
340  // Parameter changed successfully, save value
341  rgb_brightness_ = config.rgb_brightness;
342  }
343  else
344  {
345  // Parameter could not be changed, reset parameter to value before change
346  config.rgb_brightness = rgb_brightness_;
347  }
348  }
349  else
350  {
351  // Service could not be called, reset parameter to value before change
352  config.rgb_brightness = rgb_brightness_;
354  }
355 
356  return error;
357  }
358 
359  int callRgbContrast(l3cam_ros::RgbConfig &config)
360  {
361  int error = L3CAM_OK;
362 
363  srv_contrast_.request.contrast = config.rgb_contrast;
365  {
366  error = srv_contrast_.response.error;
367  if (!error)
368  {
369  // Parameter changed successfully, save value
370  rgb_contrast_ = config.rgb_contrast;
371  }
372  else
373  {
374  // Parameter could not be changed, reset parameter to value before change
375  config.rgb_contrast = rgb_contrast_;
376  }
377  }
378  else
379  {
380  // Service could not be called, reset parameter to value before change
381  config.rgb_contrast = rgb_contrast_;
383  }
384 
385  return error;
386  }
387 
388  int callRgbSaturation(l3cam_ros::RgbConfig &config)
389  {
390  int error = L3CAM_OK;
391 
392  srv_saturation_.request.saturation = config.rgb_saturation;
394  {
395  error = srv_saturation_.response.error;
396  if (!error)
397  {
398  // Parameter changed successfully, save value
399  rgb_saturation_ = config.rgb_saturation;
400  }
401  else
402  {
403  // Parameter could not be changed, reset parameter to value before change
404  config.rgb_saturation = rgb_saturation_;
405  }
406  }
407  else
408  {
409  // Service could not be called, reset parameter to value before change
410  config.rgb_saturation = rgb_saturation_;
412  }
413 
414  return error;
415  }
416 
417  int callRgbSharpness(l3cam_ros::RgbConfig &config)
418  {
419  int error = L3CAM_OK;
420 
421  srv_sharpness_.request.sharpness = config.rgb_sharpness;
423  {
424  error = srv_sharpness_.response.error;
425  if (!error)
426  {
427  // Parameter changed successfully, save value
428  rgb_sharpness_ = config.rgb_sharpness;
429  }
430  else
431  {
432  // Parameter could not be changed, reset parameter to value before change
433  config.rgb_sharpness = rgb_sharpness_;
434  }
435  }
436  else
437  {
438  // Service could not be called, reset parameter to value before change
439  config.rgb_sharpness = rgb_sharpness_;
441  }
442 
443  return error;
444  }
445 
446  int callRgbGamma(l3cam_ros::RgbConfig &config)
447  {
448  int error = L3CAM_OK;
449 
450  srv_gamma_.request.gamma = config.rgb_gamma;
452  {
453  error = srv_gamma_.response.error;
454  if (!error)
455  {
456  // Parameter changed successfully, save value
457  rgb_gamma_ = config.rgb_gamma;
458  }
459  else
460  {
461  // Parameter could not be changed, reset parameter to value before change
462  config.rgb_gamma = rgb_gamma_;
463  }
464  }
465  else
466  {
467  // Service could not be called, reset parameter to value before change
468  config.rgb_gamma = rgb_gamma_;
470  }
471 
472  return error;
473  }
474 
475  int callRgbGain(l3cam_ros::RgbConfig &config)
476  {
477  int error = L3CAM_OK;
478 
479  srv_gain_.request.gain = config.rgb_gain;
481  {
482  error = srv_gain_.response.error;
483  if (!error)
484  {
485  // Parameter changed successfully, save value
486  rgb_gain_ = config.rgb_gain;
487  }
488  else
489  {
490  // Parameter could not be changed, reset parameter to value before change
491  config.rgb_gain = rgb_gain_;
492  }
493  }
494  else
495  {
496  // Service could not be called, reset parameter to value before change
497  config.rgb_gain = rgb_gain_;
499  }
500 
501  return error;
502  }
503 
504  int callRgbAutoWhiteBalance(l3cam_ros::RgbConfig &config)
505  {
506  int error = L3CAM_OK;
507 
508  srv_enable_auto_white_balance_.request.enabled = config.rgb_auto_white_balance;
510  {
511  error = srv_enable_auto_white_balance_.response.error;
512  if (!error)
513  {
514  // Parameter changed successfully, save value
515  rgb_auto_white_balance_ = config.rgb_auto_white_balance;
516  }
517  else
518  {
519  // Parameter could not be changed, reset parameter to value before change
520  config.rgb_auto_white_balance = rgb_auto_white_balance_;
521  }
522  }
523  else
524  {
525  // Service could not be called, reset parameter to value before change
526  config.rgb_auto_white_balance = rgb_auto_white_balance_;
528  }
529 
530  return error;
531  }
532 
533  int callRgbWhiteBalance(l3cam_ros::RgbConfig &config)
534  {
535  int error = L3CAM_OK;
536 
538  {
539  srv_white_balance_.request.white_balance = config.rgb_white_balance;
541  {
542  error = srv_white_balance_.response.error;
543  if (!error)
544  {
545  // Parameter changed successfully, save value
546  rgb_white_balance_ = config.rgb_white_balance;
547  }
548  else
549  {
550  // Parameter could not be changed, reset parameter to value before change
551  config.rgb_white_balance = rgb_white_balance_;
552  }
553  }
554  else
555  {
556  // Service could not be called, reset parameter to value before change
557  config.rgb_white_balance = rgb_white_balance_;
559  }
560  }
561  else
562  {
563  ROS_WARN_STREAM(this->getNamespace() << " RGB camera auto white balance must be disabled to change white balance");
564  config.rgb_white_balance = rgb_white_balance_;
565  }
566 
567  return error;
568  }
569 
570  int callRgbAutoExposureTime(l3cam_ros::RgbConfig &config)
571  {
572  int error = L3CAM_OK;
573 
574  srv_enable_auto_exposure_time_.request.enabled = config.rgb_auto_exposure_time;
576  {
577  error = srv_enable_auto_exposure_time_.response.error;
578  if (!error)
579  {
580  // Parameter changed successfully, save value
581  rgb_auto_exposure_time_ = config.rgb_auto_exposure_time;
582  }
583  else
584  {
585  // Parameter could not be changed, reset parameter to value before change
586  config.rgb_auto_exposure_time = rgb_auto_exposure_time_;
587  }
588  }
589  else
590  {
591  // Service could not be called, reset parameter to value before change
592  config.rgb_auto_exposure_time = rgb_auto_exposure_time_;
594  }
595 
596  return error;
597  }
598 
599  int callRgbExposureTime(l3cam_ros::RgbConfig &config)
600  {
601  int error = L3CAM_OK;
602 
604  {
605  srv_exposure_time_.request.exposure_time = config.rgb_exposure_time;
607  {
608  error = srv_exposure_time_.response.error;
609  if (!error)
610  {
611  // Parameter changed successfully, save value
612  rgb_exposure_time_ = config.rgb_exposure_time;
613  }
614  else
615  {
616  // Parameter could not be changed, reset parameter to value before change
617  config.rgb_exposure_time = rgb_exposure_time_;
618  }
619  }
620  else
621  {
622  // Service could not be called, reset parameter to value before change
623  config.rgb_exposure_time = rgb_exposure_time_;
625  }
626  }
627  else
628  {
629  ROS_WARN_STREAM(this->getNamespace() << " RGB camera auto exposure time must be disabled to change exposure time");
630  config.rgb_exposure_time = rgb_exposure_time_;
631  }
632 
633  return error;
634  }
635 
636  int callRgbStreamingProtocol(l3cam_ros::RgbConfig &config)
637  {
638  int error = L3CAM_OK;
639 
640  srv_change_streaming_protocol_.request.protocol = config.rgb_streaming_protocol;
641  srv_change_streaming_protocol_.request.sensor_type = (int)sensorTypes::sensor_econ_rgb;
643  {
644  error = srv_change_streaming_protocol_.response.error;
645  if (!error)
646  {
647  // Parameter changed successfully, save value
648  rgb_streaming_protocol_ = config.rgb_streaming_protocol;
649  }
650  else
651  {
652  // Parameter could not be changed, reset parameter to value before change
653  config.rgb_streaming_protocol = rgb_streaming_protocol_;
654  }
655  }
656  else
657  {
658  // Service could not be called, reset parameter to value before change
659  config.rgb_streaming_protocol = rgb_streaming_protocol_;
661  }
662 
663  return error;
664  }
665 
666  int callRgbRtspPipeline(l3cam_ros::RgbConfig &config)
667  {
668  // Read-only
669  ROS_WARN_STREAM(this->getNamespace() << " The RTSP Pipeline parameter is read-only, only changeable at launch");
670  config.rgb_rtsp_pipeline = rgb_rtsp_pipeline_;
671 
672  return L3CAM_OK;
673  }
674 
675  bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
676  {
677  ROS_BMG_UNUSED(res);
678  if (req.code == 0)
679  {
680  ROS_INFO_STREAM("Exiting " << this->getNamespace() << " cleanly.");
681  }
682  else
683  {
684  ROS_WARN_STREAM("Exiting " << this->getNamespace() << ". Sensor got disconnected with error " << req.code << ": " << getErrorDescription(req.code));
685  }
686 
687  m_shutdown_requested = true;
688  return true;
689  }
690 
691  dynamic_reconfigure::Server<l3cam_ros::RgbConfig> *server_;
692 
694  l3cam_ros::ChangeRgbCameraBrightness srv_brightness_;
696  l3cam_ros::ChangeRgbCameraContrast srv_contrast_;
698  l3cam_ros::ChangeRgbCameraSaturation srv_saturation_;
700  l3cam_ros::ChangeRgbCameraSharpness srv_sharpness_;
702  l3cam_ros::ChangeRgbCameraGamma srv_gamma_;
704  l3cam_ros::ChangeRgbCameraGain srv_gain_;
706  l3cam_ros::EnableRgbCameraAutoWhiteBalance srv_enable_auto_white_balance_;
708  l3cam_ros::ChangeRgbCameraWhiteBalance srv_white_balance_;
710  l3cam_ros::EnableRgbCameraAutoExposureTime srv_enable_auto_exposure_time_;
712  l3cam_ros::ChangeRgbCameraExposureTime srv_exposure_time_;
714  l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_;
716  l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_;
717 
719 
731  std::string rgb_rtsp_pipeline_;
732 
735 
736  }; // class RgbConfiguration
737 
738 } // namespace l3cam_ros
739 
740 int main(int argc, char **argv)
741 {
742  ros::init(argc, argv, "rgb_configuration");
743 
745 
746  // Check if service is available
747  ros::Duration timeout_duration(node->timeout_secs_);
748  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
749  {
750  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
752  }
753 
754  int error = L3CAM_OK;
755  bool sensor_is_available = false;
756  // Shutdown if sensor is not available or if error returned
757  if (node->client_get_sensors_.call(node->srv_get_sensors_))
758  {
759  error = node->srv_get_sensors_.response.error;
760 
761  if (!error)
762  {
763  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
764  {
765  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_econ_rgb && node->srv_get_sensors_.response.sensors[i].sensor_available)
766  {
767  sensor_is_available = true;
768  }
769  }
770  }
771  else
772  {
773  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability: " << getErrorDescription(error));
774  return error;
775  }
776  }
777  else
778  {
779  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
781  }
782 
783  if (sensor_is_available)
784  {
785  ROS_INFO("RGB configuration is available");
786  }
787  else
788  {
789  return 0;
790  }
791 
792  node->setDynamicReconfigure();
793 
794  node->spin();
795 
796  ros::shutdown();
797  return 0;
798 }
l3cam_ros::RgbConfiguration::configureDefault
void configureDefault(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:147
l3cam_ros::RgbConfiguration::client_white_balance_
ros::ServiceClient client_white_balance_
Definition: rgb_configuration.cpp:707
l3cam_ros::RgbConfiguration::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: rgb_configuration.cpp:675
l3cam_ros::RgbConfiguration::RgbConfiguration
RgbConfiguration()
Definition: rgb_configuration.cpp:61
l3cam_ros::RgbConfiguration::rgb_exposure_time_
int rgb_exposure_time_
Definition: rgb_configuration.cpp:729
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
l3cam_ros::RgbConfiguration::setDynamicReconfigure
void setDynamicReconfigure()
Definition: rgb_configuration.cpp:86
l3cam_ros::RgbConfiguration::callRgbGamma
int callRgbGamma(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:446
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
l3cam_ros::RgbConfiguration::client_enable_auto_white_balance_
ros::ServiceClient client_enable_auto_white_balance_
Definition: rgb_configuration.cpp:705
l3cam_ros::RgbConfiguration::loadDefaultParams
void loadDefaultParams()
Definition: rgb_configuration.cpp:130
l3cam_ros::RgbConfiguration::callRgbWhiteBalance
int callRgbWhiteBalance(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:533
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::RgbConfiguration::rgb_sharpness_
int rgb_sharpness_
Definition: rgb_configuration.cpp:723
l3cam_ros::RgbConfiguration::client_saturation_
ros::ServiceClient client_saturation_
Definition: rgb_configuration.cpp:697
l3cam_ros::RgbConfiguration::callRgbSharpness
int callRgbSharpness(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:417
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
l3cam_ros::RgbConfiguration::callRgbBrightness
int callRgbBrightness(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:330
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
l3cam_ros::RgbConfiguration::callRgbAutoExposureTime
int callRgbAutoExposureTime(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:570
l3cam_ros::RgbConfiguration::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: rgb_configuration.cpp:112
l3cam_ros::RgbConfiguration::callRgbContrast
int callRgbContrast(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:359
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
l3cam_ros::RgbConfiguration::callRgbSaturation
int callRgbSaturation(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:388
l3cam_ros::RgbConfiguration::rgb_contrast_
int rgb_contrast_
Definition: rgb_configuration.cpp:721
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros
Definition: l3cam_ros_node.hpp:133
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
l3cam_ros::RgbConfiguration::spin
void spin()
Definition: rgb_configuration.cpp:94
ros::ok
ROSCPP_DECL bool ok()
l3cam_ros::L3Cam::timeout_secs_
int timeout_secs_
Definition: l3cam_ros_node.hpp:404
ros::ServiceServer
l3cam_ros::RgbConfiguration::rgb_gain_
int rgb_gain_
Definition: rgb_configuration.cpp:725
l3cam_ros::RgbConfiguration::parametersCallback
void parametersCallback(l3cam_ros::RgbConfig &config, uint32_t level)
Definition: rgb_configuration.cpp:271
l3cam_ros::RgbConfiguration::client_gain_
ros::ServiceClient client_gain_
Definition: rgb_configuration.cpp:703
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros_utils.hpp
l3cam_ros::RgbConfiguration::rgb_saturation_
int rgb_saturation_
Definition: rgb_configuration.cpp:722
l3cam_ros::RgbConfiguration::callRgbAutoWhiteBalance
int callRgbAutoWhiteBalance(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:504
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::RgbConfiguration::timeout_secs_
int timeout_secs_
Definition: rgb_configuration.cpp:108
l3cam_ros::RgbConfiguration::callRgbStreamingProtocol
int callRgbStreamingProtocol(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:636
l3cam_ros::RgbConfiguration::m_shutdown_requested
bool m_shutdown_requested
Definition: rgb_configuration.cpp:734
l3cam_ros::RgbConfiguration::rgb_auto_exposure_time_
bool rgb_auto_exposure_time_
Definition: rgb_configuration.cpp:728
l3cam_ros::RgbConfiguration::srv_white_balance_
l3cam_ros::ChangeRgbCameraWhiteBalance srv_white_balance_
Definition: rgb_configuration.cpp:708
ros::ServiceClient
main
int main(int argc, char **argv)
Definition: rgb_configuration.cpp:740
l3cam_ros::RgbConfiguration::client_get_sensors_
ros::ServiceClient client_get_sensors_
Definition: rgb_configuration.cpp:105
l3cam_ros::RgbConfiguration::client_change_streaming_protocol_
ros::ServiceClient client_change_streaming_protocol_
Definition: rgb_configuration.cpp:713
l3cam_ros::RgbConfiguration::srv_gamma_
l3cam_ros::ChangeRgbCameraGamma srv_gamma_
Definition: rgb_configuration.cpp:702
l3cam_ros::RgbConfiguration::m_default_configured
bool m_default_configured
Definition: rgb_configuration.cpp:733
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
l3cam_ros::RgbConfiguration::srv_gain_
l3cam_ros::ChangeRgbCameraGain srv_gain_
Definition: rgb_configuration.cpp:704
l3cam_ros::RgbConfiguration::srv_contrast_
l3cam_ros::ChangeRgbCameraContrast srv_contrast_
Definition: rgb_configuration.cpp:696
l3cam_ros::RgbConfiguration::srv_brightness_
l3cam_ros::ChangeRgbCameraBrightness srv_brightness_
Definition: rgb_configuration.cpp:694
l3cam_ros::RgbConfiguration::client_sharpness_
ros::ServiceClient client_sharpness_
Definition: rgb_configuration.cpp:699
l3cam_ros::RgbConfiguration::client_enable_auto_exposure_time_
ros::ServiceClient client_enable_auto_exposure_time_
Definition: rgb_configuration.cpp:709
ros::NodeHandle::NodeHandle
NodeHandle(const NodeHandle &parent, const std::string &ns)
l3cam_ros::RgbConfiguration::srv_change_streaming_protocol_
l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_
Definition: rgb_configuration.cpp:714
l3cam_ros::RgbConfiguration::srv_saturation_
l3cam_ros::ChangeRgbCameraSaturation srv_saturation_
Definition: rgb_configuration.cpp:698
l3cam_ros::RgbConfiguration::client_contrast_
ros::ServiceClient client_contrast_
Definition: rgb_configuration.cpp:695
l3cam_ros::RgbConfiguration::client_get_rtsp_pipeline_
ros::ServiceClient client_get_rtsp_pipeline_
Definition: rgb_configuration.cpp:715
l3cam_ros::RgbConfiguration::rgb_gamma_
int rgb_gamma_
Definition: rgb_configuration.cpp:724
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::RgbConfiguration::srv_get_rtsp_pipeline_
l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_
Definition: rgb_configuration.cpp:716
l3cam_ros::RgbConfiguration::srv_enable_auto_white_balance_
l3cam_ros::EnableRgbCameraAutoWhiteBalance srv_enable_auto_white_balance_
Definition: rgb_configuration.cpp:706
l3cam_ros::RgbConfiguration::srv_sharpness_
l3cam_ros::ChangeRgbCameraSharpness srv_sharpness_
Definition: rgb_configuration.cpp:700
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
l3cam_ros::RgbConfiguration::client_exposure_time_
ros::ServiceClient client_exposure_time_
Definition: rgb_configuration.cpp:711
ros::Duration::sleep
bool sleep() const
l3cam_ros::RgbConfiguration::rgb_auto_white_balance_
bool rgb_auto_white_balance_
Definition: rgb_configuration.cpp:726
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
l3cam_ros::RgbConfiguration::rgb_white_balance_
int rgb_white_balance_
Definition: rgb_configuration.cpp:727
l3cam_ros::RgbConfiguration::srv_exposure_time_
l3cam_ros::ChangeRgbCameraExposureTime srv_exposure_time_
Definition: rgb_configuration.cpp:712
l3cam_ros::RgbConfiguration::callRgbRtspPipeline
int callRgbRtspPipeline(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:666
ROS_INFO
#define ROS_INFO(...)
l3cam_ros::RgbConfiguration::rgb_rtsp_pipeline_
std::string rgb_rtsp_pipeline_
Definition: rgb_configuration.cpp:731
l3cam_ros::RgbConfiguration::srv_get_sensors_
l3cam_ros::GetSensorsAvailable srv_get_sensors_
Definition: rgb_configuration.cpp:106
ros::Duration
l3cam_ros::RgbConfiguration::callRgbGain
int callRgbGain(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:475
l3cam_ros::RgbConfiguration::srv_enable_auto_exposure_time_
l3cam_ros::EnableRgbCameraAutoExposureTime srv_enable_auto_exposure_time_
Definition: rgb_configuration.cpp:710
l3cam_ros::RgbConfiguration::server_
dynamic_reconfigure::Server< l3cam_ros::RgbConfig > * server_
Definition: rgb_configuration.cpp:691
l3cam_ros::RgbConfiguration
Definition: rgb_configuration.cpp:58
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
l3cam_ros::RgbConfiguration::client_gamma_
ros::ServiceClient client_gamma_
Definition: rgb_configuration.cpp:701
ros::NodeHandle
l3cam_ros::RgbConfiguration::srv_sensor_disconnected_
ros::ServiceServer srv_sensor_disconnected_
Definition: rgb_configuration.cpp:718
l3cam_ros::RgbConfiguration::rgb_streaming_protocol_
int rgb_streaming_protocol_
Definition: rgb_configuration.cpp:730
l3cam_ros::RgbConfiguration::rgb_brightness_
int rgb_brightness_
Definition: rgb_configuration.cpp:720
l3cam_ros::RgbConfiguration::client_brightness_
ros::ServiceClient client_brightness_
Definition: rgb_configuration.cpp:693
l3cam_ros::RgbConfiguration::callRgbExposureTime
int callRgbExposureTime(l3cam_ros::RgbConfig &config)
Definition: rgb_configuration.cpp:599


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