polarimetric_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/PolarimetricConfig.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/EnablePolarimetricCameraStreamProcessedImage.h"
40 #include "l3cam_ros/ChangePolarimetricCameraProcessType.h"
41 #include "l3cam_ros/ChangePolarimetricCameraBrightness.h"
42 #include "l3cam_ros/ChangePolarimetricCameraBlackLevel.h"
43 #include "l3cam_ros/EnablePolarimetricCameraAutoGain.h"
44 #include "l3cam_ros/ChangePolarimetricCameraAutoGainRange.h"
45 #include "l3cam_ros/ChangePolarimetricCameraGain.h"
46 #include "l3cam_ros/EnablePolarimetricCameraAutoExposureTime.h"
47 #include "l3cam_ros/ChangePolarimetricCameraAutoExposureTimeRange.h"
48 #include "l3cam_ros/ChangePolarimetricCameraExposureTime.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:
62  {
63  // Create service clients
64  client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>("/L3Cam/l3cam_ros_node/get_sensors_available");
65  client_stream_processed_ = serviceClient<l3cam_ros::EnablePolarimetricCameraStreamProcessedImage>("/L3Cam/polarimetric_wide_stream/enable_polarimetric_stream_processed_image");
66  client_process_type_ = serviceClient<l3cam_ros::ChangePolarimetricCameraProcessType>("/L3Cam/polarimetric_wide_stream/change_polarimetric_process_type");
67  client_brightness_ = serviceClient<l3cam_ros::ChangePolarimetricCameraBrightness>("/L3Cam/l3cam_ros_node/change_polarimetric_brightness");
68  client_black_level_ = serviceClient<l3cam_ros::ChangePolarimetricCameraBlackLevel>("/L3Cam/l3cam_ros_node/change_polarimetric_black_level");
69  client_enable_auto_gain_ = serviceClient<l3cam_ros::EnablePolarimetricCameraAutoGain>("/L3Cam/l3cam_ros_node/enable_polarimetric_auto_gain");
70  client_auto_gain_range_ = serviceClient<l3cam_ros::ChangePolarimetricCameraAutoGainRange>("/L3Cam/l3cam_ros_node/change_polarimetric_auto_gain_range");
71  client_gain_ = serviceClient<l3cam_ros::ChangePolarimetricCameraGain>("/L3Cam/l3cam_ros_node/change_polarimetric_gain");
72  client_enable_auto_exposure_time_ = serviceClient<l3cam_ros::EnablePolarimetricCameraAutoExposureTime>("/L3Cam/l3cam_ros_node/enable_polarimetric_auto_exposure_time");
73  client_auto_exposure_time_range_ = serviceClient<l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange>("/L3Cam/l3cam_ros_node/change_polarimetric_auto_exposure_time_range");
74  client_exposure_time_ = serviceClient<l3cam_ros::ChangePolarimetricCameraExposureTime>("/L3Cam/l3cam_ros_node/change_polarimetric_exposure_time");
75  client_change_streaming_protocol_ = serviceClient<l3cam_ros::ChangeStreamingProtocol>("/L3Cam/l3cam_ros_node/change_streaming_protocol");
76  client_get_rtsp_pipeline_ = serviceClient<l3cam_ros::GetRtspPipeline>("/L3Cam/l3cam_ros_node/get_rtsp_pipeline");
77 
79 
80  // Create service server
81  srv_sensor_disconnected_ = advertiseService("polarimetric_configuration_disconnected", &PolarimetricConfiguration::sensorDisconnectedCallback, this);
82 
83  m_default_configured = false;
84  m_shutdown_requested = false;
85  }
86 
88  {
89  // Dynamic reconfigure callback
90  // server_ is a pointer so we only declare it if sensor is available and reconfigure should be available
91  server_ = new dynamic_reconfigure::Server<l3cam_ros::PolarimetricConfig>;
92  server_->setCallback(std::bind(&PolarimetricConfiguration::parametersCallback, this, std::placeholders::_1, std::placeholders::_2));
93  }
94 
95  void spin()
96  {
97  while (ros::ok() && !m_shutdown_requested)
98  {
99  ros::spinOnce();
100  ros::Duration(0.1).sleep();
101  }
102 
103  ros::shutdown();
104  }
105 
107  l3cam_ros::GetSensorsAvailable srv_get_sensors_;
108 
110 
111  private:
112  template <typename T>
113  void loadParam(const std::string &param_name, T &param_var, const T &default_val)
114  {
115  std::string full_param_name;
116 
117  if (searchParam(param_name, full_param_name))
118  {
119  if(!getParam(full_param_name, param_var))
120  {
121  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
122  }
123  }
124  else
125  {
126  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
127  param_var = default_val;
128  }
129  }
130 
132  {
133  // Get and save parameters
134  loadParam("timeout_secs", timeout_secs_, 60);
135  loadParam("polarimetric_stream_processed_image", polarimetric_stream_processed_, true);
136  loadParam("polarimetric_process_type", polarimetric_process_type_, 4);
137  loadParam("polarimetric_brightness", polarimetric_brightness_, 127);
138  loadParam("polarimetric_black_level", polarimetric_black_level_, 6.0);
139  loadParam("polarimetric_auto_gain", polarimetric_auto_gain_, true);
140  loadParam("polarimetric_auto_gain_range_minimum", polarimetric_auto_gain_range_minimum_, 0.0);
141  loadParam("polarimetric_auto_gain_range_maximum", polarimetric_auto_gain_range_maximum_, 48.0);
142  loadParam("polarimetric_gain", polarimetric_gain_, 24.0);
143  loadParam("polarimetric_auto_exposure_time", polarimetric_auto_exposure_time_, true);
144  loadParam("polarimetric_auto_exposure_time_range_minimum", polarimetric_auto_exposure_time_range_minimum_, 33.456);
145  loadParam("polarimetric_auto_exposure_time_range_maximum", polarimetric_auto_exposure_time_range_maximum_, 66470.6);
146  loadParam("polarimetric_exposure_time", polarimetric_exposure_time_, 500000.0);
147  loadParam("polarimetric_streaming_protocol", polarimetric_streaming_protocol_, 0);
148  }
149 
150  void configureDefault(l3cam_ros::PolarimetricConfig &config)
151  {
152  // Configure default params to dynamix reconfigure if inside range
153  config.polarimetric_stream_processed_image = polarimetric_stream_processed_;
154 
156  {
157  config.polarimetric_process_type = polarimetric_process_type_;
158  }
159  else
160  {
161  polarimetric_process_type_ = config.polarimetric_process_type;
162  }
163 
165  {
166  config.polarimetric_brightness = polarimetric_brightness_;
167  }
168  else
169  {
170  polarimetric_brightness_ = config.polarimetric_brightness;
171  }
172 
174  {
175  config.polarimetric_black_level = polarimetric_black_level_;
176  }
177  else
178  {
179  polarimetric_black_level_ = config.polarimetric_black_level;
180  }
181 
182  config.polarimetric_auto_gain = polarimetric_auto_gain_;
183 
185  {
186  config.polarimetric_auto_gain_range_minimum = polarimetric_auto_gain_range_minimum_;
187  }
188  else
189  {
190  polarimetric_auto_gain_range_minimum_ = config.polarimetric_auto_gain_range_minimum;
191  }
192 
194  {
195  config.polarimetric_auto_gain_range_maximum = polarimetric_auto_gain_range_maximum_;
196  }
197  else
198  {
199  polarimetric_auto_gain_range_maximum_ = config.polarimetric_auto_gain_range_maximum;
200  }
201 
202  if (polarimetric_gain_ >= 0 && polarimetric_gain_ <= 48)
203  {
204  config.polarimetric_gain = polarimetric_gain_;
205  }
206  else
207  {
208  polarimetric_gain_ = config.polarimetric_gain;
209  }
210 
211  config.polarimetric_auto_exposure_time = polarimetric_auto_exposure_time_;
212 
214  {
215  config.polarimetric_auto_exposure_time_range_minimum = polarimetric_auto_exposure_time_range_minimum_;
216  }
217  else
218  {
219  polarimetric_auto_exposure_time_range_minimum_ = config.polarimetric_auto_exposure_time_range_minimum;
220  }
221 
223  {
224  config.polarimetric_auto_exposure_time_range_maximum = polarimetric_auto_exposure_time_range_maximum_;
225  }
226  else
227  {
228  polarimetric_auto_exposure_time_range_maximum_ = config.polarimetric_auto_exposure_time_range_maximum;
229  }
230 
231  if (polarimetric_exposure_time_ >= 33.456 && polarimetric_exposure_time_ <= 66470.6)
232  {
233  config.polarimetric_exposure_time = polarimetric_exposure_time_;
234  }
235  else
236  {
237  polarimetric_exposure_time_ = config.polarimetric_exposure_time;
238  }
239 
241  {
242  config.polarimetric_streaming_protocol = polarimetric_streaming_protocol_;
243  }
244  else
245  {
246  polarimetric_streaming_protocol_ = config.polarimetric_streaming_protocol;
247  }
248 
249  // Get pipeline
250  int error = L3CAM_OK;
251  ros::Duration timeout_duration(timeout_secs_);
252  if (!client_get_rtsp_pipeline_.waitForExistence(timeout_duration))
253  {
254  ROS_ERROR_STREAM(this->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
255  }
256  else
257  {
258  srv_get_rtsp_pipeline_.request.sensor_type = (int)sensorTypes::sensor_pol;
260  {
261  error = srv_get_rtsp_pipeline_.response.error;
262  if (!error)
263  {
265  config.polarimetric_rtsp_pipeline = srv_get_rtsp_pipeline_.response.pipeline;
266  }
267  else
268  {
269  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting RTSP pipeline: " << getErrorDescription(error));
270  config.polarimetric_rtsp_pipeline = "";
272  }
273  }
274  else
275  {
276  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service get_rtsp_pipeline");
277  config.polarimetric_rtsp_pipeline = "";
279  }
280  }
281 
282  m_default_configured = true;
283  }
284 
285  void parametersCallback(l3cam_ros::PolarimetricConfig &config, uint32_t level)
286  {
287  int error = L3CAM_OK;
288 
290  {
291  configureDefault(config);
292  }
293  else
294  {
295  // Filter by parameter and call service
296  switch (level)
297  {
298  case 0: // polarimetric_stream_processed_image
299  error = callPolarimetricStreamProcessedImage(config);
300  break;
301  case 1: // polarimetric_process_type
302  error = callPolarimetricProcessType(config);
303  break;
304  case 2: // polarimetric_brightness
305  error = callPolarimetricBrightness(config);
306  break;
307  case 3: // polarimetric_black_level
308  error = callPolarimetricBlackLevel(config);
309  break;
310  case 4: // polarimetric_auto_gain
311  error = callPolarimetricAutoGain(config);
312  break;
313  case 5: // polarimetric_auto_gain_range_minimum
314  error = callPolarimetricAutoGainRange(config);
315  break;
316  case 6: // polarimetric_auto_gain_range_maximum
317  error = callPolarimetricAutoGainRange(config);
318  break;
319  case 7: // polarimetric_gain
320  error = callPolarimetricGain(config);
321  break;
322  case 8: // polarimetric_auto_exposure_time
323  error = callPolarimetricAutoExposureTime(config);
324  break;
325  case 9: // polarimetric_auto_exposure_time_range_minimum
327  break;
328  case 10: // polarimetric_auto_exposure_time_range_maximum
330  break;
331  case 11: // polarimetric_exposure_time
332  error = callPolarimetricExposureTime(config);
333  break;
334  case 12: // polarimetric_streaming_protocol
335  error = callPolarimetricStreamingProtocol(config);
336  break;
337  case 13: // polarimetric_rtsp_pipeline
338  error = callPolarimetricRtspPipeline(config);
339  break;
340  }
341  }
342 
343  if (error)
344  {
345  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while changing parameter: " << getErrorDescription(error));
346  }
347  }
348 
349  // Service calls
350  int callPolarimetricStreamProcessedImage(l3cam_ros::PolarimetricConfig &config)
351  {
352  int error = L3CAM_OK;
353 
354  srv_stream_processed_.request.enabled = config.polarimetric_stream_processed_image;
356  {
357  error = srv_stream_processed_.response.error;
358  if (!error)
359  {
360  // Parameter changed successfully, save value
361  polarimetric_stream_processed_ = config.polarimetric_stream_processed_image;
362  }
363  else
364  {
365  // Parameter could not be changed, reset parameter to value before change
366  config.polarimetric_stream_processed_image = polarimetric_stream_processed_;
367  }
368  }
369  else
370  {
371  // Service could not be called, reset parameter to value before change
372  config.polarimetric_stream_processed_image = polarimetric_stream_processed_;
374  }
375 
376  return error;
377  }
378 
379  int callPolarimetricProcessType(l3cam_ros::PolarimetricConfig &config)
380  {
381  int error = L3CAM_OK;
382 
383  srv_process_type_.request.type = config.polarimetric_process_type;
385  {
386  error = srv_process_type_.response.error;
387  if (!error)
388  {
389  // Parameter changed successfully, save value
390  polarimetric_process_type_ = config.polarimetric_process_type;
391  }
392  else
393  {
394  // Parameter could not be changed, reset parameter to value before change
395  config.polarimetric_process_type = polarimetric_process_type_;
396  }
397  }
398  else
399  {
400  // Service could not be called, reset parameter to value before change
401  config.polarimetric_process_type = polarimetric_process_type_;
403  }
404 
405  return error;
406  }
407 
408  int callPolarimetricBrightness(l3cam_ros::PolarimetricConfig &config)
409  {
410  int error = L3CAM_OK;
411 
412  srv_brightness_.request.brightness = config.polarimetric_brightness;
414  {
415  error = srv_brightness_.response.error;
416  if (!error)
417  {
418  // Parameter changed successfully, save value
419  polarimetric_brightness_ = config.polarimetric_brightness;
420  }
421  else
422  {
423  // Parameter could not be changed, reset parameter to value before change
424  config.polarimetric_brightness = polarimetric_brightness_;
425  }
426  }
427  else
428  {
429  // Service could not be called, reset parameter to value before change
430  config.polarimetric_brightness = polarimetric_brightness_;
432  }
433 
434  return error;
435  }
436 
437  int callPolarimetricBlackLevel(l3cam_ros::PolarimetricConfig &config)
438  {
439  int error = L3CAM_OK;
440 
441  srv_black_level_.request.black_level = config.polarimetric_black_level;
443  {
444  error = srv_black_level_.response.error;
445  if (!error)
446  {
447  // Parameter changed successfully, save value
448  polarimetric_black_level_ = config.polarimetric_black_level;
449  }
450  else
451  {
452  // Parameter could not be changed, reset parameter to value before change
453  config.polarimetric_black_level = polarimetric_black_level_;
454  }
455  }
456  else
457  {
458  // Service could not be called, reset parameter to value before change
459  config.polarimetric_black_level = polarimetric_black_level_;
461  }
462 
463  return error;
464  }
465 
466  int callPolarimetricAutoGain(l3cam_ros::PolarimetricConfig &config)
467  {
468  int error = L3CAM_OK;
469 
470  srv_enable_auto_gain_.request.enabled = config.polarimetric_auto_gain;
472  {
473  error = srv_enable_auto_gain_.response.error;
474  if (!error)
475  {
476  // Parameter changed successfully, save value
477  polarimetric_auto_gain_ = config.polarimetric_auto_gain;
478  }
479  else
480  {
481  // Parameter could not be changed, reset parameter to value before change
482  config.polarimetric_auto_gain = polarimetric_auto_gain_;
483  }
484  }
485  else
486  {
487  // Service could not be called, reset parameter to value before change
488  config.polarimetric_auto_gain = polarimetric_auto_gain_;
490  }
491 
492  return error;
493  }
494 
495  int callPolarimetricAutoGainRange(l3cam_ros::PolarimetricConfig &config)
496  {
497  int error = L3CAM_OK;
498 
500  {
501  srv_auto_gain_range_.request.min_gain = config.polarimetric_auto_gain_range_minimum;
502  srv_auto_gain_range_.request.max_gain = config.polarimetric_auto_gain_range_maximum;
504  {
505  error = srv_auto_gain_range_.response.error;
506  if (!error)
507  {
508  // Parameter changed successfully, save value
509  polarimetric_auto_gain_range_minimum_ = config.polarimetric_auto_gain_range_minimum;
510  polarimetric_auto_gain_range_maximum_ = config.polarimetric_auto_gain_range_maximum;
511  }
512  else
513  {
514  // Parameter could not be changed, reset parameter to value before change
515  config.polarimetric_auto_gain_range_minimum = polarimetric_auto_gain_range_minimum_;
516  config.polarimetric_auto_gain_range_maximum = polarimetric_auto_gain_range_maximum_;
517  }
518  }
519  else
520  {
521  // Service could not be called, reset parameter to value before change
522  config.polarimetric_auto_gain_range_minimum = polarimetric_auto_gain_range_minimum_;
523  config.polarimetric_auto_gain_range_maximum = polarimetric_auto_gain_range_maximum_;
525  }
526  }
527  else
528  {
529  ROS_WARN_STREAM(this->getNamespace() << " Polarimetric camera auto gain must be enabled to change auto gain range");
530  config.polarimetric_auto_gain_range_minimum = polarimetric_auto_gain_range_minimum_;
531  config.polarimetric_auto_gain_range_maximum = polarimetric_auto_gain_range_maximum_;
532  }
533 
534  return error;
535  }
536 
537  int callPolarimetricGain(l3cam_ros::PolarimetricConfig &config)
538  {
539  int error = L3CAM_OK;
540 
542  {
543  srv_gain_.request.gain = config.polarimetric_gain;
545  {
546  error = srv_gain_.response.error;
547  if (!error)
548  {
549  // Parameter changed successfully, save value
550  polarimetric_gain_ = config.polarimetric_gain;
551  }
552  else
553  {
554  // Parameter could not be changed, reset parameter to value before change
555  config.polarimetric_gain = polarimetric_gain_;
556  }
557  }
558  else
559  {
560  // Service could not be called, reset parameter to value before change
561  config.polarimetric_gain = polarimetric_gain_;
563  }
564  }
565  else
566  {
567  ROS_WARN_STREAM(this->getNamespace() << " Polarimetric camera auto gain must be disabled to change gain");
568  config.polarimetric_gain = polarimetric_gain_;
569  }
570 
571  return error;
572  }
573 
574  int callPolarimetricAutoExposureTime(l3cam_ros::PolarimetricConfig &config)
575  {
576  int error = L3CAM_OK;
577 
578  srv_enable_auto_exposure_time_.request.enabled = config.polarimetric_auto_exposure_time;
580  {
581  error = srv_enable_auto_exposure_time_.response.error;
582  if (!error)
583  {
584  // Parameter changed successfully, save value
585  polarimetric_auto_exposure_time_ = config.polarimetric_auto_exposure_time;
586  }
587  else
588  {
589  // Parameter could not be changed, reset parameter to value before change
590  config.polarimetric_auto_exposure_time = polarimetric_auto_exposure_time_;
591  }
592  }
593  else
594  {
595  // Service could not be called, reset parameter to value before change
596  config.polarimetric_auto_exposure_time = polarimetric_auto_exposure_time_;
598  }
599 
600  return error;
601  }
602 
603  int callPolarimetricAutoExposureTimeRange(l3cam_ros::PolarimetricConfig &config)
604  {
605  int error = L3CAM_OK;
606 
608  {
609  srv_auto_exposure_time_range_.request.min_exposure = config.polarimetric_auto_exposure_time_range_minimum;
610  srv_auto_exposure_time_range_.request.max_exposure = config.polarimetric_auto_exposure_time_range_maximum;
612  {
613  error = srv_auto_exposure_time_range_.response.error;
614  if (!error)
615  {
616  // Parameter changed successfully, save value
617  polarimetric_auto_exposure_time_range_minimum_ = config.polarimetric_auto_exposure_time_range_minimum;
618  polarimetric_auto_exposure_time_range_maximum_ = config.polarimetric_auto_exposure_time_range_maximum;
619  }
620  else
621  {
622  // Parameter could not be changed, reset parameter to value before change
623  config.polarimetric_auto_exposure_time_range_minimum = polarimetric_auto_exposure_time_range_minimum_;
624  config.polarimetric_auto_exposure_time_range_maximum = polarimetric_auto_exposure_time_range_maximum_;
625  }
626  }
627  else
628  {
629  // Service could not be called, reset parameter to value before change
630  config.polarimetric_auto_exposure_time_range_minimum = polarimetric_auto_exposure_time_range_minimum_;
631  config.polarimetric_auto_exposure_time_range_maximum = polarimetric_auto_exposure_time_range_maximum_;
633  }
634  }
635  else
636  {
637  ROS_WARN_STREAM(this->getNamespace() << " Polarimetric camera auto exposure time must be enabled to change auto exposure time range");
638  config.polarimetric_auto_exposure_time_range_minimum = polarimetric_auto_exposure_time_range_minimum_;
639  config.polarimetric_auto_exposure_time_range_maximum = polarimetric_auto_exposure_time_range_maximum_;
640  }
641 
642  return error;
643  }
644 
645  int callPolarimetricExposureTime(l3cam_ros::PolarimetricConfig &config)
646  {
647  int error = L3CAM_OK;
648 
650  {
651  srv_exposure_time_.request.exposure_time = config.polarimetric_exposure_time;
653  {
654  error = srv_exposure_time_.response.error;
655  if (!error)
656  {
657  // Parameter changed successfully, save value
658  polarimetric_exposure_time_ = config.polarimetric_exposure_time;
659  }
660  else
661  {
662  // Parameter could not be changed, reset parameter to value before change
663  config.polarimetric_exposure_time = polarimetric_exposure_time_;
664  }
665  }
666  else
667  {
668  // Service could not be called, reset parameter to value before change
669  config.polarimetric_exposure_time = polarimetric_exposure_time_;
671  }
672  }
673  else
674  {
675  ROS_WARN_STREAM(this->getNamespace() << " Polarimetric camera auto exposure time must be disabled to change exposure time");
676  config.polarimetric_exposure_time = polarimetric_exposure_time_;
677  }
678 
679  return error;
680  }
681 
682  int callPolarimetricStreamingProtocol(l3cam_ros::PolarimetricConfig &config)
683  {
684  int error = L3CAM_OK;
685 
686  srv_change_streaming_protocol_.request.protocol = config.polarimetric_streaming_protocol;
687  srv_change_streaming_protocol_.request.sensor_type = (int)sensorTypes::sensor_pol;
689  {
690  error = srv_change_streaming_protocol_.response.error;
691  if (!error)
692  {
693  // Parameter changed successfully, save value
694  polarimetric_streaming_protocol_ = config.polarimetric_streaming_protocol;
695  }
696  else
697  {
698  // Parameter could not be changed, reset parameter to value before change
699  config.polarimetric_streaming_protocol = polarimetric_streaming_protocol_;
700  }
701  }
702  else
703  {
704  // Service could not be called, reset parameter to value before change
705  config.polarimetric_streaming_protocol = polarimetric_streaming_protocol_;
707  }
708 
709  return error;
710  }
711 
712  int callPolarimetricRtspPipeline(l3cam_ros::PolarimetricConfig &config)
713  {
714  // Read-only
715  ROS_WARN_STREAM(this->getNamespace() << " The RTSP Pipeline parameter is read-only, only changeable at launch");
716  config.polarimetric_rtsp_pipeline = polarimetric_rtsp_pipeline_;
717 
718  return L3CAM_OK;
719  }
720 
721  bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
722  {
723  ROS_BMG_UNUSED(res);
724  if (req.code == 0)
725  {
726  ROS_INFO_STREAM("Exiting " << this->getNamespace() << " cleanly.");
727  }
728  else
729  {
730  ROS_WARN_STREAM("Exiting " << this->getNamespace() << ". Sensor got disconnected with error " << req.code << ": " << getErrorDescription(req.code));
731  }
732 
733  m_shutdown_requested = true;
734  ros::shutdown();
735  return true;
736  }
737 
738  dynamic_reconfigure::Server<l3cam_ros::PolarimetricConfig> *server_;
739 
741  l3cam_ros::EnablePolarimetricCameraStreamProcessedImage srv_stream_processed_;
743  l3cam_ros::ChangePolarimetricCameraProcessType srv_process_type_;
745  l3cam_ros::ChangePolarimetricCameraBrightness srv_brightness_;
747  l3cam_ros::ChangePolarimetricCameraBlackLevel srv_black_level_;
749  l3cam_ros::EnablePolarimetricCameraAutoGain srv_enable_auto_gain_;
751  l3cam_ros::ChangePolarimetricCameraAutoGainRange srv_auto_gain_range_;
753  l3cam_ros::ChangePolarimetricCameraGain srv_gain_;
755  l3cam_ros::EnablePolarimetricCameraAutoExposureTime srv_enable_auto_exposure_time_;
757  l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange srv_auto_exposure_time_range_;
759  l3cam_ros::ChangePolarimetricCameraExposureTime srv_exposure_time_;
761  l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_;
763  l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_;
764 
766 
781 
784 
785  }; // class PolarimetricConfiguration
786 
787 } // namespace l3cam_ros
788 
789 int main(int argc, char **argv)
790 {
791  ros::init(argc, argv, "polarimetric_configuration");
792 
794 
795  // Check if service is available
796  ros::Duration timeout_duration(node->timeout_secs_);
797  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
798  {
799  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
801  }
802 
803  int error = L3CAM_OK;
804  bool sensor_is_available = false;
805  // Shutdown if sensor is not available or if error returned
806  if (node->client_get_sensors_.call(node->srv_get_sensors_))
807  {
808  error = node->srv_get_sensors_.response.error;
809 
810  if (!error)
811  {
812  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
813  {
814  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_pol && node->srv_get_sensors_.response.sensors[i].sensor_available)
815  {
816  sensor_is_available = true;
817  }
818  }
819  }
820  else
821  {
822  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability: " << getErrorDescription(error));
823  return error;
824  }
825  }
826  else
827  {
828  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
830  }
831 
832  if (sensor_is_available)
833  {
834  ROS_INFO("Polarimetric configuration is available");
835  }
836  else
837  {
838  return 0;
839  }
840 
841  node->setDynamicReconfigure();
842 
843  node->spin();
844 
845  ros::shutdown();
846  return 0;
847 }
l3cam_ros::PolarimetricConfiguration::callPolarimetricAutoGainRange
int callPolarimetricAutoGainRange(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:495
l3cam_ros::PolarimetricConfiguration::polarimetric_brightness_
int polarimetric_brightness_
Definition: polarimetric_configuration.cpp:769
l3cam_ros::PolarimetricConfiguration::callPolarimetricGain
int callPolarimetricGain(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:537
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
l3cam_ros::PolarimetricConfiguration::configureDefault
void configureDefault(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:150
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
l3cam_ros::PolarimetricConfiguration::srv_sensor_disconnected_
ros::ServiceServer srv_sensor_disconnected_
Definition: polarimetric_configuration.cpp:765
l3cam_ros::PolarimetricConfiguration::polarimetric_gain_
double polarimetric_gain_
Definition: polarimetric_configuration.cpp:774
l3cam_ros::PolarimetricConfiguration::callPolarimetricExposureTime
int callPolarimetricExposureTime(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:645
l3cam_ros::PolarimetricConfiguration::callPolarimetricProcessType
int callPolarimetricProcessType(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:379
l3cam_ros::PolarimetricConfiguration::srv_process_type_
l3cam_ros::ChangePolarimetricCameraProcessType srv_process_type_
Definition: polarimetric_configuration.cpp:743
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::PolarimetricConfiguration::callPolarimetricBlackLevel
int callPolarimetricBlackLevel(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:437
l3cam_ros::PolarimetricConfiguration::srv_auto_exposure_time_range_
l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange srv_auto_exposure_time_range_
Definition: polarimetric_configuration.cpp:757
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
l3cam_ros::PolarimetricConfiguration::client_stream_processed_
ros::ServiceClient client_stream_processed_
Definition: polarimetric_configuration.cpp:740
l3cam_ros::PolarimetricConfiguration::loadDefaultParams
void loadDefaultParams()
Definition: polarimetric_configuration.cpp:131
l3cam_ros::PolarimetricConfiguration::client_enable_auto_exposure_time_
ros::ServiceClient client_enable_auto_exposure_time_
Definition: polarimetric_configuration.cpp:754
l3cam_ros::PolarimetricConfiguration::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: polarimetric_configuration.cpp:113
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
l3cam_ros::PolarimetricConfiguration::client_auto_exposure_time_range_
ros::ServiceClient client_auto_exposure_time_range_
Definition: polarimetric_configuration.cpp:756
l3cam_ros::PolarimetricConfiguration::srv_exposure_time_
l3cam_ros::ChangePolarimetricCameraExposureTime srv_exposure_time_
Definition: polarimetric_configuration.cpp:759
l3cam_ros::PolarimetricConfiguration::srv_change_streaming_protocol_
l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_
Definition: polarimetric_configuration.cpp:761
ros::spinOnce
ROSCPP_DECL void spinOnce()
l3cam_ros::PolarimetricConfiguration::polarimetric_auto_exposure_time_
bool polarimetric_auto_exposure_time_
Definition: polarimetric_configuration.cpp:775
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
l3cam_ros::PolarimetricConfiguration::srv_brightness_
l3cam_ros::ChangePolarimetricCameraBrightness srv_brightness_
Definition: polarimetric_configuration.cpp:745
l3cam_ros::PolarimetricConfiguration::polarimetric_auto_gain_range_minimum_
double polarimetric_auto_gain_range_minimum_
Definition: polarimetric_configuration.cpp:772
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros::PolarimetricConfiguration::client_auto_gain_range_
ros::ServiceClient client_auto_gain_range_
Definition: polarimetric_configuration.cpp:750
l3cam_ros::PolarimetricConfiguration::polarimetric_exposure_time_
double polarimetric_exposure_time_
Definition: polarimetric_configuration.cpp:778
l3cam_ros
Definition: l3cam_ros_node.hpp:133
l3cam_ros::PolarimetricConfiguration::srv_auto_gain_range_
l3cam_ros::ChangePolarimetricCameraAutoGainRange srv_auto_gain_range_
Definition: polarimetric_configuration.cpp:751
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
l3cam_ros::PolarimetricConfiguration
Definition: polarimetric_configuration.cpp:58
ros::ok
ROSCPP_DECL bool ok()
main
int main(int argc, char **argv)
Definition: polarimetric_configuration.cpp:789
l3cam_ros::PolarimetricConfiguration::callPolarimetricStreamingProtocol
int callPolarimetricStreamingProtocol(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:682
l3cam_ros::PolarimetricConfiguration::polarimetric_auto_exposure_time_range_minimum_
double polarimetric_auto_exposure_time_range_minimum_
Definition: polarimetric_configuration.cpp:776
l3cam_ros::L3Cam::timeout_secs_
int timeout_secs_
Definition: l3cam_ros_node.hpp:404
ros::ServiceServer
l3cam_ros::PolarimetricConfiguration::polarimetric_auto_gain_
bool polarimetric_auto_gain_
Definition: polarimetric_configuration.cpp:771
l3cam_ros::PolarimetricConfiguration::client_enable_auto_gain_
ros::ServiceClient client_enable_auto_gain_
Definition: polarimetric_configuration.cpp:748
l3cam_ros::PolarimetricConfiguration::polarimetric_black_level_
double polarimetric_black_level_
Definition: polarimetric_configuration.cpp:770
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros::PolarimetricConfiguration::srv_get_rtsp_pipeline_
l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_
Definition: polarimetric_configuration.cpp:763
l3cam_ros::PolarimetricConfiguration::callPolarimetricAutoExposureTimeRange
int callPolarimetricAutoExposureTimeRange(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:603
l3cam_ros_utils.hpp
l3cam_ros::PolarimetricConfiguration::m_default_configured
bool m_default_configured
Definition: polarimetric_configuration.cpp:782
l3cam_ros::PolarimetricConfiguration::callPolarimetricAutoExposureTime
int callPolarimetricAutoExposureTime(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:574
l3cam_ros::PolarimetricConfiguration::client_get_sensors_
ros::ServiceClient client_get_sensors_
Definition: polarimetric_configuration.cpp:106
l3cam_ros::PolarimetricConfiguration::callPolarimetricAutoGain
int callPolarimetricAutoGain(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:466
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::PolarimetricConfiguration::client_change_streaming_protocol_
ros::ServiceClient client_change_streaming_protocol_
Definition: polarimetric_configuration.cpp:760
l3cam_ros::PolarimetricConfiguration::timeout_secs_
int timeout_secs_
Definition: polarimetric_configuration.cpp:109
ros::ServiceClient
l3cam_ros::PolarimetricConfiguration::parametersCallback
void parametersCallback(l3cam_ros::PolarimetricConfig &config, uint32_t level)
Definition: polarimetric_configuration.cpp:285
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
l3cam_ros::PolarimetricConfiguration::polarimetric_auto_gain_range_maximum_
double polarimetric_auto_gain_range_maximum_
Definition: polarimetric_configuration.cpp:773
l3cam_ros::PolarimetricConfiguration::polarimetric_rtsp_pipeline_
std::string polarimetric_rtsp_pipeline_
Definition: polarimetric_configuration.cpp:780
ros::NodeHandle::NodeHandle
NodeHandle(const NodeHandle &parent, const std::string &ns)
l3cam_ros::PolarimetricConfiguration::polarimetric_streaming_protocol_
int polarimetric_streaming_protocol_
Definition: polarimetric_configuration.cpp:779
l3cam_ros::PolarimetricConfiguration::server_
dynamic_reconfigure::Server< l3cam_ros::PolarimetricConfig > * server_
Definition: polarimetric_configuration.cpp:738
l3cam_ros::PolarimetricConfiguration::client_process_type_
ros::ServiceClient client_process_type_
Definition: polarimetric_configuration.cpp:742
l3cam_ros::PolarimetricConfiguration::client_black_level_
ros::ServiceClient client_black_level_
Definition: polarimetric_configuration.cpp:746
l3cam_ros::PolarimetricConfiguration::callPolarimetricBrightness
int callPolarimetricBrightness(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:408
l3cam_ros::PolarimetricConfiguration::client_brightness_
ros::ServiceClient client_brightness_
Definition: polarimetric_configuration.cpp:744
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::PolarimetricConfiguration::setDynamicReconfigure
void setDynamicReconfigure()
Definition: polarimetric_configuration.cpp:87
l3cam_ros::PolarimetricConfiguration::spin
void spin()
Definition: polarimetric_configuration.cpp:95
l3cam_ros::PolarimetricConfiguration::callPolarimetricRtspPipeline
int callPolarimetricRtspPipeline(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:712
l3cam_ros::PolarimetricConfiguration::srv_black_level_
l3cam_ros::ChangePolarimetricCameraBlackLevel srv_black_level_
Definition: polarimetric_configuration.cpp:747
l3cam_ros::PolarimetricConfiguration::polarimetric_auto_exposure_time_range_maximum_
double polarimetric_auto_exposure_time_range_maximum_
Definition: polarimetric_configuration.cpp:777
l3cam_ros::PolarimetricConfiguration::srv_stream_processed_
l3cam_ros::EnablePolarimetricCameraStreamProcessedImage srv_stream_processed_
Definition: polarimetric_configuration.cpp:741
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
l3cam_ros::PolarimetricConfiguration::polarimetric_stream_processed_
bool polarimetric_stream_processed_
Definition: polarimetric_configuration.cpp:767
l3cam_ros::PolarimetricConfiguration::srv_get_sensors_
l3cam_ros::GetSensorsAvailable srv_get_sensors_
Definition: polarimetric_configuration.cpp:107
l3cam_ros::PolarimetricConfiguration::srv_enable_auto_gain_
l3cam_ros::EnablePolarimetricCameraAutoGain srv_enable_auto_gain_
Definition: polarimetric_configuration.cpp:749
l3cam_ros::PolarimetricConfiguration::srv_enable_auto_exposure_time_
l3cam_ros::EnablePolarimetricCameraAutoExposureTime srv_enable_auto_exposure_time_
Definition: polarimetric_configuration.cpp:755
l3cam_ros::PolarimetricConfiguration::PolarimetricConfiguration
PolarimetricConfiguration()
Definition: polarimetric_configuration.cpp:61
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
l3cam_ros::PolarimetricConfiguration::callPolarimetricStreamProcessedImage
int callPolarimetricStreamProcessedImage(l3cam_ros::PolarimetricConfig &config)
Definition: polarimetric_configuration.cpp:350
l3cam_ros::PolarimetricConfiguration::polarimetric_process_type_
int polarimetric_process_type_
Definition: polarimetric_configuration.cpp:768
ros::Duration::sleep
bool sleep() const
l3cam_ros::PolarimetricConfiguration::client_gain_
ros::ServiceClient client_gain_
Definition: polarimetric_configuration.cpp:752
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
l3cam_ros::PolarimetricConfiguration::m_shutdown_requested
bool m_shutdown_requested
Definition: polarimetric_configuration.cpp:783
ROS_INFO
#define ROS_INFO(...)
l3cam_ros::PolarimetricConfiguration::srv_gain_
l3cam_ros::ChangePolarimetricCameraGain srv_gain_
Definition: polarimetric_configuration.cpp:753
ros::Duration
l3cam_ros::PolarimetricConfiguration::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: polarimetric_configuration.cpp:721
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
l3cam_ros::PolarimetricConfiguration::client_get_rtsp_pipeline_
ros::ServiceClient client_get_rtsp_pipeline_
Definition: polarimetric_configuration.cpp:762
ros::NodeHandle
l3cam_ros::PolarimetricConfiguration::client_exposure_time_
ros::ServiceClient client_exposure_time_
Definition: polarimetric_configuration.cpp:758


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