lidar_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/LidarConfig.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/ChangePointcloudColor.h"
40 #include "l3cam_ros/ChangePointcloudColorRange.h"
41 #include "l3cam_ros/ChangeDistanceRange.h"
42 #include "l3cam_ros/SetBiasShortRange.h"
43 #include "l3cam_ros/EnableAutoBias.h"
44 #include "l3cam_ros/ChangeBiasValue.h"
45 #include "l3cam_ros/ChangeAutobiasValue.h"
46 #include "l3cam_ros/ChangeStreamingProtocol.h"
47 #include "l3cam_ros/GetRtspPipeline.h"
48 
49 #include "l3cam_ros/SensorDisconnected.h"
50 
51 #include "l3cam_ros_utils.hpp"
52 
53 namespace l3cam_ros
54 {
56  {
57  public:
58  explicit LidarConfiguration() : ros::NodeHandle("~")
59  {
60  // Create service clients
61  client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>("/L3Cam/l3cam_ros_node/get_sensors_available");
62  client_color_ = serviceClient<l3cam_ros::ChangePointcloudColor>("/L3Cam/l3cam_ros_node/change_pointcloud_color");
63  client_color_range_ = serviceClient<l3cam_ros::ChangePointcloudColorRange>("/L3Cam/l3cam_ros_node/change_pointcloud_color_range");
64  client_distance_range_ = serviceClient<l3cam_ros::ChangeDistanceRange>("/L3Cam/l3cam_ros_node/change_distance_range");
65  client_bias_short_range_ = serviceClient<l3cam_ros::SetBiasShortRange>("/L3Cam/l3cam_ros_node/set_bias_short_range");
66  client_auto_bias_ = serviceClient<l3cam_ros::EnableAutoBias>("/L3Cam/l3cam_ros_node/enable_auto_bias");
67  client_bias_value_ = serviceClient<l3cam_ros::ChangeBiasValue>("/L3Cam/l3cam_ros_node/change_bias_value");
68  client_autobias_value_ = serviceClient<l3cam_ros::ChangeAutobiasValue>("/L3Cam/l3cam_ros_node/change_autobias_value");
69  client_change_streaming_protocol_ = serviceClient<l3cam_ros::ChangeStreamingProtocol>("/L3Cam/l3cam_ros_node/change_streaming_protocol");
70  client_get_rtsp_pipeline_ = serviceClient<l3cam_ros::GetRtspPipeline>("/L3Cam/l3cam_ros_node/get_rtsp_pipeline");
71 
73 
74  // Create service server
76 
77  m_default_configured = false;
78  m_shutdown_requested = false;
79  }
80 
82  {
83  // Dynamic reconfigure callback
84  // server_ is a pointer so we only declare it if sensor is available and reconfigure should be available
85  server_ = new dynamic_reconfigure::Server<l3cam_ros::LidarConfig>;
86  server_->setCallback(std::bind(&LidarConfiguration::parametersCallback, this, std::placeholders::_1, std::placeholders::_2));
87  }
88 
89  void spin()
90  {
91  while (ros::ok() && !m_shutdown_requested)
92  {
93  ros::spinOnce();
94  ros::Duration(0.1).sleep();
95  }
96 
97  ros::shutdown();
98  }
99 
101  l3cam_ros::GetSensorsAvailable srv_get_sensors_;
102 
104 
105  private:
106  template <typename T>
107  void loadParam(const std::string &param_name, T &param_var, const T &default_val)
108  {
109  std::string full_param_name;
110 
111  if (searchParam(param_name, full_param_name))
112  {
113  if (!getParam(full_param_name, param_var))
114  {
115  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
116  }
117  }
118  else
119  {
120  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
121  param_var = default_val;
122  }
123  }
124 
126  {
127  // Get and save parameters
128  loadParam("timeout_secs", timeout_secs_, 60);
129  loadParam("pointcloud_color", pointcloud_color_, 0);
130  loadParam("pointcloud_color_range_minimum", pointcloud_color_range_minimum_, 0);
131  loadParam("pointcloud_color_range_maximum", pointcloud_color_range_maximum_, 300000);
132  loadParam("distance_range_minimum", distance_range_minimum_, 0);
133  loadParam("distance_range_maximum", distance_range_maximum_, 300000);
134  loadParam("bias_short_range", bias_short_range_, false);
135  loadParam("auto_bias", auto_bias_, true);
136  loadParam("bias_value_right", bias_value_right_, 1580);
137  loadParam("bias_value_left", bias_value_left_, 1380);
138  loadParam("autobias_value_right", autobias_value_right_, 50);
139  loadParam("autobias_value_left", autobias_value_left_, 50);
140  loadParam("lidar_streaming_protocol", lidar_streaming_protocol_, 0);
141  }
142 
143  void configureDefault(l3cam_ros::LidarConfig &config)
144  {
145  // Configure default params to dynamix reconfigure if inside range
146  if (pointcloud_color_ >= 0 && pointcloud_color_ <= 7 || pointcloud_color_ >= 12 && pointcloud_color_ <= 15)
147  {
148  config.pointcloud_color = pointcloud_color_;
149  }
150  else
151  {
152  pointcloud_color_ = config.pointcloud_color;
153  }
154 
156  {
157  config.pointcloud_color_range_minimum = pointcloud_color_range_minimum_;
158  }
159  else
160  {
161  pointcloud_color_range_minimum_ = config.pointcloud_color_range_minimum;
162  }
163 
165  {
166  config.pointcloud_color_range_maximum = pointcloud_color_range_maximum_;
167  }
168  else
169  {
170  pointcloud_color_range_maximum_ = config.pointcloud_color_range_maximum;
171  }
172 
173  if (distance_range_minimum_ >= 0 && distance_range_minimum_ <= 300000)
174  {
175  config.distance_range_minimum = distance_range_minimum_;
176  }
177  else
178  {
179  distance_range_minimum_ = config.distance_range_minimum;
180  }
181 
182  if (distance_range_maximum_ >= 0 && distance_range_maximum_ <= 300000)
183  {
184  config.distance_range_maximum = distance_range_maximum_;
185  }
186  else
187  {
188  distance_range_maximum_ = config.distance_range_maximum;
189  }
190 
191  config.bias_short_range = bias_short_range_;
192 
193  config.auto_bias = auto_bias_;
194  if (bias_value_right_ >= 700 && bias_value_right_ <= 3500)
195  {
196  config.bias_value_right = bias_value_right_;
197  }
198  else
199  {
200  bias_value_right_ = config.bias_value_right;
201  }
202 
203  if (bias_value_left_ >= 700 && bias_value_left_ <= 3500)
204  {
205  config.bias_value_left = bias_value_left_;
206  }
207  else
208  {
209  bias_value_left_ = config.bias_value_left;
210  }
211 
212  if (autobias_value_right_ >= 0 && autobias_value_right_ <= 100)
213  {
214  config.autobias_value_right = autobias_value_right_;
215  }
216  else
217  {
218  autobias_value_right_ = config.autobias_value_right;
219  }
220 
221  if (autobias_value_left_ >= 0 && autobias_value_left_ <= 100)
222  {
223  config.autobias_value_left = autobias_value_left_;
224  }
225  else
226  {
227  autobias_value_left_ = config.autobias_value_left;
228  }
229 
231  {
232  config.lidar_streaming_protocol = lidar_streaming_protocol_;
233  }
234  else
235  {
236  lidar_streaming_protocol_ = config.lidar_streaming_protocol;
237  }
238 
239  // Get pipeline
240  int error = L3CAM_OK;
241  ros::Duration timeout_duration(timeout_secs_);
242  if (!client_get_rtsp_pipeline_.waitForExistence(timeout_duration))
243  {
244  ROS_ERROR_STREAM(this->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
245  }
246  else
247  {
248  srv_get_rtsp_pipeline_.request.sensor_type = (int)sensorTypes::sensor_lidar;
250  {
251  error = srv_get_rtsp_pipeline_.response.error;
252  if (!error)
253  {
254  lidar_rtsp_pipeline_ = srv_get_rtsp_pipeline_.response.pipeline;
255  config.lidar_rtsp_pipeline = srv_get_rtsp_pipeline_.response.pipeline;
256  }
257  else
258  {
259  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting RTSP pipeline: " << getErrorDescription(error));
260  config.lidar_rtsp_pipeline = "";
262  }
263  }
264  else
265  {
266  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service get_rtsp_pipeline");
267  config.lidar_rtsp_pipeline = "";
269  }
270  }
271 
272  m_default_configured = true;
273  }
274 
275  void parametersCallback(l3cam_ros::LidarConfig &config, uint32_t level)
276  {
277  int error = L3CAM_OK;
278 
280  {
281  configureDefault(config);
282  }
283  else
284  {
285  // Filter by parameter and call service
286  switch (level)
287  {
288  case 0: // pointcloud_color
289  error = callColor(config);
290  break;
291  case 1: // pointcloud_color_range_minimum
292  error = callColorRange(config);
293  break;
294  case 2: // pointcloud_color_range_maximum
295  error = callColorRange(config);
296  break;
297  case 3: // distance_range_minimum
298  error = callDistanceRange(config);
299  break;
300  case 4: // distance_range_maximum
301  error = callDistanceRange(config);
302  break;
303  case 5: // bias_short_range
304  error = callBiasShortRange(config);
305  break;
306  case 6: // auto_bias
307  error = callAutoBias(config);
308  break;
309  case 7: // bias_value_right
310  error = callBiasValueRight(config);
311  break;
312  case 8: // bias_value_left
313  error = callBiasValueLeft(config);
314  break;
315  case 9: // autobias_value_right
316  error = callAutobiasValueRight(config);
317  break;
318  case 10: // autobias_value_left
319  error = callAutobiasValueLeft(config);
320  break;
321  case 11: // lidar_streaming_protocol
322  error = callStreamingProtocol(config);
323  break;
324  case 12: // lidar_rtsp_pipeline
325  error = callRtspPipeline(config);
326  break;
327  }
328  }
329 
330  if (error)
331  {
332  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while changing parameter: " << getErrorDescription(error));
333  }
334  }
335 
336  // Service calls
337  int callColor(l3cam_ros::LidarConfig &config)
338  {
339  int error = L3CAM_OK;
340 
341  srv_color_.request.visualization_color = config.pointcloud_color;
343  {
344  error = srv_color_.response.error;
345  if (!error)
346  {
347  // Parameter changed successfully, save value
348  pointcloud_color_ = config.pointcloud_color;
349  }
350  else
351  {
352  // Parameter could not be changed, reset parameter to value before change
353  config.pointcloud_color = pointcloud_color_;
354  }
355  }
356  else
357  {
358  // Service could not be called, reset parameter to value before change
359  config.pointcloud_color = pointcloud_color_;
361  }
362 
363  return error;
364  }
365 
366  int callColorRange(l3cam_ros::LidarConfig &config)
367  {
368  int error = L3CAM_OK;
369 
370  srv_color_range_.request.min_value = config.pointcloud_color_range_minimum;
371  srv_color_range_.request.max_value = config.pointcloud_color_range_maximum;
373  {
374  error = srv_color_range_.response.error;
375  if (!error)
376  {
377  // Parameter changed successfully, save value
378  pointcloud_color_range_minimum_ = config.pointcloud_color_range_minimum;
379  pointcloud_color_range_maximum_ = config.pointcloud_color_range_maximum;
380  }
381  else
382  {
383  // Parameter could not be changed, reset parameter to value before change
384  config.pointcloud_color_range_minimum = pointcloud_color_range_minimum_;
385  config.pointcloud_color_range_maximum = pointcloud_color_range_maximum_;
386  }
387  }
388  else
389  {
390  // Service could not be called, reset parameter to value before change
391  config.pointcloud_color_range_minimum = pointcloud_color_range_minimum_;
392  config.pointcloud_color_range_maximum = pointcloud_color_range_maximum_;
394  }
395 
396  return error;
397  }
398 
399  int callDistanceRange(l3cam_ros::LidarConfig &config)
400  {
401  int error = L3CAM_OK;
402 
403  srv_distance_range_.request.min_value = config.distance_range_minimum;
404  srv_distance_range_.request.max_value = config.distance_range_maximum;
406  {
407  error = srv_distance_range_.response.error;
408  if (!error)
409  {
410  // Parameter changed successfully, save value
411  distance_range_minimum_ = config.distance_range_minimum;
412  distance_range_maximum_ = config.distance_range_maximum;
413  }
414  else
415  {
416  // Parameter could not be changed, reset parameter to value before change
417  config.distance_range_minimum = distance_range_minimum_;
418  config.distance_range_maximum = distance_range_maximum_;
419  }
420  }
421  else
422  {
423  // Service could not be called, reset parameter to value before change
424  config.distance_range_minimum = distance_range_minimum_;
425  config.distance_range_maximum = distance_range_maximum_;
427  }
428 
429  return error;
430  }
431 
432  int callBiasShortRange(l3cam_ros::LidarConfig &config)
433  {
434  int error = L3CAM_OK;
435 
436  srv_bias_short_range_.request.enabled = config.bias_short_range;
438  {
439  error = srv_bias_short_range_.response.error;
440  if (!error)
441  {
442  // Parameter changed successfully, save value
443  bias_short_range_ = config.bias_short_range;
444  }
445  else
446  {
447  // Parameter could not be changed, reset parameter to value before change
448  config.bias_short_range = bias_short_range_;
449  }
450  }
451  else
452  {
453  // Service could not be called, reset parameter to value before change
454  config.bias_short_range = bias_short_range_;
456  }
457 
458  return error;
459  }
460 
461  int callAutoBias(l3cam_ros::LidarConfig &config)
462  {
463  int error = L3CAM_OK;
464 
465  srv_auto_bias_.request.enabled = config.auto_bias;
467  {
468  error = srv_bias_short_range_.response.error;
469  if (!error)
470  {
471  // Parameter changed successfully, save value
472  auto_bias_ = config.auto_bias;
473  }
474  else
475  {
476  // Parameter could not be changed, reset parameter to value before change
477  config.auto_bias = auto_bias_;
478  }
479  }
480  else
481  {
482  // Service could not be called, reset parameter to value before change
483  config.auto_bias = auto_bias_;
485  }
486 
487  return error;
488  }
489 
490  int callBiasValueRight(l3cam_ros::LidarConfig &config)
491  {
492  int error = L3CAM_OK;
493 
494  srv_bias_value_.request.index = 1;
495  srv_bias_value_.request.bias = config.bias_value_right;
497  {
498  error = srv_bias_value_.response.error;
499  if (!error)
500  {
501  // Parameter changed successfully, save value
502  bias_value_right_ = config.bias_value_right;
503  }
504  else
505  {
506  // Parameter could not be changed, reset parameter to value before change
507  config.bias_value_right = bias_value_right_;
508  }
509  }
510  else
511  {
512  // Service could not be called, reset parameter to value before change
513  config.bias_value_right = bias_value_right_;
515  }
516 
517  return error;
518  }
519 
520  int callBiasValueLeft(l3cam_ros::LidarConfig &config)
521  {
522  int error = L3CAM_OK;
523 
524  srv_bias_value_.request.index = 2;
525  srv_bias_value_.request.bias = config.bias_value_left;
527  {
528  error = srv_bias_value_.response.error;
529  if (!error)
530  {
531  // Parameter changed successfully, save value
532  bias_value_left_ = config.bias_value_left;
533  }
534  else
535  {
536  // Parameter could not be changed, reset parameter to value before change
537  config.bias_value_left = bias_value_left_;
538  }
539  }
540  else
541  {
542  // Service could not be called, reset parameter to value before change
543  config.bias_value_left = bias_value_left_;
545  }
546 
547  return error;
548  }
549 
550  int callAutobiasValueRight(l3cam_ros::LidarConfig &config)
551  {
552  int error = L3CAM_OK;
553 
554  srv_autobias_value_.request.index = 1;
555  srv_autobias_value_.request.autobias = config.autobias_value_right;
557  {
558  error = srv_autobias_value_.response.error;
559  if (!error)
560  {
561  // Parameter changed successfully, save value
562  autobias_value_right_ = config.autobias_value_right;
563  }
564  else
565  {
566  // Parameter could not be changed, reset parameter to value before change
567  config.autobias_value_right = autobias_value_right_;
568  }
569  }
570  else
571  {
572  // Service could not be called, reset parameter to value before change
573  config.autobias_value_right = autobias_value_right_;
575  }
576 
577  return error;
578  }
579 
580  int callAutobiasValueLeft(l3cam_ros::LidarConfig &config)
581  {
582  int error = L3CAM_OK;
583 
584  srv_autobias_value_.request.index = 2;
585  srv_autobias_value_.request.autobias = config.autobias_value_left;
587  {
588  error = srv_autobias_value_.response.error;
589  if (!error)
590  {
591  // Parameter changed successfully, save value
592  autobias_value_left_ = config.autobias_value_left;
593  }
594  else
595  {
596  // Parameter could not be changed, reset parameter to value before change
597  config.autobias_value_left = autobias_value_left_;
598  }
599  }
600  else
601  {
602  // Service could not be called, reset parameter to value before change
603  config.autobias_value_left = autobias_value_left_;
605  }
606 
607  return error;
608  }
609 
610  int callStreamingProtocol(l3cam_ros::LidarConfig &config)
611  {
612  int error = L3CAM_OK;
613 
614  srv_change_streaming_protocol_.request.protocol = config.lidar_streaming_protocol;
615  srv_change_streaming_protocol_.request.sensor_type = (int)sensorTypes::sensor_lidar;
617  {
618  error = srv_change_streaming_protocol_.response.error;
619  if (!error)
620  {
621  // Parameter changed successfully, save value
622  lidar_streaming_protocol_ = config.lidar_streaming_protocol;
623  }
624  else
625  {
626  // Parameter could not be changed, reset parameter to value before change
627  config.lidar_streaming_protocol = lidar_streaming_protocol_;
628  }
629  }
630  else
631  {
632  // Service could not be called, reset parameter to value before change
633  config.lidar_streaming_protocol = lidar_streaming_protocol_;
635  }
636 
637  return error;
638  }
639 
640  int callRtspPipeline(l3cam_ros::LidarConfig &config)
641  {
642  // Read-only
643  ROS_WARN_STREAM(this->getNamespace() << " The RTSP Pipeline parameter is read-only, only changeable at launch");
644  config.lidar_rtsp_pipeline = lidar_rtsp_pipeline_;
645 
646  return L3CAM_OK;
647  }
648 
649  bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
650  {
651  ROS_BMG_UNUSED(res);
652  if (req.code == 0)
653  {
654  ROS_INFO_STREAM(this->getNamespace() << " Exiting " << this->getNamespace() << " cleanly.");
655  }
656  else
657  {
658  ROS_WARN_STREAM(this->getNamespace() << " Exiting " << this->getNamespace() << ". Sensor got disconnected with error " << req.code << ": " << getErrorDescription(req.code));
659  }
660 
661  m_shutdown_requested = true;
662  return true;
663  }
664 
665  dynamic_reconfigure::Server<l3cam_ros::LidarConfig> *server_;
666 
668  l3cam_ros::ChangePointcloudColor srv_color_;
670  l3cam_ros::ChangePointcloudColorRange srv_color_range_;
672  l3cam_ros::ChangeDistanceRange srv_distance_range_;
674  l3cam_ros::SetBiasShortRange srv_bias_short_range_;
676  l3cam_ros::EnableAutoBias srv_auto_bias_;
678  l3cam_ros::ChangeBiasValue srv_bias_value_;
680  l3cam_ros::ChangeAutobiasValue srv_autobias_value_;
682  l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_;
684  l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_;
685 
687 
700  std::string lidar_rtsp_pipeline_;
701 
704 
705  }; // class LidarConfiguration
706 
707 } // namespace l3cam_ros
708 
709 int main(int argc, char **argv)
710 {
711  ros::init(argc, argv, "lidar_configuration");
712 
714 
715  // Check if service is available
716  ros::Duration timeout_duration(node->timeout_secs_);
717  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
718  {
719  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
721  }
722 
723  int error = L3CAM_OK;
724  bool sensor_is_available = false;
725  // Shutdown if sensor is not available or if error returned
726  if (node->client_get_sensors_.call(node->srv_get_sensors_))
727  {
728  error = node->srv_get_sensors_.response.error;
729 
730  if (!error)
731  {
732  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
733  {
734  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_lidar && node->srv_get_sensors_.response.sensors[i].sensor_available)
735  {
736  sensor_is_available = true;
737  }
738  }
739  }
740  else
741  {
742  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability: " << getErrorDescription(error));
743  return error;
744  }
745  }
746  else
747  {
748  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
750  }
751 
752  if (sensor_is_available)
753  {
754  ROS_INFO("LiDAR configuration is available");
755  }
756  else
757  {
758  return 0;
759  }
760 
761  node->setDynamicReconfigure();
762 
763  node->spin();
764 
765  ros::shutdown();
766  return 0;
767 }
l3cam_ros::LidarConfiguration::parametersCallback
void parametersCallback(l3cam_ros::LidarConfig &config, uint32_t level)
Definition: lidar_configuration.cpp:275
l3cam_ros::LidarConfiguration::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: lidar_configuration.cpp:107
l3cam_ros::LidarConfiguration::autobias_value_right_
int autobias_value_right_
Definition: lidar_configuration.cpp:697
l3cam_ros::LidarConfiguration::distance_range_minimum_
int distance_range_minimum_
Definition: lidar_configuration.cpp:691
l3cam_ros::LidarConfiguration::client_bias_value_
ros::ServiceClient client_bias_value_
Definition: lidar_configuration.cpp:677
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
l3cam_ros::LidarConfiguration::m_default_configured
bool m_default_configured
Definition: lidar_configuration.cpp:702
l3cam_ros::LidarConfiguration::srv_get_sensors_
l3cam_ros::GetSensorsAvailable srv_get_sensors_
Definition: lidar_configuration.cpp:101
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
l3cam_ros::LidarConfiguration::bias_short_range_
bool bias_short_range_
Definition: lidar_configuration.cpp:693
l3cam_ros::LidarConfiguration::client_bias_short_range_
ros::ServiceClient client_bias_short_range_
Definition: lidar_configuration.cpp:673
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::LidarConfiguration::LidarConfiguration
LidarConfiguration()
Definition: lidar_configuration.cpp:58
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
l3cam_ros::LidarConfiguration::callColorRange
int callColorRange(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:366
l3cam_ros::LidarConfiguration::callAutoBias
int callAutoBias(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:461
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
l3cam_ros::LidarConfiguration::callBiasValueRight
int callBiasValueRight(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:490
l3cam_ros::LidarConfiguration::callAutobiasValueRight
int callAutobiasValueRight(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:550
l3cam_ros::LidarConfiguration::callRtspPipeline
int callRtspPipeline(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:640
l3cam_ros::LidarConfiguration::callAutobiasValueLeft
int callAutobiasValueLeft(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:580
l3cam_ros::LidarConfiguration::srv_color_
l3cam_ros::ChangePointcloudColor srv_color_
Definition: lidar_configuration.cpp:668
ros::spinOnce
ROSCPP_DECL void spinOnce()
l3cam_ros::LidarConfiguration::client_auto_bias_
ros::ServiceClient client_auto_bias_
Definition: lidar_configuration.cpp:675
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros::LidarConfiguration::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: lidar_configuration.cpp:649
l3cam_ros::LidarConfiguration::client_change_streaming_protocol_
ros::ServiceClient client_change_streaming_protocol_
Definition: lidar_configuration.cpp:681
l3cam_ros
Definition: l3cam_ros_node.hpp:133
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
ros::ok
ROSCPP_DECL bool ok()
l3cam_ros::LidarConfiguration::distance_range_maximum_
int distance_range_maximum_
Definition: lidar_configuration.cpp:692
l3cam_ros::L3Cam::timeout_secs_
int timeout_secs_
Definition: l3cam_ros_node.hpp:404
ros::ServiceServer
l3cam_ros::LidarConfiguration::callColor
int callColor(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:337
l3cam_ros::LidarConfiguration::setDynamicReconfigure
void setDynamicReconfigure()
Definition: lidar_configuration.cpp:81
l3cam_ros::LidarConfiguration::pointcloud_color_
int pointcloud_color_
Definition: lidar_configuration.cpp:688
l3cam_ros::LidarConfiguration::pointcloud_color_range_maximum_
int pointcloud_color_range_maximum_
Definition: lidar_configuration.cpp:690
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros::LidarConfiguration::autobias_value_left_
int autobias_value_left_
Definition: lidar_configuration.cpp:698
l3cam_ros::LidarConfiguration::client_distance_range_
ros::ServiceClient client_distance_range_
Definition: lidar_configuration.cpp:671
l3cam_ros::LidarConfiguration::srv_color_range_
l3cam_ros::ChangePointcloudColorRange srv_color_range_
Definition: lidar_configuration.cpp:670
l3cam_ros::LidarConfiguration::client_color_range_
ros::ServiceClient client_color_range_
Definition: lidar_configuration.cpp:669
l3cam_ros_utils.hpp
l3cam_ros::LidarConfiguration::srv_autobias_value_
l3cam_ros::ChangeAutobiasValue srv_autobias_value_
Definition: lidar_configuration.cpp:680
l3cam_ros::LidarConfiguration::bias_value_left_
int bias_value_left_
Definition: lidar_configuration.cpp:696
l3cam_ros::LidarConfiguration::configureDefault
void configureDefault(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:143
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::LidarConfiguration::lidar_streaming_protocol_
int lidar_streaming_protocol_
Definition: lidar_configuration.cpp:699
l3cam_ros::LidarConfiguration::srv_bias_short_range_
l3cam_ros::SetBiasShortRange srv_bias_short_range_
Definition: lidar_configuration.cpp:674
l3cam_ros::LidarConfiguration::auto_bias_
bool auto_bias_
Definition: lidar_configuration.cpp:694
ros::ServiceClient
l3cam_ros::LidarConfiguration
Definition: lidar_configuration.cpp:55
l3cam_ros::LidarConfiguration::client_autobias_value_
ros::ServiceClient client_autobias_value_
Definition: lidar_configuration.cpp:679
l3cam_ros::LidarConfiguration::client_get_rtsp_pipeline_
ros::ServiceClient client_get_rtsp_pipeline_
Definition: lidar_configuration.cpp:683
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
l3cam_ros::LidarConfiguration::server_
dynamic_reconfigure::Server< l3cam_ros::LidarConfig > * server_
Definition: lidar_configuration.cpp:665
l3cam_ros::LidarConfiguration::srv_change_streaming_protocol_
l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_
Definition: lidar_configuration.cpp:682
ros::NodeHandle::NodeHandle
NodeHandle(const NodeHandle &parent, const std::string &ns)
main
int main(int argc, char **argv)
Definition: lidar_configuration.cpp:709
l3cam_ros::LidarConfiguration::srv_auto_bias_
l3cam_ros::EnableAutoBias srv_auto_bias_
Definition: lidar_configuration.cpp:676
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::LidarConfiguration::callBiasShortRange
int callBiasShortRange(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:432
l3cam_ros::LidarConfiguration::timeout_secs_
int timeout_secs_
Definition: lidar_configuration.cpp:103
l3cam_ros::LidarConfiguration::srv_sensor_disconnected_
ros::ServiceServer srv_sensor_disconnected_
Definition: lidar_configuration.cpp:686
l3cam_ros::LidarConfiguration::callDistanceRange
int callDistanceRange(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:399
l3cam_ros::LidarConfiguration::lidar_rtsp_pipeline_
std::string lidar_rtsp_pipeline_
Definition: lidar_configuration.cpp:700
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
l3cam_ros::LidarConfiguration::srv_distance_range_
l3cam_ros::ChangeDistanceRange srv_distance_range_
Definition: lidar_configuration.cpp:672
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
l3cam_ros::LidarConfiguration::loadDefaultParams
void loadDefaultParams()
Definition: lidar_configuration.cpp:125
ros::Duration::sleep
bool sleep() const
l3cam_ros::LidarConfiguration::bias_value_right_
int bias_value_right_
Definition: lidar_configuration.cpp:695
l3cam_ros::LidarConfiguration::callStreamingProtocol
int callStreamingProtocol(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:610
l3cam_ros::LidarConfiguration::client_get_sensors_
ros::ServiceClient client_get_sensors_
Definition: lidar_configuration.cpp:100
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
l3cam_ros::LidarConfiguration::callBiasValueLeft
int callBiasValueLeft(l3cam_ros::LidarConfig &config)
Definition: lidar_configuration.cpp:520
ROS_INFO
#define ROS_INFO(...)
l3cam_ros::LidarConfiguration::srv_bias_value_
l3cam_ros::ChangeBiasValue srv_bias_value_
Definition: lidar_configuration.cpp:678
l3cam_ros::LidarConfiguration::pointcloud_color_range_minimum_
int pointcloud_color_range_minimum_
Definition: lidar_configuration.cpp:689
ros::Duration
l3cam_ros::LidarConfiguration::srv_get_rtsp_pipeline_
l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_
Definition: lidar_configuration.cpp:684
l3cam_ros::LidarConfiguration::m_shutdown_requested
bool m_shutdown_requested
Definition: lidar_configuration.cpp:703
l3cam_ros::LidarConfiguration::spin
void spin()
Definition: lidar_configuration.cpp:89
l3cam_ros::LidarConfiguration::client_color_
ros::ServiceClient client_color_
Definition: lidar_configuration.cpp:667
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
ros::NodeHandle


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