l3cam_ros_node.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 "l3cam_ros_node.hpp"
29 
30 #include <signal.h>
31 
32 #include <libL3Cam.h>
33 #include <libL3Cam_allied.h>
34 #include <libL3Cam_econ.h>
35 #include <libL3Cam_polarimetric.h>
36 #include <libL3Cam_thermal.h>
37 #include <beamErrors.h>
38 
39 #include "l3cam_ros/Sensor.h"
40 
42 
43 namespace l3cam_ros
44 {
45  L3Cam::L3Cam() : ros::NodeHandle("~")
46  {
47  // Register callback for sensor disconnection errors
48  registerErrorCallback(errorNotification);
49 
50  // L3Cam node status
52  srv_libl3cam_status_ = advertiseService("libl3cam_status", &L3Cam::libL3camStatus, this);
53 
54  loadParam("timeout_secs", timeout_secs_, 60);
55 
56  m_num_devices = 0;
57  m_shutdown_requested = false;
58  }
59 
60  void L3Cam::spin()
61  {
62  while (ros::ok() && !m_shutdown_requested)
63  {
64  ros::spinOnce();
65  ros::Duration(0.1).sleep();
66  }
67 
68  // Before exiting stop stream, device and terminate
69  std::cout << "Terminating..." << std::endl;
70  STOP_STREAM(node->m_devices[0]);
71  STOP_DEVICE(node->m_devices[0]);
72  TERMINATE(node->m_devices[0]);
74  node = NULL;
75  // Needs to wait for a second to Terminate
76  usleep(1000000);
77  std::cout << "Terminated." << std::endl;
78 
79  ros::shutdown();
80  }
81 
83  {
84  // Initialize L3Cam
85  int error = L3CAM_OK;
86 
87  std::string local_address, device_address;
88  param("/l3cam_ros_node/local_address", local_address);
89  param("/l3cam_ros_node/device_address", device_address);
90 
91  if (local_address == "" || device_address == "")
92  {
93  error = INITIALIZE(NULL, NULL);
94  }
95  else
96  {
97  error = INITIALIZE(&local_address[0], &device_address[0]);
98  }
99 
100  if (error)
101  return error;
102 
103  int i = 0;
104  while (m_num_devices == 0 && error == L3CAM_OK)
105  {
106  error = FIND_DEVICES(m_devices, &m_num_devices);
107 
108  if (!ros::ok())
109  {
110  return L3CAM_ROS_INTERRUPTED;
111  }
112 
113  if (i >= timeout_secs_ * 2)
115  usleep(500000);
116  ++i;
117  }
118 
119  if (error)
120  return error;
122  ROS_INFO_STREAM("Device found " << std::string(m_devices[0].ip_address)
123  << ", model " << (int)m_devices[0].model
124  << ", serial number " << std::string(m_devices[0].serial_number)
125  << ", app version " << std::string(m_devices[0].app_version));
126 
127  int status = 0;
128  error = GET_DEVICE_STATUS(m_devices[0], &status);
129  if (error)
130  return error;
131  ROS_INFO_STREAM("Device status " << status);
132 
133  int num_sensors = 0;
134  error = GET_SENSORS_AVAILABLE(m_devices[0], m_av_sensors, &num_sensors);
135  if (error)
136  return error;
137 
138  for (int i = 0; i < num_sensors; ++i)
139  {
140  switch (m_av_sensors[i].sensor_type)
141  {
142  case sensor_lidar:
144  break;
145  case sensor_econ_rgb:
147  break;
148  case sensor_thermal:
150  break;
151  case sensor_pol:
153  break;
154  case sensor_allied_wide:
156  break;
157  case sensor_allied_narrow:
159  break;
160  case sensor_econ_wide:
162  break;
163  }
164  }
165 
166  ROS_INFO_STREAM(num_sensors << ((num_sensors == 1) ? " sensor" : " sensors") << " available");
167 
169 
170  return L3CAM_OK;
171  }
172 
174  {
175  int error = L3CAM_OK;
176 
177  error = START_DEVICE(m_devices[0]);
178  if (error)
179  {
180  return error;
181  }
182 
184  ROS_INFO("Device started");
185 
187 
188  error = START_STREAM(m_devices[0]);
189  if (error)
190  return error;
191 
193  ROS_INFO("Device streaming ready\n");
194 
195  return L3CAM_OK;
196  }
197 
198  void L3Cam::disconnectAll(int code)
199  {
200  networkDisconnected(code);
201  if (m_lidar_sensor != NULL && m_lidar_sensor->sensor_available)
202  {
203  lidarDisconnected(code);
204  }
205  if (m_polarimetric_sensor != NULL && m_polarimetric_sensor->sensor_available)
206  {
207  polDisconnected(code);
208  }
209  if (m_rgb_sensor != NULL && m_rgb_sensor->sensor_available)
210  {
211  rgbDisconnected(code);
212  }
213  if (m_allied_wide_sensor != NULL && m_allied_wide_sensor->sensor_available)
214  {
216  }
217  if (m_allied_narrow_sensor != NULL && m_allied_narrow_sensor->sensor_available)
218  {
220  }
221  if (m_thermal_sensor != NULL && m_thermal_sensor->sensor_available)
222  {
223  thermalDisconnected(code);
224  }
225  }
226 
227  // Initialize Services
229  {
230  srv_get_version_ = advertiseService("get_version", &L3Cam::getVersion, this);
231  srv_initialize_ = advertiseService("initialize", &L3Cam::initialize, this);
232  srv_terminate_ = advertiseService("terminate", &L3Cam::terminate, this);
233  srv_find_devices_ = advertiseService("find_devices", &L3Cam::findDevices, this);
235  srv_get_device_info_ = advertiseService("get_device_info", &L3Cam::getDeviceInfo, this);
236  srv_get_device_status_ = advertiseService("get_device_status", &L3Cam::getDeviceStatus, this);
239  srv_get_rtsp_pipeline_ = advertiseService("get_rtsp_pipeline", &L3Cam::getRtspPipeline, this);
242  srv_power_off_device_ = advertiseService("power_off_device", &L3Cam::powerOffDevice, this);
243  srv_start_device_ = advertiseService("start_device", &L3Cam::startDevice, this);
244  srv_stop_device_ = advertiseService("stop_device", &L3Cam::stopDevice, this);
245  srv_start_stream_ = advertiseService("start_stream", &L3Cam::startStream, this);
246  srv_stop_stream_ = advertiseService("stop_stream", &L3Cam::stopStream, this);
248 
249  client_network_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/network_configuration/network_disconnected");
250 
251  if (m_lidar_sensor != NULL && m_lidar_sensor->sensor_available) // if lidar is available
252  {
254  }
255 
256  if (m_polarimetric_sensor != NULL && m_polarimetric_sensor->sensor_available) // if polarimetric is available
257  {
259  }
260 
261  if (m_rgb_sensor != NULL && m_rgb_sensor->sensor_available) // if rgb is available
262  {
264  }
265 
266  if (m_thermal_sensor != NULL && m_thermal_sensor->sensor_available) // if thermal is available
267  {
269  }
270 
271  if (m_allied_wide_sensor != NULL && m_allied_wide_sensor->sensor_available) // if allied wide is available
272  {
274  }
275  else if (m_allied_narrow_sensor != NULL && m_allied_narrow_sensor->sensor_available) // if allied narrow is available
276  {
278  }
279 
280  ROS_INFO("Services ready");
281  }
282 
284  {
288  srv_set_bias_short_range_ = advertiseService("set_bias_short_range", &L3Cam::setBiasShortRange, this);
289  srv_enable_auto_bias_ = advertiseService("enable_auto_bias", &L3Cam::enableAutoBias, this);
290  srv_change_bias_value_ = advertiseService("change_bias_value", &L3Cam::changeBiasValue, this);
292  srv_get_autobias_value_ = advertiseService("get_autobias_value", &L3Cam::getAutobiasValue, this);
293 
294  client_lidar_stream_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/lidar_stream/lidar_stream_disconnected");
295  client_lidar_configuration_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/lidar_configuration/lidar_configuration_disconnected");
296  }
297 
299  {
309 
310  client_pol_wide_stream_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/polarimetric_wide_stream/polarimetric_wide_stream_disconnected");
311  client_pol_configuration_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/polarimetric_configuration/polarimetric_configuration_disconnected");
312  }
313 
315  {
327 
328  client_rgb_narrow_stream_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/rgb_narrow_stream/rgb_narrow_stream_disconnected");
329  client_rgb_configuration_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/rgb_configuration/rgb_configuration_disconnected");
330  }
331 
333  {
339 
340  client_thermal_stream_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/thermal_stream/thermal_stream_disconnected");
341  client_thermal_configuration_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/thermal_configuration/thermal_configuration_disconnected");
342  }
343 
345  {
363 
385 
386  client_pol_wide_stream_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/polarimetric_wide_stream/polarimetric_wide_stream_disconnected");
387  client_wide_configuration_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/allied_wide_configuration/allied_wide_configuration_disconnected");
388  }
389 
391  {
409 
431 
432  client_rgb_narrow_stream_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/rgb_narrow_stream/rgb_narrow_stream_disconnected");
433  client_narrow_configuration_disconnected_ = serviceClient<l3cam_ros::SensorDisconnected>("/L3Cam/allied_narrow_configuration/allied_narrow_configuration_disconnected");
434  }
435 
436  inline void L3Cam::printDefaultError(int error, std::string param)
437  {
438  if (error != L3CAM_OK)
439  {
440  ROS_WARN_STREAM(this->getNamespace() << " error " << error << " while setting default parameter " << param << ": "
441  << getErrorDescription(error));
442  }
443  }
444 
445  // Load default params
446  template <typename T>
447  void L3Cam::loadParam(const std::string &param_name, T &param_var, const T &default_val)
448  {
449  std::string full_param_name;
450 
451  if (searchParam(param_name, full_param_name))
452  {
453  if (!getParam(full_param_name, param_var))
454  {
455  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
456  }
457  }
458  else
459  {
460  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
461  param_var = default_val;
462  }
463  }
464 
466  {
468  if (m_lidar_sensor != NULL) // if lidar should be available in the L3Cam
469  {
470  if (m_lidar_sensor->sensor_available) // if lidar is available
471  {
473  }
474  else
475  {
476  ROS_ERROR_STREAM(this->getNamespace() << " error: LiDAR not available.");
477  }
478  }
479  if (m_polarimetric_sensor != NULL) // if polarimetric should be available in the L3Cam
480  {
481  if (m_polarimetric_sensor->sensor_available) // if polarimetric is available
482  {
484  }
485  else
486  {
487  ROS_ERROR_STREAM(this->getNamespace() << " error: Polarimetric camera not available.");
488  }
489  }
490  if (m_rgb_sensor != NULL) // if rgb should be available in the L3Cam
491  {
492  if (m_rgb_sensor->sensor_available) // if rgb is available
493  {
495  }
496  else
497  {
498  ROS_ERROR_STREAM(this->getNamespace() << " error: RGB camera not available.");
499  }
500  }
501  if (m_thermal_sensor != NULL) // if thermal should be available in the L3Cam
502  {
503  if (m_thermal_sensor->sensor_available) // if thermal is available
504  {
506  }
507  else
508  {
509  ROS_ERROR_STREAM(this->getNamespace() << " error: Thermal camera not available.");
510  }
511  }
512  if (m_allied_wide_sensor != NULL) // if allied wide should be available in the L3Cam
513  {
514  if (m_allied_wide_sensor->sensor_available) // if allied wide is available
515  {
517  }
518  else
519  {
520  ROS_ERROR_STREAM(this->getNamespace() << " error: Allied Wide camera not available.");
521  }
522  }
523  if (m_allied_narrow_sensor != NULL) // if allied narrow should be available in the L3Cam
524  {
525  if (m_allied_narrow_sensor->sensor_available) // if allied narrow is available
526  {
528  }
529  else
530  {
531  ROS_ERROR_STREAM(this->getNamespace() << " error: Allied Narrow camera not available.");
532  }
533  }
534 
535  ROS_INFO("Default parameters loaded");
536  }
537 
539  {
540  char *ip_address = NULL;
541  char *netmask = NULL;
542  char *gateway = NULL;
543  int error = GET_NETWORK_CONFIGURATION(m_devices[0], &ip_address, &netmask, &gateway);
544  if (!error)
545  {
546  param("/ip_address", std::string(ip_address));
547  param("/netmask", std::string(netmask));
548  param("/gateway", std::string(gateway));
549  }
550  }
551 
553  {
554  int pointcloud_color;
555  loadParam("pointcloud_color", pointcloud_color, 0);
556  printDefaultError(CHANGE_POINT_CLOUD_COLOR(m_devices[0], pointcloud_color), "pointcloud_color");
557  int pointcloud_color_range_minimum;
558  loadParam("pointcloud_color_range_minimum", pointcloud_color_range_minimum, 0);
559  int pointcloud_color_range_maximum;
560  loadParam("pointcloud_color_range_maximum", pointcloud_color_range_maximum, 300000);
561  printDefaultError(CHANGE_POINT_CLOUD_COLOR_RANGE(m_devices[0], pointcloud_color_range_minimum, pointcloud_color_range_maximum), "pointcloud_color_range");
562  int distance_range_minimum;
563  loadParam("distance_range_minimum", distance_range_minimum, 0);
564  int distance_range_maximum;
565  loadParam("distance_range_maximum", distance_range_maximum, 300000);
566  printDefaultError(CHANGE_DISTANCE_RANGE(m_devices[0], distance_range_minimum, distance_range_maximum), "distance_range");
567  bool bias_short_range;
568  loadParam("bias_short_range", bias_short_range, false);
569  printDefaultError(SET_BIAS_SHORT_RANGE(m_devices[0], bias_short_range), "bias_short_range");
570  bool auto_bias;
571  loadParam("auto_bias", auto_bias, true);
572  printDefaultError(ENABLE_AUTO_BIAS(m_devices[0], auto_bias), "auto_bias");
573  if (!auto_bias)
574  {
575  int bias_value_right;
576  loadParam("bias_value_right", bias_value_right, 1580);
577  printDefaultError(CHANGE_BIAS_VALUE(m_devices[0], 1, bias_value_right), "bias_value_right");
578  int bias_value_left;
579  loadParam("bias_value_left", bias_value_left, 1380);
580  printDefaultError(CHANGE_BIAS_VALUE(m_devices[0], 2, bias_value_left), "bias_value_left");
581  }
582  else
583  {
584  int autobias_value_right;
585  loadParam("autobias_value_right", autobias_value_right, 50);
586  printDefaultError(CHANGE_AUTOBIAS_VALUE(m_devices[0], 1, autobias_value_right), "autobias_value_right");
587  int autobias_value_left;
588  loadParam("autobias_value_left", autobias_value_left, 50);
589  printDefaultError(CHANGE_AUTOBIAS_VALUE(m_devices[0], 2, autobias_value_left), "autobias_value_left");
590  }
591  int lidar_streaming_protocol;
592  loadParam("lidar_streaming_protocol", lidar_streaming_protocol, 0);
593  if (lidar_streaming_protocol == 1)
594  {
595  m_lidar_sensor->protocol = protocol_gstreamer;
596  printDefaultError(CHANGE_STREAMING_PROTOCOL(m_devices[0], m_lidar_sensor), "lidar_streaming_protocol");
597  }
598  std::string lidar_rtsp_pipeline;
599  loadParam("lidar_rtsp_pipeline", lidar_rtsp_pipeline, std::string(""));
600  if (lidar_rtsp_pipeline != "")
601  {
602  char *pipeline = &lidar_rtsp_pipeline[0];
603  printDefaultError(CHANGE_RTSP_PIPELINE(m_devices[0], *m_lidar_sensor, pipeline), "lidar_rtsp_pipeline");
604  }
605  }
606 
608  {
609  int polarimetric_brightness;
610  loadParam("polarimetric_brightness", polarimetric_brightness, 127);
611  printDefaultError(CHANGE_POLARIMETRIC_CAMERA_BRIGHTNESS(m_devices[0], polarimetric_brightness), "polarimetric_brightness");
612  double polarimetric_black_level;
613  loadParam("polarimetric_black_level", polarimetric_black_level, 6.0);
614  printDefaultError(CHANGE_POLARIMETRIC_CAMERA_BLACK_LEVEL(m_devices[0], polarimetric_black_level), "polarimetric_black_level");
615  bool polarimetric_auto_gain;
616  loadParam("polarimetric_auto_gain", polarimetric_auto_gain, true);
617  printDefaultError(ENABLE_POLARIMETRIC_CAMERA_AUTO_GAIN(m_devices[0], polarimetric_auto_gain), "polarimetric_auto_gain");
618  if (polarimetric_auto_gain)
619  {
620  double polarimetric_auto_gain_range_minimum;
621  loadParam("polarimetric_auto_gain_range_minimum", polarimetric_auto_gain_range_minimum, 0.0);
622  double polarimetric_auto_gain_range_maximum;
623  loadParam("polarimetric_auto_gain_range_maximum", polarimetric_auto_gain_range_maximum, 48.0);
624  printDefaultError(CHANGE_POLARIMETRIC_CAMERA_AUTO_GAIN_RANGE(m_devices[0], polarimetric_auto_gain_range_minimum, polarimetric_auto_gain_range_maximum), "polarimetric_auto_gain_range");
625  }
626  else
627  {
628  double polarimetric_gain;
629  loadParam("polarimetric_gain", polarimetric_gain, 24.0);
630  printDefaultError(CHANGE_POLARIMETRIC_CAMERA_GAIN(m_devices[0], polarimetric_gain), "polarimetric_gain");
631  }
632  bool polarimetric_auto_exposure_time;
633  loadParam("polarimetric_auto_exposure_time", polarimetric_auto_exposure_time, true);
634  printDefaultError(ENABLE_POLARIMETRIC_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], polarimetric_auto_exposure_time), "polarimetric_auto_exposure_time");
635  if (polarimetric_auto_exposure_time)
636  {
637  double polarimetric_auto_exposure_time_range_minimum;
638  loadParam("polarimetric_auto_exposure_time_range_minimum", polarimetric_auto_exposure_time_range_minimum, 33.456);
639  double polarimetric_auto_exposure_time_range_maximum;
640  loadParam("polarimetric_auto_exposure_time_range_maximum", polarimetric_auto_exposure_time_range_maximum, 66470.6);
641  printDefaultError(CHANGE_POLARIMETRIC_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], polarimetric_auto_exposure_time_range_minimum, polarimetric_auto_exposure_time_range_maximum), "polarimetric_auto_exposure_time_range");
642  }
643  else
644  {
645  double polarimetric_exposure_time;
646  loadParam("polarimetric_exposure_time", polarimetric_exposure_time, 500000.0);
647  printDefaultError(CHANGE_POLARIMETRIC_CAMERA_EXPOSURE_TIME(m_devices[0], polarimetric_exposure_time), "polarimetric_exposure_time");
648  }
649  int polarimetric_streaming_protocol;
650  loadParam("polarimetric_streaming_protocol", polarimetric_streaming_protocol, 0);
651  if (polarimetric_streaming_protocol == 1)
652  {
653  m_polarimetric_sensor->protocol = protocol_gstreamer;
654  printDefaultError(CHANGE_STREAMING_PROTOCOL(m_devices[0], m_polarimetric_sensor), "polarimetric_streaming_protocol");
655  }
656  std::string polarimetric_rtsp_pipeline;
657  loadParam("polarimetric_rtsp_pipeline", polarimetric_rtsp_pipeline, std::string(""));
658  if (polarimetric_rtsp_pipeline != "")
659  {
660  char *pipeline = &polarimetric_rtsp_pipeline[0];
661  printDefaultError(CHANGE_RTSP_PIPELINE(m_devices[0], *m_polarimetric_sensor, pipeline), "polarimetric_rtsp_pipeline");
662  }
663  }
664 
666  {
667  int rgb_brightness;
668  param("/l3cam_ros_nod/rgb_brightness", rgb_brightness, 0);
669  printDefaultError(CHANGE_RGB_CAMERA_BRIGHTNESS(m_devices[0], rgb_brightness), "rgb_brightness");
670  int rgb_contrast;
671  param("/l3cam_ros_nod/rgb_contrast", rgb_contrast, 10);
672  printDefaultError(CHANGE_RGB_CAMERA_CONTRAST(m_devices[0], rgb_contrast), "rgb_contrast");
673  int rgb_saturation;
674  param("/l3cam_ros_nod/rgb_saturation", rgb_saturation, 16);
675  printDefaultError(CHANGE_RGB_CAMERA_SATURATION(m_devices[0], rgb_saturation), "rgb_saturation");
676  int rgb_sharpness;
677  loadParam("rgb_sharpness", rgb_sharpness, 16);
678  printDefaultError(CHANGE_RGB_CAMERA_SHARPNESS(m_devices[0], rgb_sharpness), "rgb_sharpness");
679  int rgb_gamma;
680  loadParam("rgb_gamma", rgb_gamma, 220);
681  printDefaultError(CHANGE_RGB_CAMERA_GAMMA(m_devices[0], rgb_gamma), "rgb_gamma");
682  int rgb_gain;
683  loadParam("rgb_gain", rgb_gain, 0);
684  printDefaultError(CHANGE_RGB_CAMERA_GAIN(m_devices[0], rgb_gain), "rgb_gain");
685  bool rgb_auto_white_balance;
686  loadParam("rgb_auto_white_balance", rgb_auto_white_balance, true);
687  printDefaultError(ENABLE_RGB_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], rgb_auto_white_balance), "rgb_auto_white_balance");
688  if (!rgb_auto_white_balance)
689  {
690  int rgb_white_balance;
691  loadParam("rgb_white_balance", rgb_white_balance, 5000);
692  printDefaultError(CHANGE_RGB_CAMERA_WHITE_BALANCE(m_devices[0], rgb_white_balance), "rgb_white_balance");
693  }
694  bool rgb_auto_exposure_time;
695  loadParam("rgb_auto_exposure_time", rgb_auto_exposure_time, true);
696  printDefaultError(ENABLE_RGB_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], rgb_auto_exposure_time), "rgb_auto_exposure_time");
697  if (!rgb_auto_exposure_time)
698  {
699  int rgb_exposure_time;
700  loadParam("rgb_exposure_time", rgb_exposure_time, 156);
701  printDefaultError(CHANGE_RGB_CAMERA_EXPOSURE_TIME(m_devices[0], rgb_exposure_time), "rgb_exposure_time");
702  }
703  int rgb_resolution;
704  loadParam("rgb_resolution", rgb_resolution, 3);
705  printDefaultError(CHANGE_RGB_CAMERA_RESOLUTION(m_devices[0], (econResolutions)rgb_resolution), "rgb_resolution");
706  int rgb_framerate;
707  loadParam("rgb_framerate", rgb_framerate, 10);
708  printDefaultError(CHANGE_RGB_CAMERA_FRAMERATE(m_devices[0], rgb_framerate), "rgb_framerate");
709  int rgb_streaming_protocol;
710  loadParam("rgb_streaming_protocol", rgb_streaming_protocol, 0);
711  if (rgb_streaming_protocol == 1)
712  {
713  m_rgb_sensor->protocol = protocol_gstreamer;
714  printDefaultError(CHANGE_STREAMING_PROTOCOL(m_devices[0], m_rgb_sensor), "rgb_streaming_protocol");
715  }
716  std::string rgb_rtsp_pipeline;
717  loadParam("rgb_rtsp_pipeline", rgb_rtsp_pipeline, std::string(""));
718  if (rgb_rtsp_pipeline != "")
719  {
720  char *pipeline = &rgb_rtsp_pipeline[0];
721  printDefaultError(CHANGE_RTSP_PIPELINE(m_devices[0], *m_rgb_sensor, pipeline), "rgb_rtsp_pipeline");
722  }
723  }
724 
726  {
727  int thermal_colormap;
728  loadParam("thermal_colormap", thermal_colormap, 1);
729  printDefaultError(CHANGE_THERMAL_CAMERA_COLORMAP(m_devices[0], thermal_colormap), "thermal_colormap");
730  bool thermal_temperature_filter;
731  loadParam("thermal_temperature_filter", thermal_temperature_filter, false);
732  printDefaultError(ENABLE_THERMAL_CAMERA_TEMPERATURE_FILTER(m_devices[0], thermal_temperature_filter), "thermal_temperature_filter");
733  int thermal_temperature_filter_min;
734  loadParam("thermal_temperature_filter_min", thermal_temperature_filter_min, 0);
735  int thermal_temperature_filter_max;
736  loadParam("thermal_temperature_filter_max", thermal_temperature_filter_max, 50);
737  printDefaultError(CHANGE_THERMAL_CAMERA_TEMPERATURE_FILTER(m_devices[0], thermal_temperature_filter_min, thermal_temperature_filter_max), "thermal_temperature_filter_max");
738  int thermal_processing_pipeline;
739  loadParam("thermal_processing_pipeline", thermal_processing_pipeline, 1);
740  printDefaultError(CHANGE_THERMAL_CAMERA_PROCESSING_PIPELINE(m_devices[0], thermal_processing_pipeline), "thermal_processing_pipeline");
741  bool thermal_temperature_data_udp;
742  loadParam("thermal_temperature_data_udp", thermal_temperature_data_udp, false);
743  printDefaultError(ENABLE_THERMAL_CAMERA_TEMPERATURE_DATA_UDP(m_devices[0], thermal_temperature_data_udp), "thermal_temperature_data_udp");
744  int thermal_streaming_protocol;
745  loadParam("thermal_streaming_protocol", thermal_streaming_protocol, 0);
746  if (thermal_streaming_protocol == 1)
747  {
748  m_thermal_sensor->protocol = protocol_gstreamer;
749  printDefaultError(CHANGE_STREAMING_PROTOCOL(m_devices[0], m_thermal_sensor), "thermal_streaming_protocol");
750  }
751  std::string thermal_rtsp_pipeline;
752  loadParam("thermal_rtsp_pipeline", thermal_rtsp_pipeline, std::string(""));
753  if (thermal_rtsp_pipeline != "")
754  {
755  char *pipeline = &thermal_rtsp_pipeline[0];
756  printDefaultError(CHANGE_RTSP_PIPELINE(m_devices[0], *m_thermal_sensor, pipeline), "thermal_rtsp_pipeline");
757  }
758  }
759 
761  {
762  double allied_wide_black_level;
763  loadParam("allied_wide_black_level", allied_wide_black_level, 0.);
764  printDefaultError(CHANGE_ALLIED_CAMERA_BLACK_LEVEL(m_devices[0], *m_allied_wide_sensor, allied_wide_black_level), "allied_wide_black_level");
765  bool allied_wide_auto_exposure_time;
766  loadParam("allied_wide_auto_exposure_time", allied_wide_auto_exposure_time, false);
767  printDefaultError(ENABLE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], *m_allied_wide_sensor, allied_wide_auto_exposure_time), "allied_wide_auto_exposure_time");
768  if (allied_wide_auto_exposure_time)
769  {
770  double allied_wide_auto_exposure_time_range_min;
771  loadParam("allied_wide_auto_exposure_time_range_min", allied_wide_auto_exposure_time_range_min, 87.596);
772  double allied_wide_auto_exposure_time_range_max;
773  loadParam("allied_wide_auto_exposure_time_range_max", allied_wide_auto_exposure_time_range_max, 87.596);
774  printDefaultError(CHANGE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], *m_allied_wide_sensor, allied_wide_auto_exposure_time_range_min, allied_wide_auto_exposure_time_range_max), "allied_wide_auto_exposure_time_range");
775  }
776  else
777  {
778  double allied_wide_exposure_time;
779  loadParam("allied_wide_exposure_time", allied_wide_exposure_time, 4992.32);
780  printDefaultError(CHANGE_ALLIED_CAMERA_EXPOSURE_TIME_US(m_devices[0], *m_allied_wide_sensor, allied_wide_exposure_time), "allied_wide_exposure_time");
781  }
782  bool allied_wide_auto_gain;
783  loadParam("allied_wide_auto_gain", allied_wide_auto_gain, false);
784  printDefaultError(ENABLE_ALLIED_CAMERA_AUTO_GAIN(m_devices[0], *m_allied_wide_sensor, allied_wide_auto_gain), "allied_wide_auto_gain");
785  if (allied_wide_auto_gain)
786  {
787  double allied_wide_auto_gain_range_min;
788  loadParam("allied_wide_auto_gain_range_min", allied_wide_auto_gain_range_min, 0.);
789  double allied_wide_auto_gain_range_max;
790  loadParam("allied_wide_auto_gain_range_max", allied_wide_auto_gain_range_max, 48.);
791  printDefaultError(CHANGE_ALLIED_CAMERA_AUTO_GAIN_RANGE(m_devices[0], *m_allied_wide_sensor, (float)allied_wide_auto_gain_range_min, (float)allied_wide_auto_gain_range_max), "allied_wide_auto_gain_range");
792  }
793  else
794  {
795  double allied_wide_gain;
796  loadParam("allied_wide_gain", allied_wide_gain, 0.);
797  printDefaultError(CHANGE_ALLIED_CAMERA_GAIN(m_devices[0], *m_allied_wide_sensor, allied_wide_gain), "allied_wide_gain");
798  }
799  double allied_wide_gamma;
800  loadParam("allied_wide_gamma", allied_wide_gamma, 1.);
801  printDefaultError(CHANGE_ALLIED_CAMERA_GAMMA(m_devices[0], *m_allied_wide_sensor, allied_wide_gamma), "allied_wide_gamma");
802  double allied_wide_saturation;
803  loadParam("allied_wide_saturation", allied_wide_saturation, 1.);
804  printDefaultError(CHANGE_ALLIED_CAMERA_SATURATION(m_devices[0], *m_allied_wide_sensor, allied_wide_saturation), "allied_wide_saturation");
805  double allied_wide_sharpness;
806  loadParam("allied_wide_sharpness", allied_wide_sharpness, 0.);
807  printDefaultError(CHANGE_ALLIED_CAMERA_SHARPNESS(m_devices[0], *m_allied_wide_sensor, allied_wide_sharpness), "allied_wide_sharpness");
808  double allied_wide_hue;
809  loadParam("allied_wide_hue", allied_wide_hue, 0.);
810  printDefaultError(CHANGE_ALLIED_CAMERA_HUE(m_devices[0], *m_allied_wide_sensor, allied_wide_hue), "allied_wide_hue");
811  int allied_wide_intensity_auto_precedence;
812  loadParam("allied_wide_intensity_auto_precedence", allied_wide_intensity_auto_precedence, 0);
813  printDefaultError(CHANGE_ALLIED_CAMERA_INTENSITY_AUTO_PRECEDENCE(m_devices[0], *m_allied_wide_sensor, allied_wide_intensity_auto_precedence), "allied_wide_intensity_auto_precedence");
814  bool allied_wide_auto_white_balance;
815  loadParam("allied_wide_auto_white_balance", allied_wide_auto_white_balance, false);
816  printDefaultError(ENABLE_ALLIED_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], *m_allied_wide_sensor, allied_wide_auto_white_balance), "allied_wide_auto_white_balance");
817  int allied_wide_balance_ratio_selector;
818  loadParam("allied_wide_balance_ratio_selector", allied_wide_balance_ratio_selector, 0);
819  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_RATIO_SELECTOR(m_devices[0], *m_allied_wide_sensor, allied_wide_balance_ratio_selector), "allied_wide_balance_ratio_selector");
820  double allied_wide_balance_ratio;
821  loadParam("allied_wide_balance_ratio", allied_wide_balance_ratio, 2.35498);
822  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_RATIO(m_devices[0], *m_allied_wide_sensor, allied_wide_balance_ratio), "allied_wide_balance_ratio");
823  double allied_wide_balance_white_auto_rate;
824  loadParam("allied_wide_balance_white_auto_rate", allied_wide_balance_white_auto_rate, 100.);
825  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_RATE(m_devices[0], *m_allied_wide_sensor, allied_wide_balance_white_auto_rate), "allied_wide_balance_white_auto_rate");
826  double allied_wide_balance_white_auto_tolerance;
827  loadParam("allied_wide_balance_white_auto_tolerance", allied_wide_balance_white_auto_tolerance, 5.);
828  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_TOLERANCE(m_devices[0], *m_allied_wide_sensor, allied_wide_balance_white_auto_tolerance), "allied_wide_balance_white_auto_tolerance");
829  int allied_wide_auto_mode_region_height;
830  loadParam("allied_wide_auto_mode_region_height", allied_wide_auto_mode_region_height, 2056);
831  int allied_wide_auto_mode_region_width;
832  loadParam("allied_wide_auto_mode_region_width", allied_wide_auto_mode_region_width, 2464);
833  printDefaultError(CHANGE_ALLIED_CAMERA_AUTO_MODE_REGION(m_devices[0], *m_allied_wide_sensor, allied_wide_auto_mode_region_height, allied_wide_auto_mode_region_width), "allied_wide_auto_mode_region_width");
834  int allied_wide_intensity_controller_region;
835  loadParam("allied_wide_intensity_controller_region", allied_wide_intensity_controller_region, 0);
836  printDefaultError(CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_REGION(m_devices[0], *m_allied_wide_sensor, allied_wide_intensity_controller_region), "allied_wide_intensity_controller_region");
837  double allied_wide_intensity_controller_target;
838  loadParam("allied_wide_intensity_controller_target", allied_wide_intensity_controller_target, 50.);
839  printDefaultError(CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_TARGET(m_devices[0], *m_allied_wide_sensor, allied_wide_intensity_controller_target), "allied_wide_intensity_controller_target");
840  int allied_wide_max_driver_buffers_count;
841  loadParam("allied_wide_max_driver_buffers_count", allied_wide_max_driver_buffers_count, 64);
842  printDefaultError(CHANGE_ALLIED_CAMERA_MAX_DRIVER_BUFFERS_COUNT(m_devices[0], *m_allied_wide_sensor, allied_wide_max_driver_buffers_count), "allied_wide_max_driver_buffers_count");
843  int allied_wide_streaming_protocol;
844  loadParam("allied_wide_streaming_protocol", allied_wide_streaming_protocol, 0);
845  if (allied_wide_streaming_protocol == 1)
846  {
847  m_allied_wide_sensor->protocol = protocol_gstreamer;
848  printDefaultError(CHANGE_STREAMING_PROTOCOL(m_devices[0], m_allied_wide_sensor), "allied_wide_streaming_protocol");
849  }
850  std::string allied_wide_rtsp_pipeline;
851  loadParam("allied_wide_rtsp_pipeline", allied_wide_rtsp_pipeline, std::string(""));
852  if (allied_wide_rtsp_pipeline != "")
853  {
854  char *pipeline = &allied_wide_rtsp_pipeline[0];
855  printDefaultError(CHANGE_RTSP_PIPELINE(m_devices[0], *m_allied_wide_sensor, pipeline), "allied_wide_rtsp_pipeline");
856  }
857  }
858 
860  {
861  double allied_narrow_black_level;
862  loadParam("allied_narrow_black_level", allied_narrow_black_level, 0.);
863  printDefaultError(CHANGE_ALLIED_CAMERA_BLACK_LEVEL(m_devices[0], *m_allied_narrow_sensor, allied_narrow_black_level), "allied_narrow_black_level");
864  bool allied_narrow_auto_exposure_time;
865  loadParam("allied_narrow_auto_exposure_time", allied_narrow_auto_exposure_time, false);
866  printDefaultError(ENABLE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], *m_allied_narrow_sensor, allied_narrow_auto_exposure_time), "allied_narrow_auto_exposure_time");
867  if (allied_narrow_auto_exposure_time)
868  {
869  double allied_narrow_auto_exposure_time_range_min;
870  loadParam("allied_narrow_auto_exposure_time_range_min", allied_narrow_auto_exposure_time_range_min, 87.596);
871  double allied_narrow_auto_exposure_time_range_max;
872  loadParam("allied_narrow_auto_exposure_time_range_max", allied_narrow_auto_exposure_time_range_max, 87.596);
873  printDefaultError(CHANGE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], *m_allied_narrow_sensor, allied_narrow_auto_exposure_time_range_min, allied_narrow_auto_exposure_time_range_max), "allied_narrow_auto_exposure_time_range");
874  }
875  else
876  {
877  double allied_narrow_exposure_time;
878  loadParam("allied_narrow_exposure_time", allied_narrow_exposure_time, 4992.32);
879  printDefaultError(CHANGE_ALLIED_CAMERA_EXPOSURE_TIME_US(m_devices[0], *m_allied_narrow_sensor, allied_narrow_exposure_time), "allied_narrow_exposure_time");
880  }
881  bool allied_narrow_auto_gain;
882  loadParam("allied_narrow_auto_gain", allied_narrow_auto_gain, false);
883  printDefaultError(ENABLE_ALLIED_CAMERA_AUTO_GAIN(m_devices[0], *m_allied_narrow_sensor, allied_narrow_auto_gain), "allied_narrow_auto_gain");
884  if (allied_narrow_auto_gain)
885  {
886  double allied_narrow_auto_gain_range_min;
887  loadParam("allied_narrow_auto_gain_range_min", allied_narrow_auto_gain_range_min, 0.);
888  double allied_narrow_auto_gain_range_max;
889  loadParam("allied_narrow_auto_gain_range_max", allied_narrow_auto_gain_range_max, 48.);
890  printDefaultError(CHANGE_ALLIED_CAMERA_AUTO_GAIN_RANGE(m_devices[0], *m_allied_narrow_sensor, (float)allied_narrow_auto_gain_range_min, (float)allied_narrow_auto_gain_range_max), "allied_narrow_auto_gain_range");
891  }
892  else
893  {
894  double allied_narrow_gain;
895  loadParam("allied_narrow_gain", allied_narrow_gain, 0.);
896  printDefaultError(CHANGE_ALLIED_CAMERA_GAIN(m_devices[0], *m_allied_narrow_sensor, allied_narrow_gain), "allied_narrow_gain");
897  }
898  double allied_narrow_gamma;
899  loadParam("allied_narrow_gamma", allied_narrow_gamma, 1.);
900  printDefaultError(CHANGE_ALLIED_CAMERA_GAMMA(m_devices[0], *m_allied_narrow_sensor, allied_narrow_gamma), "allied_narrow_gamma");
901  double allied_narrow_saturation;
902  loadParam("allied_narrow_saturation", allied_narrow_saturation, 1.);
903  printDefaultError(CHANGE_ALLIED_CAMERA_SATURATION(m_devices[0], *m_allied_narrow_sensor, allied_narrow_saturation), "allied_narrow_saturation");
904  double allied_narrow_sharpness;
905  loadParam("allied_narrow_sharpness", allied_narrow_sharpness, 0.);
906  printDefaultError(CHANGE_ALLIED_CAMERA_SHARPNESS(m_devices[0], *m_allied_narrow_sensor, allied_narrow_sharpness), "allied_narrow_sharpness");
907  double allied_narrow_hue;
908  loadParam("allied_narrow_hue", allied_narrow_hue, 0.);
909  printDefaultError(CHANGE_ALLIED_CAMERA_HUE(m_devices[0], *m_allied_narrow_sensor, allied_narrow_hue), "allied_narrow_hue");
910  int allied_narrow_intensity_auto_precedence;
911  loadParam("allied_narrow_intensity_auto_precedence", allied_narrow_intensity_auto_precedence, 0);
912  printDefaultError(CHANGE_ALLIED_CAMERA_INTENSITY_AUTO_PRECEDENCE(m_devices[0], *m_allied_narrow_sensor, allied_narrow_intensity_auto_precedence), "allied_narrow_intensity_auto_precedence");
913  bool allied_narrow_auto_white_balance;
914  loadParam("allied_narrow_auto_white_balance", allied_narrow_auto_white_balance, false);
915  printDefaultError(ENABLE_ALLIED_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], *m_allied_narrow_sensor, allied_narrow_auto_white_balance), "allied_narrow_auto_white_balance");
916  int allied_narrow_balance_ratio_selector;
917  loadParam("allied_narrow_balance_ratio_selector", allied_narrow_balance_ratio_selector, 0);
918  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_RATIO_SELECTOR(m_devices[0], *m_allied_narrow_sensor, allied_narrow_balance_ratio_selector), "allied_narrow_balance_ratio_selector");
919  double allied_narrow_balance_ratio;
920  loadParam("allied_narrow_balance_ratio", allied_narrow_balance_ratio, 2.35498);
921  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_RATIO(m_devices[0], *m_allied_narrow_sensor, allied_narrow_balance_ratio), "allied_narrow_balance_ratio");
922  double allied_narrow_balance_white_auto_rate;
923  loadParam("allied_narrow_balance_white_auto_rate", allied_narrow_balance_white_auto_rate, 100.);
924  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_RATE(m_devices[0], *m_allied_narrow_sensor, allied_narrow_balance_white_auto_rate), "allied_narrow_balance_white_auto_rate");
925  double allied_narrow_balance_white_auto_tolerance;
926  loadParam("allied_narrow_balance_white_auto_tolerance", allied_narrow_balance_white_auto_tolerance, 5.);
927  printDefaultError(CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_TOLERANCE(m_devices[0], *m_allied_narrow_sensor, allied_narrow_balance_white_auto_tolerance), "allied_narrow_balance_white_auto_tolerance");
928  int allied_narrow_auto_mode_region_height;
929  loadParam("allied_narrow_auto_mode_region_height", allied_narrow_auto_mode_region_height, 2056);
930  int allied_narrow_auto_mode_region_width;
931  loadParam("allied_narrow_auto_mode_region_width", allied_narrow_auto_mode_region_width, 2464);
932  printDefaultError(CHANGE_ALLIED_CAMERA_AUTO_MODE_REGION(m_devices[0], *m_allied_narrow_sensor, allied_narrow_auto_mode_region_height, allied_narrow_auto_mode_region_width), "allied_narrow_auto_mode_region_width");
933  int allied_narrow_intensity_controller_region;
934  loadParam("allied_narrow_intensity_controller_region", allied_narrow_intensity_controller_region, 0);
935  printDefaultError(CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_REGION(m_devices[0], *m_allied_narrow_sensor, allied_narrow_intensity_controller_region), "allied_narrow_intensity_controller_region");
936  double allied_narrow_intensity_controller_target;
937  loadParam("allied_narrow_intensity_controller_target", allied_narrow_intensity_controller_target, 50.);
938  printDefaultError(CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_TARGET(m_devices[0], *m_allied_narrow_sensor, allied_narrow_intensity_controller_target), "allied_narrow_intensity_controller_target");
939  int allied_narrow_max_driver_buffers_count;
940  loadParam("allied_narrow_max_driver_buffers_count", allied_narrow_max_driver_buffers_count, 64);
941  printDefaultError(CHANGE_ALLIED_CAMERA_MAX_DRIVER_BUFFERS_COUNT(m_devices[0], *m_allied_narrow_sensor, allied_narrow_max_driver_buffers_count), "allied_narrow_max_driver_buffers_count");
942  int allied_narrow_streaming_protocol;
943  loadParam("allied_narrow_streaming_protocol", allied_narrow_streaming_protocol, 0);
944  if (allied_narrow_streaming_protocol == 1)
945  {
946  m_allied_narrow_sensor->protocol = protocol_gstreamer;
947  printDefaultError(CHANGE_STREAMING_PROTOCOL(m_devices[0], m_allied_narrow_sensor), "allied_narrow_streaming_protocol");
948  }
949  std::string allied_narrow_rtsp_pipeline;
950  loadParam("allied_narrow_rtsp_pipeline", allied_narrow_rtsp_pipeline, std::string(""));
951  if (allied_narrow_rtsp_pipeline != "")
952  {
953  char *pipeline = &allied_narrow_rtsp_pipeline[0];
954  printDefaultError(CHANGE_RTSP_PIPELINE(m_devices[0], *m_allied_narrow_sensor, pipeline), "allied_narrow_rtsp_pipeline");
955  }
956  }
957 
958  // Service callbacks
959  bool L3Cam::libL3camStatus(l3cam_ros::LibL3camStatus::Request &req, l3cam_ros::LibL3camStatus::Response &res)
960  {
961  ROS_BMG_UNUSED(req);
962  res.status = (int)m_status;
963  return true;
964  }
965 
966  bool L3Cam::getVersion(l3cam_ros::GetVersion::Request &req, l3cam_ros::GetVersion::Response &res)
967  {
968  ROS_BMG_UNUSED(req);
969  res.version = GET_VERSION();
970  return true;
971  }
972 
973  bool L3Cam::initialize(l3cam_ros::Initialize::Request &req, l3cam_ros::Initialize::Response &res)
974  {
975  ROS_BMG_UNUSED(res);
976  res.error = INITIALIZE(&req.local_address[0], &req.device_address[0]);
977  return true;
978  }
979 
980  bool L3Cam::terminate(l3cam_ros::Terminate::Request &req, l3cam_ros::Terminate::Response &res)
981  {
982  ROS_BMG_UNUSED(req);
983  res.error = STOP_STREAM(m_devices[0]);
984  if (!res.error)
985  {
987  res.error = STOP_DEVICE(m_devices[0]);
988  }
989  if (!res.error)
990  {
992  res.error = TERMINATE(m_devices[0]);
993  if (!res.error)
994  {
996  disconnectAll(0);
997  m_shutdown_requested = true;
998  }
999  }
1000  return true;
1001  }
1002 
1003  bool L3Cam::findDevices(l3cam_ros::FindDevices::Request &req, l3cam_ros::FindDevices::Response &res)
1004  {
1005  ROS_BMG_UNUSED(req);
1006  res.error = FIND_DEVICES(&m_devices[0], &res.num_devices);
1007  return true;
1008  }
1009 
1010  bool L3Cam::getLocalServerAddress(l3cam_ros::GetLocalServerAddress::Request &req, l3cam_ros::GetLocalServerAddress::Response &res)
1011  {
1012  ROS_BMG_UNUSED(req);
1013  res.local_ip_address = GET_LOCAL_SERVER_ADDRESS(m_devices[0]);
1014  return true;
1015  }
1016 
1017  bool L3Cam::getDeviceInfo(l3cam_ros::GetDeviceInfo::Request &req, l3cam_ros::GetDeviceInfo::Response &res)
1018  {
1019  ROS_BMG_UNUSED(req);
1020  res.ip_address = std::string(m_devices[0].ip_address);
1021  res.model = m_devices[0].model;
1022  res.serial_number = std::string(m_devices[0].serial_number);
1023  res.app_version = std::string(m_devices[0].app_version);
1024  return true;
1025  }
1026 
1027  bool L3Cam::getDeviceStatus(l3cam_ros::GetDeviceStatus::Request &req, l3cam_ros::GetDeviceStatus::Response &res)
1028  {
1029  ROS_BMG_UNUSED(req);
1030  res.error = GET_DEVICE_STATUS(m_devices[0], &res.system_status);
1031  return true;
1032  }
1033 
1034  bool L3Cam::getSensorsAvailable(l3cam_ros::GetSensorsAvailable::Request &req, l3cam_ros::GetSensorsAvailable::Response &res)
1035  {
1036  ROS_BMG_UNUSED(req);
1037  res.error = GET_SENSORS_AVAILABLE(m_devices[0], m_av_sensors, &res.num_sensors);
1038  res.sensors.resize(res.num_sensors);
1039  for (int i = 0; i < res.num_sensors; ++i)
1040  {
1041  res.sensors[i].protocol = m_av_sensors[i].protocol;
1042  res.sensors[i].sensor_type = m_av_sensors[i].sensor_type;
1043  res.sensors[i].sensor_status = m_av_sensors[i].sensor_status;
1044  res.sensors[i].image_type = m_av_sensors[i].image_type;
1045  res.sensors[i].perception_enabled = m_av_sensors[i].perception_enabled;
1046  res.sensors[i].sensor_available = m_av_sensors[i].sensor_available;
1047  }
1048  return true;
1049  }
1050 
1051  bool L3Cam::changeStreamingProtocol(l3cam_ros::ChangeStreamingProtocol::Request &req, l3cam_ros::ChangeStreamingProtocol::Response &res)
1052  {
1053  STOP_STREAM(m_devices[0]);
1055 
1056  streamingProtocols protocol;
1057  switch (req.protocol)
1058  {
1059  case 0:
1060  protocol = protocol_raw_udp;
1061  break;
1062  case 1:
1063  protocol = protocol_gstreamer;
1064  break;
1065  default:
1066  protocol = protocol_raw_udp;
1067  break;
1068  }
1069 
1070  switch (req.sensor_type)
1071  {
1072  case (int)sensorTypes::sensor_lidar:
1073  m_lidar_sensor->protocol = protocol;
1074  res.error = CHANGE_STREAMING_PROTOCOL(m_devices[0], m_lidar_sensor);
1075  break;
1076  case (int)sensorTypes::sensor_pol:
1077  m_polarimetric_sensor->protocol = protocol;
1078  res.error = CHANGE_STREAMING_PROTOCOL(m_devices[0], m_polarimetric_sensor);
1079  break;
1080  case (int)sensorTypes::sensor_econ_rgb:
1081  m_rgb_sensor->protocol = protocol;
1082  res.error = CHANGE_STREAMING_PROTOCOL(m_devices[0], m_rgb_sensor);
1083  break;
1084  case (int)sensorTypes::sensor_thermal:
1085  m_thermal_sensor->protocol = protocol;
1086  res.error = CHANGE_STREAMING_PROTOCOL(m_devices[0], m_thermal_sensor);
1087  break;
1088  case (int)sensorTypes::sensor_allied_wide:
1089  m_allied_wide_sensor->protocol = protocol;
1090  res.error = CHANGE_STREAMING_PROTOCOL(m_devices[0], m_allied_wide_sensor);
1091  break;
1092  case (int)sensorTypes::sensor_allied_narrow:
1093  m_allied_narrow_sensor->protocol = protocol;
1094  res.error = CHANGE_STREAMING_PROTOCOL(m_devices[0], m_allied_narrow_sensor);
1095  break;
1096  case (int)sensorTypes::sensor_econ_wide:
1097  m_econ_wide_sensor->protocol = protocol;
1098  res.error = CHANGE_STREAMING_PROTOCOL(m_devices[0], m_econ_wide_sensor);
1099  break;
1100  }
1101 
1102  START_STREAM(m_devices[0]);
1104 
1105  return true;
1106  }
1107 
1108  bool L3Cam::getRtspPipeline(l3cam_ros::GetRtspPipeline::Request &req, l3cam_ros::GetRtspPipeline::Response &res)
1109  {
1110  char *pipeline = NULL;
1111  switch (req.sensor_type)
1112  {
1113  case (int)sensorTypes::sensor_lidar:
1114  res.error = GET_RTSP_PIPELINE(m_devices[0], *m_lidar_sensor, &pipeline);
1115  res.pipeline = std::string(pipeline);
1116  break;
1117  case (int)sensorTypes::sensor_pol:
1118  res.error = GET_RTSP_PIPELINE(m_devices[0], *m_polarimetric_sensor, &pipeline);
1119  res.pipeline = std::string(pipeline);
1120  break;
1121  case (int)sensorTypes::sensor_econ_wide:
1122  res.error = GET_RTSP_PIPELINE(m_devices[0], *m_econ_wide_sensor, &pipeline);
1123  res.pipeline = std::string(pipeline);
1124  break;
1125  case (int)sensorTypes::sensor_thermal:
1126  res.error = GET_RTSP_PIPELINE(m_devices[0], *m_thermal_sensor, &pipeline);
1127  res.pipeline = std::string(pipeline);
1128  break;
1129  case (int)sensorTypes::sensor_allied_wide:
1130  res.error = GET_RTSP_PIPELINE(m_devices[0], *m_allied_wide_sensor, &pipeline);
1131  res.pipeline = std::string(pipeline);
1132  break;
1133  case (int)sensorTypes::sensor_allied_narrow:
1134  res.error = GET_RTSP_PIPELINE(m_devices[0], *m_allied_narrow_sensor, &pipeline);
1135  res.pipeline = std::string(pipeline);
1136  break;
1137  case (int)sensorTypes::sensor_econ_rgb:
1138  res.error = GET_RTSP_PIPELINE(m_devices[0], *m_rgb_sensor, &pipeline);
1139  res.pipeline = std::string(pipeline);
1140  break;
1141  }
1142 
1143  return true;
1144  }
1145 
1146  bool L3Cam::getNetworkConfiguration(l3cam_ros::GetNetworkConfiguration::Request &req, l3cam_ros::GetNetworkConfiguration::Response &res)
1147  {
1148  ROS_BMG_UNUSED(req);
1149  char *ip_address = NULL;
1150  char *netmask = NULL;
1151  char *gateway = NULL;
1152  res.error = GET_NETWORK_CONFIGURATION(m_devices[0], &ip_address, &netmask, &gateway);
1153  res.ip_address = std::string(ip_address);
1154  res.netmask = std::string(netmask);
1155  res.gateway = std::string(gateway);
1156  return true;
1157  }
1158 
1159  bool L3Cam::changeNetworkConfiguration(l3cam_ros::ChangeNetworkConfiguration::Request &req, l3cam_ros::ChangeNetworkConfiguration::Response &res)
1160  {
1161  if (req.enable_dhcp)
1162  res.error = CHANGE_NETWORK_CONFIGURATION(m_devices[0], NULL, NULL, NULL, true);
1163  else
1164  {
1165  std::string ip_address = req.ip_address;
1166  std::string netmask = req.netmask;
1167  std::string gateway = req.gateway;
1168  res.error = CHANGE_NETWORK_CONFIGURATION(m_devices[0], (char *)ip_address.data(), (char *)netmask.data(), (char *)gateway.data(), false);
1169  }
1170 
1171  return true;
1172  }
1173 
1174  bool L3Cam::powerOffDevice(l3cam_ros::PowerOffDevice::Request &req, l3cam_ros::PowerOffDevice::Response &res)
1175  {
1176  ROS_BMG_UNUSED(req);
1177  POWER_OFF_DEVICE(m_devices[0]);
1178  res.error = 0;
1179  return true;
1180  }
1181 
1182  bool L3Cam::startDevice(l3cam_ros::StartDevice::Request &req, l3cam_ros::StartDevice::Response &res)
1183  {
1184  ROS_BMG_UNUSED(req);
1185  res.error = START_DEVICE(m_devices[0]);
1186  if (!res.error)
1187  {
1189  }
1190  return true;
1191  }
1192 
1193  bool L3Cam::stopDevice(l3cam_ros::StopDevice::Request &req, l3cam_ros::StopDevice::Response &res)
1194  {
1195  ROS_BMG_UNUSED(req);
1196  res.error = STOP_DEVICE(m_devices[0]);
1197  if (!res.error)
1198  {
1200  res.error = STOP_DEVICE(m_devices[0]);
1201  if (!res.error)
1202  {
1204  }
1205  }
1206  return true;
1207  }
1208 
1209  bool L3Cam::startStream(l3cam_ros::StartStream::Request &req, l3cam_ros::StartStream::Response &res)
1210  {
1211  ROS_BMG_UNUSED(req);
1212  res.error = START_STREAM(m_devices[0]);
1213  if (!res.error)
1214  {
1216  }
1217  return true;
1218  }
1219 
1220  bool L3Cam::stopStream(l3cam_ros::StopStream::Request &req, l3cam_ros::StopStream::Response &res)
1221  {
1222  ROS_BMG_UNUSED(req);
1223  res.error = STOP_STREAM(m_devices[0]);
1224  if (!res.error)
1225  {
1227  }
1228  return true;
1229  }
1230 
1231  bool L3Cam::getDeviceTemperatures(l3cam_ros::GetDeviceTemperatures::Request &req, l3cam_ros::GetDeviceTemperatures::Response &res)
1232  {
1233  ROS_BMG_UNUSED(req);
1234  int32_t *temperatures = (int32_t *)malloc(sizeof(int32_t) * 11);
1235  int error = GET_DEVICE_TEMPERATURES(m_devices[0], temperatures);
1236  res.error = error;
1237  if (error != L3CAM_OK)
1238  {
1239  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " in temperatures error: " << getErrorDescription(error));
1240  res.bcpu_temp = 0;
1241  res.mcpu_temp = 0;
1242  res.gpu_temp = 0;
1243  res.pll_temp = 0;
1244  res.board_temp = 0;
1245  res.diode_temp = 0;
1246  res.pmic_temp = 0;
1247  res.fan_temp = 0;
1248  res.inter_temp = 0;
1249  res.allied_wide_temp = 0;
1250  res.allied_narrow_temp = 0;
1251  }
1252  else
1253  {
1254  res.bcpu_temp = temperatures[0] / 1000.0;
1255  res.mcpu_temp = temperatures[1] / 1000.0;
1256  res.gpu_temp = temperatures[2] / 1000.0;
1257  res.pll_temp = temperatures[3] / 1000.0;
1258  res.board_temp = temperatures[4] / 1000.0;
1259  res.diode_temp = temperatures[5] / 1000.0;
1260  res.pmic_temp = temperatures[6] / 1000.0;
1261  res.fan_temp = temperatures[7] / 1000.0;
1262  res.inter_temp = temperatures[8] / 1000.0;
1263  res.allied_wide_temp = temperatures[9] / 1000.0;
1264  res.allied_narrow_temp = temperatures[10] / 1000.0;
1265  }
1266  free(temperatures);
1267 
1268  return true;
1269  }
1270 
1271  // LiDAR
1272  bool L3Cam::changePointcloudColor(l3cam_ros::ChangePointcloudColor::Request &req, l3cam_ros::ChangePointcloudColor::Response &res)
1273  {
1274  res.error = CHANGE_POINT_CLOUD_COLOR(m_devices[0], req.visualization_color);
1275  return true;
1276  }
1277 
1278  bool L3Cam::changePointcloudColorRange(l3cam_ros::ChangePointcloudColorRange::Request &req, l3cam_ros::ChangePointcloudColorRange::Response &res)
1279  {
1280  res.error = CHANGE_POINT_CLOUD_COLOR_RANGE(m_devices[0], req.min_value, req.max_value);
1281  return true;
1282  }
1283 
1284  bool L3Cam::changeDistanceRange(l3cam_ros::ChangeDistanceRange::Request &req, l3cam_ros::ChangeDistanceRange::Response &res)
1285  {
1286  res.error = CHANGE_DISTANCE_RANGE(m_devices[0], req.min_value, req.max_value);
1287  return true;
1288  }
1289 
1290  bool L3Cam::setBiasShortRange(l3cam_ros::SetBiasShortRange::Request &req, l3cam_ros::SetBiasShortRange::Response &res)
1291  {
1292  res.error = SET_BIAS_SHORT_RANGE(m_devices[0], req.enabled);
1293  return true;
1294  }
1295 
1296  bool L3Cam::enableAutoBias(l3cam_ros::EnableAutoBias::Request &req, l3cam_ros::EnableAutoBias::Response &res)
1297  {
1298  res.error = ENABLE_AUTO_BIAS(m_devices[0], req.enabled);
1299  return true;
1300  }
1301 
1302  bool L3Cam::changeBiasValue(l3cam_ros::ChangeBiasValue::Request &req, l3cam_ros::ChangeBiasValue::Response &res)
1303  {
1304  res.error = CHANGE_BIAS_VALUE(m_devices[0], req.index, req.bias);
1305  return true;
1306  }
1307 
1308  bool L3Cam::changeAutobiasValue(l3cam_ros::ChangeAutobiasValue::Request &req, l3cam_ros::ChangeAutobiasValue::Response &res)
1309  {
1310  res.error = CHANGE_AUTOBIAS_VALUE(m_devices[0], req.index, req.autobias);
1311  return true;
1312  }
1313 
1314  bool L3Cam::getAutobiasValue(l3cam_ros::GetAutobiasValue::Request &req, l3cam_ros::GetAutobiasValue::Response &res)
1315  {
1316  uint8_t *gain;
1317  res.error = GET_AUTOBIAS_VALUE(m_devices[0], req.index, gain);
1318  res.gain = *gain;
1319  return true;
1320  }
1321 
1322  // Polarimetric
1323  bool L3Cam::setPolarimetricCameraDefaultSettings(l3cam_ros::SetPolarimetricCameraDefaultSettings::Request &req, l3cam_ros::SetPolarimetricCameraDefaultSettings::Response &res)
1324  {
1325  ROS_BMG_UNUSED(req);
1326  res.error = SET_POLARIMETRIC_CAMERA_DEFAULT_SETTINGS(m_devices[0]);
1327  return true;
1328  }
1329 
1330  bool L3Cam::changePolarimetricCameraBrightness(l3cam_ros::ChangePolarimetricCameraBrightness::Request &req, l3cam_ros::ChangePolarimetricCameraBrightness::Response &res)
1331  {
1332  res.error = CHANGE_POLARIMETRIC_CAMERA_BRIGHTNESS(m_devices[0], req.brightness);
1333  return true;
1334  }
1335 
1336  bool L3Cam::changePolarimetricCameraBlackLevel(l3cam_ros::ChangePolarimetricCameraBlackLevel::Request &req, l3cam_ros::ChangePolarimetricCameraBlackLevel::Response &res)
1337  {
1338  res.error = CHANGE_POLARIMETRIC_CAMERA_BLACK_LEVEL(m_devices[0], req.black_level);
1339  return true;
1340  }
1341 
1342  bool L3Cam::enablePolarimetricCameraAutoGain(l3cam_ros::EnablePolarimetricCameraAutoGain::Request &req, l3cam_ros::EnablePolarimetricCameraAutoGain::Response &res)
1343  {
1344  res.error = ENABLE_POLARIMETRIC_CAMERA_AUTO_GAIN(m_devices[0], req.enabled);
1345  return true;
1346  }
1347 
1348  bool L3Cam::changePolarimetricCameraAutoGainRange(l3cam_ros::ChangePolarimetricCameraAutoGainRange::Request &req, l3cam_ros::ChangePolarimetricCameraAutoGainRange::Response &res)
1349  {
1350  res.error = CHANGE_POLARIMETRIC_CAMERA_AUTO_GAIN_RANGE(m_devices[0], req.min_gain, req.max_gain);
1351  return true;
1352  }
1353 
1354  bool L3Cam::changePolarimetricCameraGain(l3cam_ros::ChangePolarimetricCameraGain::Request &req, l3cam_ros::ChangePolarimetricCameraGain::Response &res)
1355  {
1356  res.error = CHANGE_POLARIMETRIC_CAMERA_GAIN(m_devices[0], req.gain);
1357  return true;
1358  }
1359 
1360  bool L3Cam::enablePolarimetricCameraAutoExposureTime(l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Request &req, l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Response &res)
1361  {
1362  res.error = ENABLE_POLARIMETRIC_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], req.enabled);
1363  return true;
1364  }
1365 
1366  bool L3Cam::changePolarimetricCameraAutoExposureTimeRange(l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Request &req, l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Response &res)
1367  {
1368  res.error = CHANGE_POLARIMETRIC_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], req.min_exposure, req.max_exposure);
1369  return true;
1370  }
1371 
1372  bool L3Cam::changePolarimetricCameraExposureTime(l3cam_ros::ChangePolarimetricCameraExposureTime::Request &req, l3cam_ros::ChangePolarimetricCameraExposureTime::Response &res)
1373  {
1374  res.error = CHANGE_POLARIMETRIC_CAMERA_EXPOSURE_TIME(m_devices[0], req.exposure_time);
1375  return true;
1376  }
1377 
1378  // RGB
1379  bool L3Cam::setRgbCameraDefaultSettings(l3cam_ros::SetRgbCameraDefaultSettings::Request &req, l3cam_ros::SetRgbCameraDefaultSettings::Response &res)
1380  {
1381  ROS_BMG_UNUSED(req);
1382  res.error = SET_RGB_CAMERA_DEFAULT_SETTINGS(m_devices[0]);
1383  return true;
1384  }
1385 
1386  bool L3Cam::changeRgbCameraBrightness(l3cam_ros::ChangeRgbCameraBrightness::Request &req, l3cam_ros::ChangeRgbCameraBrightness::Response &res)
1387  {
1388  res.error = CHANGE_RGB_CAMERA_BRIGHTNESS(m_devices[0], req.brightness);
1389  return true;
1390  }
1391 
1392  bool L3Cam::changeRgbCameraContrast(l3cam_ros::ChangeRgbCameraContrast::Request &req, l3cam_ros::ChangeRgbCameraContrast::Response &res)
1393  {
1394  res.error = CHANGE_RGB_CAMERA_CONTRAST(m_devices[0], req.contrast);
1395  return true;
1396  }
1397 
1398  bool L3Cam::changeRgbCameraSaturation(l3cam_ros::ChangeRgbCameraSaturation::Request &req, l3cam_ros::ChangeRgbCameraSaturation::Response &res)
1399  {
1400  res.error = CHANGE_RGB_CAMERA_SATURATION(m_devices[0], req.saturation);
1401  return true;
1402  }
1403 
1404  bool L3Cam::changeRgbCameraSharpness(l3cam_ros::ChangeRgbCameraSharpness::Request &req, l3cam_ros::ChangeRgbCameraSharpness::Response &res)
1405  {
1406  res.error = CHANGE_RGB_CAMERA_SHARPNESS(m_devices[0], req.sharpness);
1407  return true;
1408  }
1409 
1410  bool L3Cam::changeRgbCameraGamma(l3cam_ros::ChangeRgbCameraGamma::Request &req, l3cam_ros::ChangeRgbCameraGamma::Response &res)
1411  {
1412  res.error = CHANGE_RGB_CAMERA_GAMMA(m_devices[0], req.gamma);
1413  return true;
1414  }
1415 
1416  bool L3Cam::changeRgbCameraGain(l3cam_ros::ChangeRgbCameraGain::Request &req, l3cam_ros::ChangeRgbCameraGain::Response &res)
1417  {
1418  res.error = CHANGE_RGB_CAMERA_GAIN(m_devices[0], req.gain);
1419  return true;
1420  }
1421 
1422  bool L3Cam::enableRgbCameraAutoWhiteBalance(l3cam_ros::EnableRgbCameraAutoWhiteBalance::Request &req, l3cam_ros::EnableRgbCameraAutoWhiteBalance::Response &res)
1423  {
1424  res.error = ENABLE_RGB_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], req.enabled);
1425  return true;
1426  }
1427 
1428  bool L3Cam::changeRgbCameraWhiteBalance(l3cam_ros::ChangeRgbCameraWhiteBalance::Request &req, l3cam_ros::ChangeRgbCameraWhiteBalance::Response &res)
1429  {
1430  res.error = CHANGE_RGB_CAMERA_WHITE_BALANCE(m_devices[0], req.white_balance);
1431  return true;
1432  }
1433 
1434  bool L3Cam::enableRgbCameraAutoExposureTime(l3cam_ros::EnableRgbCameraAutoExposureTime::Request &req, l3cam_ros::EnableRgbCameraAutoExposureTime::Response &res)
1435  {
1436  res.error = ENABLE_RGB_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], req.enabled);
1437  return true;
1438  }
1439 
1440  bool L3Cam::changeRgbCameraExposureTime(l3cam_ros::ChangeRgbCameraExposureTime::Request &req, l3cam_ros::ChangeRgbCameraExposureTime::Response &res)
1441  {
1442  res.error = CHANGE_RGB_CAMERA_EXPOSURE_TIME(m_devices[0], req.exposure_time);
1443  return true;
1444  }
1445 
1446  // Thermal
1447  bool L3Cam::changeThermalCameraColormap(l3cam_ros::ChangeThermalCameraColormap::Request &req, l3cam_ros::ChangeThermalCameraColormap::Response &res)
1448  {
1449  res.error = CHANGE_THERMAL_CAMERA_COLORMAP(m_devices[0], (newThermalTypes)req.colormap);
1450  return true;
1451  }
1452 
1453  bool L3Cam::enableThermalCameraTemperatureFilter(l3cam_ros::EnableThermalCameraTemperatureFilter::Request &req, l3cam_ros::EnableThermalCameraTemperatureFilter::Response &res)
1454  {
1455  res.error = ENABLE_THERMAL_CAMERA_TEMPERATURE_FILTER(m_devices[0], req.enabled);
1456  return true;
1457  }
1458 
1459  bool L3Cam::changeThermalCameraTemperatureFilter(l3cam_ros::ChangeThermalCameraTemperatureFilter::Request &req, l3cam_ros::ChangeThermalCameraTemperatureFilter::Response &res)
1460  {
1461  res.error = CHANGE_THERMAL_CAMERA_TEMPERATURE_FILTER(m_devices[0], req.min_temperature, req.max_temperature);
1462  return true;
1463  }
1464 
1465  bool L3Cam::changeThermalCameraProcessingPipeline(l3cam_ros::ChangeThermalCameraProcessingPipeline::Request &req, l3cam_ros::ChangeThermalCameraProcessingPipeline::Response &res)
1466  {
1467  res.error = CHANGE_THERMAL_CAMERA_PROCESSING_PIPELINE(m_devices[0], req.pipeline);
1468  return true;
1469  }
1470 
1471  bool L3Cam::enableThermalCameraTemperatureDataUdp(l3cam_ros::EnableThermalCameraTemperatureDataUdp::Request &req, l3cam_ros::EnableThermalCameraTemperatureDataUdp::Response &res)
1472  {
1473  res.error = ENABLE_THERMAL_CAMERA_TEMPERATURE_DATA_UDP(m_devices[0], req.enabled);
1474  return true;
1475  }
1476 
1477  // Allied
1478  bool L3Cam::changeAlliedCameraExposureTime(l3cam_ros::ChangeAlliedCameraExposureTime::Request &req, l3cam_ros::ChangeAlliedCameraExposureTime::Response &res)
1479  {
1480  switch (req.allied_type)
1481  {
1482  case alliedCamerasIds::wide_camera:
1483  res.error = CHANGE_ALLIED_CAMERA_EXPOSURE_TIME_US(m_devices[0], *m_allied_wide_sensor, req.exposure_time);
1484  break;
1485  case alliedCamerasIds::narrow_camera:
1486  res.error = CHANGE_ALLIED_CAMERA_EXPOSURE_TIME_US(m_devices[0], *m_allied_narrow_sensor, req.exposure_time);
1487  break;
1488  default:
1489  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1490  }
1491  return true;
1492  }
1493 
1494  bool L3Cam::enableAlliedCameraAutoExposureTime(l3cam_ros::EnableAlliedCameraAutoExposureTime::Request &req, l3cam_ros::EnableAlliedCameraAutoExposureTime::Response &res)
1495  {
1496  switch (req.allied_type)
1497  {
1498  case alliedCamerasIds::wide_camera:
1499  res.error = ENABLE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], *m_allied_wide_sensor, req.enabled);
1500  break;
1501  case alliedCamerasIds::narrow_camera:
1502  res.error = ENABLE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], *m_allied_narrow_sensor, req.enabled);
1503  break;
1504  default:
1505  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1506  }
1507  return true;
1508  }
1509 
1510  bool L3Cam::changeAlliedCameraAutoExposureTimeRange(l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Request &req, l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Response &res)
1511  {
1512  switch (req.allied_type)
1513  {
1514  case alliedCamerasIds::wide_camera:
1515  res.error = CHANGE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], *m_allied_wide_sensor, req.auto_exposure_time_range_min, req.auto_exposure_time_range_max);
1516  break;
1517  case alliedCamerasIds::narrow_camera:
1518  res.error = CHANGE_ALLIED_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], *m_allied_narrow_sensor, req.auto_exposure_time_range_min, req.auto_exposure_time_range_max);
1519  break;
1520  default:
1521  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1522  }
1523  return true;
1524  }
1525 
1526  bool L3Cam::changeAlliedCameraGain(l3cam_ros::ChangeAlliedCameraGain::Request &req, l3cam_ros::ChangeAlliedCameraGain::Response &res)
1527  {
1528  switch (req.allied_type)
1529  {
1530  case alliedCamerasIds::wide_camera:
1531  res.error = CHANGE_ALLIED_CAMERA_GAIN(m_devices[0], *m_allied_wide_sensor, req.gain);
1532  break;
1533  case alliedCamerasIds::narrow_camera:
1534  res.error = CHANGE_ALLIED_CAMERA_GAIN(m_devices[0], *m_allied_narrow_sensor, req.gain);
1535  break;
1536  default:
1537  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1538  }
1539  return true;
1540  }
1541 
1542  bool L3Cam::enableAlliedCameraAutoGain(l3cam_ros::EnableAlliedCameraAutoGain::Request &req, l3cam_ros::EnableAlliedCameraAutoGain::Response &res)
1543  {
1544  switch (req.allied_type)
1545  {
1546  case alliedCamerasIds::wide_camera:
1547  res.error = ENABLE_ALLIED_CAMERA_AUTO_GAIN(m_devices[0], *m_allied_wide_sensor, req.enabled);
1548  break;
1549  case alliedCamerasIds::narrow_camera:
1550  res.error = ENABLE_ALLIED_CAMERA_AUTO_GAIN(m_devices[0], *m_allied_narrow_sensor, req.enabled);
1551  break;
1552  default:
1553  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1554  }
1555  return true;
1556  }
1557 
1558  bool L3Cam::changeAlliedCameraAutoGainRange(l3cam_ros::ChangeAlliedCameraAutoGainRange::Request &req, l3cam_ros::ChangeAlliedCameraAutoGainRange::Response &res)
1559  {
1560  switch (req.allied_type)
1561  {
1562  case alliedCamerasIds::wide_camera:
1563  res.error = CHANGE_ALLIED_CAMERA_AUTO_GAIN_RANGE(m_devices[0], *m_allied_wide_sensor, (float)req.auto_gain_range_min, (float)req.auto_gain_range_max);
1564  break;
1565  case alliedCamerasIds::narrow_camera:
1566  res.error = CHANGE_ALLIED_CAMERA_AUTO_GAIN_RANGE(m_devices[0], *m_allied_narrow_sensor, (float)req.auto_gain_range_min, (float)req.auto_gain_range_max);
1567  break;
1568  default:
1569  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1570  }
1571  return true;
1572  }
1573 
1574  bool L3Cam::changeAlliedCameraGamma(l3cam_ros::ChangeAlliedCameraGamma::Request &req, l3cam_ros::ChangeAlliedCameraGamma::Response &res)
1575  {
1576  switch (req.allied_type)
1577  {
1578  case alliedCamerasIds::wide_camera:
1579  res.error = CHANGE_ALLIED_CAMERA_GAMMA(m_devices[0], *m_allied_wide_sensor, req.gamma);
1580  break;
1581  case alliedCamerasIds::narrow_camera:
1582  res.error = CHANGE_ALLIED_CAMERA_GAMMA(m_devices[0], *m_allied_narrow_sensor, req.gamma);
1583  break;
1584  default:
1585  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1586  }
1587  return true;
1588  }
1589 
1590  bool L3Cam::changeAlliedCameraSaturation(l3cam_ros::ChangeAlliedCameraSaturation::Request &req, l3cam_ros::ChangeAlliedCameraSaturation::Response &res)
1591  {
1592  switch (req.allied_type)
1593  {
1594  case alliedCamerasIds::wide_camera:
1595  res.error = CHANGE_ALLIED_CAMERA_SATURATION(m_devices[0], *m_allied_wide_sensor, req.saturation);
1596  break;
1597  case alliedCamerasIds::narrow_camera:
1598  res.error = CHANGE_ALLIED_CAMERA_SATURATION(m_devices[0], *m_allied_narrow_sensor, req.saturation);
1599  break;
1600  default:
1601  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1602  }
1603  return true;
1604  }
1605 
1606  bool L3Cam::changeAlliedCameraHue(l3cam_ros::ChangeAlliedCameraHue::Request &req, l3cam_ros::ChangeAlliedCameraHue::Response &res)
1607  {
1608  switch (req.allied_type)
1609  {
1610  case alliedCamerasIds::wide_camera:
1611  res.error = CHANGE_ALLIED_CAMERA_HUE(m_devices[0], *m_allied_wide_sensor, req.hue);
1612  break;
1613  case alliedCamerasIds::narrow_camera:
1614  res.error = CHANGE_ALLIED_CAMERA_HUE(m_devices[0], *m_allied_narrow_sensor, req.hue);
1615  break;
1616  default:
1617  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1618  }
1619  return true;
1620  }
1621 
1622  bool L3Cam::changeAlliedCameraIntensityAutoPrecedence(l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Request &req, l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Response &res)
1623  {
1624  switch (req.allied_type)
1625  {
1626  case alliedCamerasIds::wide_camera:
1627  res.error = CHANGE_ALLIED_CAMERA_INTENSITY_AUTO_PRECEDENCE(m_devices[0], *m_allied_wide_sensor, req.intensity_auto_precedence);
1628  break;
1629  case alliedCamerasIds::narrow_camera:
1630  res.error = CHANGE_ALLIED_CAMERA_INTENSITY_AUTO_PRECEDENCE(m_devices[0], *m_allied_narrow_sensor, req.intensity_auto_precedence);
1631  break;
1632  default:
1633  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1634  }
1635  return true;
1636  }
1637 
1638  bool L3Cam::enableAlliedCameraAutoWhiteBalance(l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Request &req, l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Response &res)
1639  {
1640  switch (req.allied_type)
1641  {
1642  case alliedCamerasIds::wide_camera:
1643  res.error = ENABLE_ALLIED_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], *m_allied_wide_sensor, req.enabled);
1644  break;
1645  case alliedCamerasIds::narrow_camera:
1646  res.error = ENABLE_ALLIED_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], *m_allied_narrow_sensor, req.enabled);
1647  break;
1648  default:
1649  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1650  }
1651  return true;
1652  }
1653 
1654  bool L3Cam::changeAlliedCameraBalanceRatioSelector(l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Request &req, l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Response &res)
1655  {
1656  switch (req.allied_type)
1657  {
1658  case alliedCamerasIds::wide_camera:
1659  res.error = CHANGE_ALLIED_CAMERA_BALANCE_RATIO_SELECTOR(m_devices[0], *m_allied_wide_sensor, req.white_balance_ratio_selector);
1660  break;
1661  case alliedCamerasIds::narrow_camera:
1662  res.error = CHANGE_ALLIED_CAMERA_BALANCE_RATIO_SELECTOR(m_devices[0], *m_allied_narrow_sensor, req.white_balance_ratio_selector);
1663  break;
1664  default:
1665  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1666  }
1667  return true;
1668  }
1669 
1670  bool L3Cam::changeAlliedCameraBalanceRatio(l3cam_ros::ChangeAlliedCameraBalanceRatio::Request &req, l3cam_ros::ChangeAlliedCameraBalanceRatio::Response &res)
1671  {
1672  switch (req.allied_type)
1673  {
1674  case alliedCamerasIds::wide_camera:
1675  res.error = CHANGE_ALLIED_CAMERA_BALANCE_RATIO(m_devices[0], *m_allied_wide_sensor, req.balance_ratio);
1676  break;
1677  case alliedCamerasIds::narrow_camera:
1678  res.error = CHANGE_ALLIED_CAMERA_BALANCE_RATIO(m_devices[0], *m_allied_narrow_sensor, req.balance_ratio);
1679  break;
1680  default:
1681  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1682  }
1683  return true;
1684  }
1685 
1686  bool L3Cam::changeAlliedCameraBalanceWhiteAutoRate(l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Request &req, l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Response &res)
1687  {
1688  switch (req.allied_type)
1689  {
1690  case alliedCamerasIds::wide_camera:
1691  res.error = CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_RATE(m_devices[0], *m_allied_wide_sensor, req.white_balance_auto_rate);
1692  break;
1693  case alliedCamerasIds::narrow_camera:
1694  res.error = CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_RATE(m_devices[0], *m_allied_narrow_sensor, req.white_balance_auto_rate);
1695  break;
1696  default:
1697  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1698  }
1699  return true;
1700  }
1701 
1702  bool L3Cam::changeAlliedCameraBalanceWhiteAutoTolerance(l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Request &req, l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Response &res)
1703  {
1704  switch (req.allied_type)
1705  {
1706  case alliedCamerasIds::wide_camera:
1707  res.error = CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_TOLERANCE(m_devices[0], *m_allied_wide_sensor, req.white_balance_auto_tolerance);
1708  break;
1709  case alliedCamerasIds::narrow_camera:
1710  res.error = CHANGE_ALLIED_CAMERA_BALANCE_WHITE_AUTO_TOLERANCE(m_devices[0], *m_allied_narrow_sensor, req.white_balance_auto_tolerance);
1711  break;
1712  default:
1713  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1714  }
1715  return true;
1716  }
1717 
1718  bool L3Cam::changeAlliedCameraIntensityControllerRegion(l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Request &req, l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Response &res)
1719  {
1720  switch (req.allied_type)
1721  {
1722  case alliedCamerasIds::wide_camera:
1723  res.error = CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_REGION(m_devices[0], *m_allied_wide_sensor, req.intensity_controller_region);
1724  break;
1725  case alliedCamerasIds::narrow_camera:
1726  res.error = CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_REGION(m_devices[0], *m_allied_narrow_sensor, req.intensity_controller_region);
1727  break;
1728  default:
1729  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1730  }
1731  return true;
1732  }
1733 
1734  bool L3Cam::changeAlliedCameraIntensityControllerTarget(l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Request &req, l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Response &res)
1735  {
1736  switch (req.allied_type)
1737  {
1738  case alliedCamerasIds::wide_camera:
1739  res.error = CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_TARGET(m_devices[0], *m_allied_wide_sensor, req.intensity_controller_target);
1740  break;
1741  case alliedCamerasIds::narrow_camera:
1742  res.error = CHANGE_ALLIED_CAMERA_INTENSITY_CONTROLLER_TARGET(m_devices[0], *m_allied_narrow_sensor, req.intensity_controller_target);
1743  break;
1744  default:
1745  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1746  }
1747  return true;
1748  }
1749 
1750  bool L3Cam::getAlliedCameraBlackLevel(l3cam_ros::GetAlliedCameraBlackLevel::Request &req, l3cam_ros::GetAlliedCameraBlackLevel::Response &res)
1751  {
1752  switch (req.allied_type)
1753  {
1754  case alliedCamerasIds::wide_camera:
1755  res.error = GET_ALLIED_CAMERA_BLACK_LEVEL(m_devices[0], *m_allied_wide_sensor, &res.black_level);
1756  break;
1757  case alliedCamerasIds::narrow_camera:
1758  res.error = GET_ALLIED_CAMERA_BLACK_LEVEL(m_devices[0], *m_allied_narrow_sensor, &res.black_level);
1759  break;
1760  default:
1761  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1762  }
1763  return true;
1764  }
1765 
1766  bool L3Cam::getAlliedCameraExposureTime(l3cam_ros::GetAlliedCameraExposureTime::Request &req, l3cam_ros::GetAlliedCameraExposureTime::Response &res)
1767  {
1768  switch (req.allied_type)
1769  {
1770  case alliedCamerasIds::wide_camera:
1771  res.error = GET_ALLIED_CAMERA_EXPOSURE_TIME_US(m_devices[0], *m_allied_wide_sensor, &res.exposure_time);
1772  break;
1773  case alliedCamerasIds::narrow_camera:
1774  res.error = GET_ALLIED_CAMERA_EXPOSURE_TIME_US(m_devices[0], *m_allied_narrow_sensor, &res.exposure_time);
1775  break;
1776  default:
1777  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1778  }
1779  return true;
1780  }
1781 
1782  bool L3Cam::getAlliedCameraAutoExposureTime(l3cam_ros::GetAlliedCameraAutoExposureTime::Request &req, l3cam_ros::GetAlliedCameraAutoExposureTime::Response &res)
1783  {
1784  bool enabled;
1785  switch (req.allied_type)
1786  {
1787  case alliedCamerasIds::wide_camera:
1788  res.error = GET_ALLIED_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], *m_allied_wide_sensor, &enabled);
1789  break;
1790  case alliedCamerasIds::narrow_camera:
1791  res.error = GET_ALLIED_CAMERA_AUTO_EXPOSURE_TIME(m_devices[0], *m_allied_narrow_sensor, &enabled);
1792  break;
1793  default:
1794  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1795  }
1796  res.enabled = enabled;
1797 
1798  return true;
1799  }
1800 
1801  bool L3Cam::getAlliedCameraAutoExposureTimeRange(l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Request &req, l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Response &res)
1802  {
1803  switch (req.allied_type)
1804  {
1805  case alliedCamerasIds::wide_camera:
1806  res.error = GET_ALLIED_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], *m_allied_wide_sensor, &res.auto_exposure_time_range_min, &res.auto_exposure_time_range_max);
1807  break;
1808  case alliedCamerasIds::narrow_camera:
1809  res.error = GET_ALLIED_CAMERA_AUTO_EXPOSURE_TIME_RANGE(m_devices[0], *m_allied_narrow_sensor, &res.auto_exposure_time_range_min, &res.auto_exposure_time_range_max);
1810  break;
1811  default:
1812  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1813  }
1814  return true;
1815  }
1816 
1817  bool L3Cam::getAlliedCameraGain(l3cam_ros::GetAlliedCameraGain::Request &req, l3cam_ros::GetAlliedCameraGain::Response &res)
1818  {
1819  switch (req.allied_type)
1820  {
1821  case alliedCamerasIds::wide_camera:
1822  res.error = GET_ALLIED_CAMERA_GAIN(m_devices[0], *m_allied_wide_sensor, &res.gain);
1823  break;
1824  case alliedCamerasIds::narrow_camera:
1825  res.error = GET_ALLIED_CAMERA_GAIN(m_devices[0], *m_allied_narrow_sensor, &res.gain);
1826  break;
1827  default:
1828  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1829  }
1830  return true;
1831  }
1832 
1833  bool L3Cam::getAlliedCameraAutoGain(l3cam_ros::GetAlliedCameraAutoGain::Request &req, l3cam_ros::GetAlliedCameraAutoGain::Response &res)
1834  {
1835  bool enabled;
1836  switch (req.allied_type)
1837  {
1838  case alliedCamerasIds::wide_camera:
1839  res.error = GET_ALLIED_CAMERA_AUTO_GAIN(m_devices[0], *m_allied_wide_sensor, &enabled);
1840  break;
1841  case alliedCamerasIds::narrow_camera:
1842  res.error = GET_ALLIED_CAMERA_AUTO_GAIN(m_devices[0], *m_allied_narrow_sensor, &enabled);
1843  break;
1844  default:
1845  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1846  }
1847  res.enabled = enabled;
1848 
1849  return true;
1850  }
1851 
1852  bool L3Cam::getAlliedCameraAutoGainRange(l3cam_ros::GetAlliedCameraAutoGainRange::Request &req, l3cam_ros::GetAlliedCameraAutoGainRange::Response &res)
1853  {
1854  switch (req.allied_type)
1855  {
1856  case alliedCamerasIds::wide_camera:
1857  res.error = GET_ALLIED_CAMERA_AUTO_GAIN_RANGE(m_devices[0], *m_allied_wide_sensor, &res.auto_gain_range_min, &res.auto_gain_range_max);
1858  break;
1859  case alliedCamerasIds::narrow_camera:
1860  res.error = GET_ALLIED_CAMERA_AUTO_GAIN_RANGE(m_devices[0], *m_allied_narrow_sensor, &res.auto_gain_range_min, &res.auto_gain_range_max);
1861  break;
1862  default:
1863  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1864  }
1865  return true;
1866  }
1867 
1868  bool L3Cam::getAlliedCameraGamma(l3cam_ros::GetAlliedCameraGamma::Request &req, l3cam_ros::GetAlliedCameraGamma::Response &res)
1869  {
1870  switch (req.allied_type)
1871  {
1872  case alliedCamerasIds::wide_camera:
1873  res.error = GET_ALLIED_CAMERA_GAMMA(m_devices[0], *m_allied_wide_sensor, &res.gamma);
1874  break;
1875  case alliedCamerasIds::narrow_camera:
1876  res.error = GET_ALLIED_CAMERA_GAMMA(m_devices[0], *m_allied_narrow_sensor, &res.gamma);
1877  break;
1878  default:
1879  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1880  }
1881  return true;
1882  }
1883 
1884  bool L3Cam::getAlliedCameraSaturation(l3cam_ros::GetAlliedCameraSaturation::Request &req, l3cam_ros::GetAlliedCameraSaturation::Response &res)
1885  {
1886  switch (req.allied_type)
1887  {
1888  case alliedCamerasIds::wide_camera:
1889  res.error = GET_ALLIED_CAMERA_SATURATION(m_devices[0], *m_allied_wide_sensor, &res.saturation);
1890  break;
1891  case alliedCamerasIds::narrow_camera:
1892  res.error = GET_ALLIED_CAMERA_SATURATION(m_devices[0], *m_allied_narrow_sensor, &res.saturation);
1893  break;
1894  default:
1895  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1896  }
1897  return true;
1898  }
1899 
1900  bool L3Cam::getAlliedCameraSharpness(l3cam_ros::GetAlliedCameraSharpness::Request &req, l3cam_ros::GetAlliedCameraSharpness::Response &res)
1901  {
1902  switch (req.allied_type)
1903  {
1904  case alliedCamerasIds::wide_camera:
1905  res.error = GET_ALLIED_CAMERA_SHARPNESS(m_devices[0], *m_allied_wide_sensor, &res.sharpness);
1906  break;
1907  case alliedCamerasIds::narrow_camera:
1908  res.error = GET_ALLIED_CAMERA_SHARPNESS(m_devices[0], *m_allied_narrow_sensor, &res.sharpness);
1909  break;
1910  default:
1911  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1912  }
1913  return true;
1914  }
1915 
1916  bool L3Cam::getAlliedCameraHue(l3cam_ros::GetAlliedCameraHue::Request &req, l3cam_ros::GetAlliedCameraHue::Response &res)
1917  {
1918  switch (req.allied_type)
1919  {
1920  case alliedCamerasIds::wide_camera:
1921  res.error = GET_ALLIED_CAMERA_HUE(m_devices[0], *m_allied_wide_sensor, &res.hue);
1922  break;
1923  case alliedCamerasIds::narrow_camera:
1924  res.error = GET_ALLIED_CAMERA_HUE(m_devices[0], *m_allied_narrow_sensor, &res.hue);
1925  break;
1926  default:
1927  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1928  }
1929  return true;
1930  }
1931 
1932  bool L3Cam::getAlliedCameraIntensityAutoPrecedence(l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Request &req, l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Response &res)
1933  {
1934  switch (req.allied_type)
1935  {
1936  case alliedCamerasIds::wide_camera:
1937  res.error = GET_ALLIED_CAMERA_INTENSITY_AUTO_PRECEDENCE(m_devices[0], *m_allied_wide_sensor, &res.intensity_auto_precedence);
1938  break;
1939  case alliedCamerasIds::narrow_camera:
1940  res.error = GET_ALLIED_CAMERA_INTENSITY_AUTO_PRECEDENCE(m_devices[0], *m_allied_narrow_sensor, &res.intensity_auto_precedence);
1941  break;
1942  default:
1943  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1944  }
1945  return true;
1946  }
1947 
1948  bool L3Cam::getAlliedCameraAutoWhiteBalance(l3cam_ros::GetAlliedCameraAutoWhiteBalance::Request &req, l3cam_ros::GetAlliedCameraAutoWhiteBalance::Response &res)
1949  {
1950  bool enabled;
1951  switch (req.allied_type)
1952  {
1953  case alliedCamerasIds::wide_camera:
1954  res.error = GET_ALLIED_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], *m_allied_wide_sensor, &enabled);
1955  break;
1956  case alliedCamerasIds::narrow_camera:
1957  res.error = GET_ALLIED_CAMERA_AUTO_WHITE_BALANCE(m_devices[0], *m_allied_narrow_sensor, &enabled);
1958  break;
1959  default:
1960  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1961  }
1962  res.enabled = enabled;
1963 
1964  return true;
1965  }
1966 
1967  bool L3Cam::getAlliedCameraBalanceRatioSelector(l3cam_ros::GetAlliedCameraBalanceRatioSelector::Request &req, l3cam_ros::GetAlliedCameraBalanceRatioSelector::Response &res)
1968  {
1969  switch (req.allied_type)
1970  {
1971  case alliedCamerasIds::wide_camera:
1972  res.error = GET_ALLIED_CAMERA_BALANCE_RATIO_SELECTOR(m_devices[0], *m_allied_wide_sensor, &res.white_balance_ratio_selector);
1973  break;
1974  case alliedCamerasIds::narrow_camera:
1975  res.error = GET_ALLIED_CAMERA_BALANCE_RATIO_SELECTOR(m_devices[0], *m_allied_narrow_sensor, &res.white_balance_ratio_selector);
1976  break;
1977  default:
1978  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1979  }
1980  return true;
1981  }
1982 
1983  bool L3Cam::getAlliedCameraBalanceRatio(l3cam_ros::GetAlliedCameraBalanceRatio::Request &req, l3cam_ros::GetAlliedCameraBalanceRatio::Response &res)
1984  {
1985  switch (req.allied_type)
1986  {
1987  case alliedCamerasIds::wide_camera:
1988  res.error = GET_ALLIED_CAMERA_BALANCE_RATIO(m_devices[0], *m_allied_wide_sensor, &res.balance_ratio);
1989  break;
1990  case alliedCamerasIds::narrow_camera:
1991  res.error = GET_ALLIED_CAMERA_BALANCE_RATIO(m_devices[0], *m_allied_narrow_sensor, &res.balance_ratio);
1992  break;
1993  default:
1994  res.error = L3CAM_VALUE_OUT_OF_RANGE;
1995  }
1996  return true;
1997  }
1998 
1999  bool L3Cam::getAlliedCameraBalanceWhiteAutoRate(l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Request &req, l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Response &res)
2000  {
2001  switch (req.allied_type)
2002  {
2003  case alliedCamerasIds::wide_camera:
2004  res.error = GET_ALLIED_CAMERA_BALANCE_WHITE_AUTO_RATE(m_devices[0], *m_allied_wide_sensor, &res.white_balance_auto_rate);
2005  break;
2006  case alliedCamerasIds::narrow_camera:
2007  res.error = GET_ALLIED_CAMERA_BALANCE_WHITE_AUTO_RATE(m_devices[0], *m_allied_narrow_sensor, &res.white_balance_auto_rate);
2008  break;
2009  default:
2010  res.error = L3CAM_VALUE_OUT_OF_RANGE;
2011  }
2012  return true;
2013  }
2014 
2015  bool L3Cam::getAlliedCameraBalanceWhiteAutoTolerance(l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Request &req, l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Response &res)
2016  {
2017  switch (req.allied_type)
2018  {
2019  case alliedCamerasIds::wide_camera:
2020  res.error = GET_ALLIED_CAMERA_BALANCE_WHITE_AUTO_TOLERANCE(m_devices[0], *m_allied_wide_sensor, &res.white_balance_auto_tolerance);
2021  break;
2022  case alliedCamerasIds::narrow_camera:
2023  res.error = GET_ALLIED_CAMERA_BALANCE_WHITE_AUTO_TOLERANCE(m_devices[0], *m_allied_narrow_sensor, &res.white_balance_auto_tolerance);
2024  break;
2025  default:
2026  res.error = L3CAM_VALUE_OUT_OF_RANGE;
2027  }
2028  return true;
2029  }
2030 
2031  bool L3Cam::getAlliedCameraAutoModeRegion(l3cam_ros::GetAlliedCameraAutoModeRegion::Request &req, l3cam_ros::GetAlliedCameraAutoModeRegion::Response &res)
2032  {
2033  switch (req.allied_type)
2034  {
2035  case alliedCamerasIds::wide_camera:
2036  res.error = GET_ALLIED_CAMERA_AUTO_MODE_REGION(m_devices[0], *m_allied_wide_sensor, &res.width, &res.height);
2037  break;
2038  case alliedCamerasIds::narrow_camera:
2039  res.error = GET_ALLIED_CAMERA_AUTO_MODE_REGION(m_devices[0], *m_allied_narrow_sensor, &res.width, &res.height);
2040  break;
2041  default:
2042  res.error = L3CAM_VALUE_OUT_OF_RANGE;
2043  }
2044  return true;
2045  }
2046 
2047  bool L3Cam::getAlliedCameraIntensityControllerRegion(l3cam_ros::GetAlliedCameraIntensityControllerRegion::Request &req, l3cam_ros::GetAlliedCameraIntensityControllerRegion::Response &res)
2048  {
2049  switch (req.allied_type)
2050  {
2051  case alliedCamerasIds::wide_camera:
2052  res.error = GET_ALLIED_CAMERA_INTENSITY_CONTROLLER_REGION(m_devices[0], *m_allied_wide_sensor, &res.intensity_controller_region);
2053  break;
2054  case alliedCamerasIds::narrow_camera:
2055  res.error = GET_ALLIED_CAMERA_INTENSITY_CONTROLLER_REGION(m_devices[0], *m_allied_narrow_sensor, &res.intensity_controller_region);
2056  break;
2057  default:
2058  res.error = L3CAM_VALUE_OUT_OF_RANGE;
2059  }
2060  return true;
2061  }
2062 
2063  bool L3Cam::getAlliedCameraIntensityControllerTarget(l3cam_ros::GetAlliedCameraIntensityControllerTarget::Request &req, l3cam_ros::GetAlliedCameraIntensityControllerTarget::Response &res)
2064  {
2065  switch (req.allied_type)
2066  {
2067  case alliedCamerasIds::wide_camera:
2068  res.error = GET_ALLIED_CAMERA_INTENSITY_CONTROLLER_TARGET(m_devices[0], *m_allied_wide_sensor, &res.intensity_controller_target);
2069  break;
2070  case alliedCamerasIds::narrow_camera:
2071  res.error = GET_ALLIED_CAMERA_INTENSITY_CONTROLLER_TARGET(m_devices[0], *m_allied_narrow_sensor, &res.intensity_controller_target);
2072  break;
2073  default:
2074  res.error = L3CAM_VALUE_OUT_OF_RANGE;
2075  }
2076  return true;
2077  }
2078 
2079  bool L3Cam::getAlliedCameraMaxDriverBuffersCount(l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Request &req, l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Response &res)
2080  {
2081  switch (req.allied_type)
2082  {
2083  case alliedCamerasIds::wide_camera:
2084  res.error = GET_ALLIED_CAMERA_MAX_DRIVER_BUFFERS_COUNT(m_devices[0], *m_allied_wide_sensor, &res.max_driver_buffers_count);
2085  break;
2086  case alliedCamerasIds::narrow_camera:
2087  res.error = GET_ALLIED_CAMERA_MAX_DRIVER_BUFFERS_COUNT(m_devices[0], *m_allied_narrow_sensor, &res.max_driver_buffers_count);
2088  break;
2089  default:
2090  res.error = L3CAM_VALUE_OUT_OF_RANGE;
2091  }
2092  return true;
2093  }
2094 
2095  // Sensors Disconnection
2097  {
2098  srv_network_disconnected_.request.code = code;
2100  {
2101  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_network_disconnected_.getService());
2102  }
2103  }
2104 
2106  {
2107  // Stream
2108  srv_pointcloud_stream_disconnected_.request.code = code;
2110  {
2111  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_lidar_stream_disconnected_.getService());
2112  }
2113 
2114  // Configuration
2115  srv_pointcloud_configuration_disconnected_.request.code = code;
2117  {
2118  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_lidar_configuration_disconnected_.getService());
2119  }
2120  }
2121 
2122  void L3Cam::polDisconnected(int code)
2123  {
2124  // Stream
2125  srv_pol_wide_stream_disconnected_.request.code = code;
2127  {
2128  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_pol_wide_stream_disconnected_.getService());
2129  }
2130 
2131  // Configuration
2132  srv_pol_configuration_disconnected_.request.code = code;
2134  {
2135  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_pol_configuration_disconnected_.getService());
2136  }
2137  }
2138 
2139  void L3Cam::rgbDisconnected(int code)
2140  {
2141  // Stream
2142  srv_rgb_narrow_stream_disconnected_.request.code = code;
2144  {
2145  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_rgb_narrow_stream_disconnected_.getService());
2146  }
2147 
2148  // Configuration
2149  srv_rgb_configuration_disconnected_.request.code = code;
2151  {
2152  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_rgb_configuration_disconnected_.getService());
2153  }
2154  }
2155 
2157  {
2158  // Stream
2159  srv_thermal_stream_disconnected_.request.code = code;
2161  {
2162  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_thermal_stream_disconnected_.getService());
2163  }
2164 
2165  // Configuration
2166  srv_thermal_configuration_disconnected_.request.code = code;
2168  {
2169  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_thermal_configuration_disconnected_.getService());
2170  }
2171  }
2172 
2174  {
2175  // Stream
2176  srv_pol_wide_stream_disconnected_.request.code = code;
2178  {
2179  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_pol_wide_stream_disconnected_.getService());
2180  }
2181 
2182  // Configuration
2183  srv_wide_configuration_disconnected_.request.code = code;
2185  {
2186  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_wide_configuration_disconnected_.getService());
2187  }
2188  }
2189 
2191  {
2192  // Stream
2193  srv_rgb_narrow_stream_disconnected_.request.code = code;
2195  {
2196  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_rgb_narrow_stream_disconnected_.getService());
2197  }
2198 
2199  // Configuration
2200  srv_narrow_configuration_disconnected_.request.code = code;
2202  {
2203  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service " << client_narrow_configuration_disconnected_.getService());
2204  }
2205  }
2206 
2207  void L3Cam::errorNotification(const int32_t *error)
2208  {
2209  // ROS_INFO_STREAM(this->getNamespace() << " Error notification received");
2210  int errort = *error;
2211 
2212  switch (errort)
2213  {
2214  case ERROR_LIDAR_TIMED_OUT:
2215  node->lidarDisconnected(errort);
2216  break;
2217  case ERROR_THERMAL_CAMERA_TIMEOUT:
2218  node->thermalDisconnected(errort);
2219  break;
2220  }
2221  }
2222 
2223 } // namespace l3cam_ros
2224 
2225 int main(int argc, char **argv)
2226 {
2227  ros::init(argc, argv, "l3cam_ros_node");
2228 
2229  ROS_INFO_STREAM("LibL3Cam version " << GET_VERSION() << "\n");
2230 
2231  node = new l3cam_ros::L3Cam();
2232 
2233  int error = L3CAM_OK;
2234  error = node->initializeDevice();
2235  if (error)
2236  {
2237  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while initializing device: " << getErrorDescription(error));
2238  ROS_INFO("Terminating...");
2239  node->disconnectAll(error);
2240  TERMINATE(node->m_devices[0]);
2242  ROS_INFO("Terminated.");
2243  ros::shutdown();
2244  return error;
2245  }
2246 
2247  error = node->startDeviceStream();
2248  if (error)
2249  {
2250  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while starting device and stream: " << getErrorDescription(error));
2251  if (error == L3CAM_TIMEOUT_ERROR)
2252  {
2253  ROS_INFO_STREAM("Device is not " << (node->m_status == LibL3CamStatus::connected_status ? "started." : "streaming."));
2254  }
2255  else
2256  {
2257  ROS_INFO("Terminating...");
2258  node->disconnectAll(error);
2259  STOP_STREAM(node->m_devices[0]);
2260  STOP_DEVICE(node->m_devices[0]);
2261  TERMINATE(node->m_devices[0]);
2263  ROS_INFO("Terminated.");
2264  ros::shutdown();
2265  return error;
2266  }
2267  }
2268 
2269  node->spin();
2270 
2271  ros::shutdown();
2272  return 0;
2273 }
l3cam_ros::L3Cam::srv_pointcloud_stream_disconnected_
l3cam_ros::SensorDisconnected srv_pointcloud_stream_disconnected_
Definition: l3cam_ros_node.hpp:373
l3cam_ros::L3Cam::getAlliedCameraExposureTime
bool getAlliedCameraExposureTime(l3cam_ros::GetAlliedCameraExposureTime::Request &req, l3cam_ros::GetAlliedCameraExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1766
l3cam_ros::L3Cam::m_shutdown_requested
bool m_shutdown_requested
Definition: l3cam_ros_node.hpp:406
l3cam_ros::L3Cam::enableAlliedCameraAutoExposureTime
bool enableAlliedCameraAutoExposureTime(l3cam_ros::EnableAlliedCameraAutoExposureTime::Request &req, l3cam_ros::EnableAlliedCameraAutoExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1494
l3cam_ros::L3Cam::changeRgbCameraExposureTime
bool changeRgbCameraExposureTime(l3cam_ros::ChangeRgbCameraExposureTime::Request &req, l3cam_ros::ChangeRgbCameraExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1440
l3cam_ros::L3Cam::printDefaultError
void printDefaultError(int error, std::string param)
Definition: l3cam_ros_node.cpp:436
l3cam_ros::L3Cam::srv_change_allied_gamma_
ros::ServiceServer srv_change_allied_gamma_
Definition: l3cam_ros_node.hpp:336
l3cam_ros::L3Cam::m_devices
l3cam m_devices[1]
Definition: l3cam_ros_node.hpp:146
l3cam_ros::L3Cam::srv_get_allied_hue_
ros::ServiceServer srv_get_allied_hue_
Definition: l3cam_ros_node.hpp:358
l3cam_ros::L3Cam::srv_enable_polarimetric_auto_gain_
ros::ServiceServer srv_enable_polarimetric_auto_gain_
Definition: l3cam_ros_node.hpp:305
l3cam_ros_node.hpp
l3cam_ros::L3Cam::getAlliedCameraIntensityAutoPrecedence
bool getAlliedCameraIntensityAutoPrecedence(l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Request &req, l3cam_ros::GetAlliedCameraIntensityAutoPrecedence::Response &res)
Definition: l3cam_ros_node.cpp:1932
l3cam_ros::L3Cam::client_thermal_configuration_disconnected_
ros::ServiceClient client_thermal_configuration_disconnected_
Definition: l3cam_ros_node.hpp:386
main
int main(int argc, char **argv)
Definition: l3cam_ros_node.cpp:2225
l3cam_ros::L3Cam::changeThermalCameraProcessingPipeline
bool changeThermalCameraProcessingPipeline(l3cam_ros::ChangeThermalCameraProcessingPipeline::Request &req, l3cam_ros::ChangeThermalCameraProcessingPipeline::Response &res)
Definition: l3cam_ros_node.cpp:1465
l3cam_ros::L3Cam::changeAlliedCameraGain
bool changeAlliedCameraGain(l3cam_ros::ChangeAlliedCameraGain::Request &req, l3cam_ros::ChangeAlliedCameraGain::Response &res)
Definition: l3cam_ros_node.cpp:1526
l3cam_ros::L3Cam::loadPolarimetricDefaultParams
void loadPolarimetricDefaultParams()
Definition: l3cam_ros_node.cpp:607
l3cam_ros::L3Cam::srv_change_allied_hue_
ros::ServiceServer srv_change_allied_hue_
Definition: l3cam_ros_node.hpp:338
l3cam_ros::L3Cam::changeRgbCameraWhiteBalance
bool changeRgbCameraWhiteBalance(l3cam_ros::ChangeRgbCameraWhiteBalance::Request &req, l3cam_ros::ChangeRgbCameraWhiteBalance::Response &res)
Definition: l3cam_ros_node.cpp:1428
l3cam_ros::L3Cam::srv_change_rgb_exposure_time_
ros::ServiceServer srv_change_rgb_exposure_time_
Definition: l3cam_ros_node.hpp:322
l3cam_ros::L3Cam::getAlliedCameraIntensityControllerRegion
bool getAlliedCameraIntensityControllerRegion(l3cam_ros::GetAlliedCameraIntensityControllerRegion::Request &req, l3cam_ros::GetAlliedCameraIntensityControllerRegion::Response &res)
Definition: l3cam_ros_node.cpp:2047
l3cam_ros::L3Cam::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: l3cam_ros_node.cpp:447
l3cam_ros::L3Cam::srv_change_pointcloud_color_range_
ros::ServiceServer srv_change_pointcloud_color_range_
Definition: l3cam_ros_node.hpp:294
l3cam_ros::L3Cam::powerOffDevice
bool powerOffDevice(l3cam_ros::PowerOffDevice::Request &req, l3cam_ros::PowerOffDevice::Response &res)
Definition: l3cam_ros_node.cpp:1174
l3cam_ros::L3Cam::getDeviceStatus
bool getDeviceStatus(l3cam_ros::GetDeviceStatus::Request &req, l3cam_ros::GetDeviceStatus::Response &res)
Definition: l3cam_ros_node.cpp:1027
l3cam_ros::L3Cam::srv_change_allied_gain_
ros::ServiceServer srv_change_allied_gain_
Definition: l3cam_ros_node.hpp:333
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::L3Cam::client_lidar_configuration_disconnected_
ros::ServiceClient client_lidar_configuration_disconnected_
Definition: l3cam_ros_node.hpp:374
l3cam_ros::L3Cam::enableRgbCameraAutoWhiteBalance
bool enableRgbCameraAutoWhiteBalance(l3cam_ros::EnableRgbCameraAutoWhiteBalance::Request &req, l3cam_ros::EnableRgbCameraAutoWhiteBalance::Response &res)
Definition: l3cam_ros_node.cpp:1422
l3cam_ros::L3Cam::changePointcloudColor
bool changePointcloudColor(l3cam_ros::ChangePointcloudColor::Request &req, l3cam_ros::ChangePointcloudColor::Response &res)
Definition: l3cam_ros_node.cpp:1272
l3cam_ros::L3Cam::srv_start_stream_
ros::ServiceServer srv_start_stream_
Definition: l3cam_ros_node.hpp:289
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
l3cam_ros::L3Cam::initializeDevice
int initializeDevice()
Definition: l3cam_ros_node.cpp:82
started_status
@ started_status
(TBD) after notification
Definition: l3cam_ros_utils.hpp:40
l3cam_ros::L3Cam::srv_change_rgb_sharpness_
ros::ServiceServer srv_change_rgb_sharpness_
Definition: l3cam_ros_node.hpp:316
l3cam_ros::L3Cam::changeAlliedCameraBalanceWhiteAutoTolerance
bool changeAlliedCameraBalanceWhiteAutoTolerance(l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Request &req, l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance::Response &res)
Definition: l3cam_ros_node.cpp:1702
l3cam_ros::L3Cam::getDeviceInfo
bool getDeviceInfo(l3cam_ros::GetDeviceInfo::Request &req, l3cam_ros::GetDeviceInfo::Response &res)
Definition: l3cam_ros_node.cpp:1017
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
l3cam_ros::L3Cam::changeAlliedCameraIntensityControllerRegion
bool changeAlliedCameraIntensityControllerRegion(l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Request &req, l3cam_ros::ChangeAlliedCameraIntensityControllerRegion::Response &res)
Definition: l3cam_ros_node.cpp:1718
l3cam_ros::L3Cam::getAlliedCameraGain
bool getAlliedCameraGain(l3cam_ros::GetAlliedCameraGain::Request &req, l3cam_ros::GetAlliedCameraGain::Response &res)
Definition: l3cam_ros_node.cpp:1817
l3cam_ros::L3Cam::changePolarimetricCameraBlackLevel
bool changePolarimetricCameraBlackLevel(l3cam_ros::ChangePolarimetricCameraBlackLevel::Request &req, l3cam_ros::ChangePolarimetricCameraBlackLevel::Response &res)
Definition: l3cam_ros_node.cpp:1336
l3cam_ros::L3Cam::setRgbCameraDefaultSettings
bool setRgbCameraDefaultSettings(l3cam_ros::SetRgbCameraDefaultSettings::Request &req, l3cam_ros::SetRgbCameraDefaultSettings::Response &res)
Definition: l3cam_ros_node.cpp:1379
l3cam_ros::L3Cam::setPolarimetricCameraDefaultSettings
bool setPolarimetricCameraDefaultSettings(l3cam_ros::SetPolarimetricCameraDefaultSettings::Request &req, l3cam_ros::SetPolarimetricCameraDefaultSettings::Response &res)
Definition: l3cam_ros_node.cpp:1323
l3cam_ros::L3Cam::client_narrow_configuration_disconnected_
ros::ServiceClient client_narrow_configuration_disconnected_
Definition: l3cam_ros_node.hpp:390
l3cam_ros::L3Cam::changeRgbCameraContrast
bool changeRgbCameraContrast(l3cam_ros::ChangeRgbCameraContrast::Request &req, l3cam_ros::ChangeRgbCameraContrast::Response &res)
Definition: l3cam_ros_node.cpp:1392
l3cam_ros::L3Cam::srv_change_network_configuration_
ros::ServiceServer srv_change_network_configuration_
Definition: l3cam_ros_node.hpp:285
l3cam_ros::L3Cam::srv_enable_allied_auto_gain_
ros::ServiceServer srv_enable_allied_auto_gain_
Definition: l3cam_ros_node.hpp:334
l3cam_ros::L3Cam::initializePolarimetricServices
void initializePolarimetricServices()
Definition: l3cam_ros_node.cpp:298
l3cam_ros::L3Cam::srv_initialize_
ros::ServiceServer srv_initialize_
Definition: l3cam_ros_node.hpp:275
l3cam_ros::L3Cam::srv_set_polarimetric_default_settings_
ros::ServiceServer srv_set_polarimetric_default_settings_
Definition: l3cam_ros_node.hpp:302
l3cam_ros::L3Cam::client_network_disconnected_
ros::ServiceClient client_network_disconnected_
Definition: l3cam_ros_node.hpp:370
l3cam_ros::L3Cam::getLocalServerAddress
bool getLocalServerAddress(l3cam_ros::GetLocalServerAddress::Request &req, l3cam_ros::GetLocalServerAddress::Response &res)
Definition: l3cam_ros_node.cpp:1010
l3cam_ros::L3Cam::srv_change_polarimetric_brightness_
ros::ServiceServer srv_change_polarimetric_brightness_
Definition: l3cam_ros_node.hpp:303
ros::spinOnce
ROSCPP_DECL void spinOnce()
l3cam_ros::L3Cam::srv_terminate_
ros::ServiceServer srv_terminate_
Definition: l3cam_ros_node.hpp:276
l3cam_ros::L3Cam::getAlliedCameraAutoModeRegion
bool getAlliedCameraAutoModeRegion(l3cam_ros::GetAlliedCameraAutoModeRegion::Request &req, l3cam_ros::GetAlliedCameraAutoModeRegion::Response &res)
Definition: l3cam_ros_node.cpp:2031
l3cam_ros::L3Cam::srv_change_bias_value_
ros::ServiceServer srv_change_bias_value_
Definition: l3cam_ros_node.hpp:298
l3cam_ros::L3Cam::srv_enable_rgb_auto_exposure_time_
ros::ServiceServer srv_enable_rgb_auto_exposure_time_
Definition: l3cam_ros_node.hpp:321
l3cam_ros::L3Cam::srv_get_allied_saturation_
ros::ServiceServer srv_get_allied_saturation_
Definition: l3cam_ros_node.hpp:356
l3cam_ros::L3Cam::srv_change_allied_exposure_time_
ros::ServiceServer srv_change_allied_exposure_time_
Definition: l3cam_ros_node.hpp:330
l3cam_ros::L3Cam::srv_change_allied_auto_gain_range_
ros::ServiceServer srv_change_allied_auto_gain_range_
Definition: l3cam_ros_node.hpp:335
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
l3cam_ros::L3Cam::srv_change_rgb_white_balance_
ros::ServiceServer srv_change_rgb_white_balance_
Definition: l3cam_ros_node.hpp:320
l3cam_ros::L3Cam::getAlliedCameraIntensityControllerTarget
bool getAlliedCameraIntensityControllerTarget(l3cam_ros::GetAlliedCameraIntensityControllerTarget::Request &req, l3cam_ros::GetAlliedCameraIntensityControllerTarget::Response &res)
Definition: l3cam_ros_node.cpp:2063
l3cam_ros::L3Cam::changePolarimetricCameraAutoExposureTimeRange
bool changePolarimetricCameraAutoExposureTimeRange(l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Request &req, l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange::Response &res)
Definition: l3cam_ros_node.cpp:1366
l3cam_ros::L3Cam::client_pol_wide_stream_disconnected_
ros::ServiceClient client_pol_wide_stream_disconnected_
Definition: l3cam_ros_node.hpp:376
l3cam_ros::L3Cam::loadDefaultParams
void loadDefaultParams()
Definition: l3cam_ros_node.cpp:465
l3cam_ros::L3Cam::lidarDisconnected
void lidarDisconnected(int code)
Definition: l3cam_ros_node.cpp:2105
l3cam_ros::L3Cam::srv_stop_stream_
ros::ServiceServer srv_stop_stream_
Definition: l3cam_ros_node.hpp:290
l3cam_ros::L3Cam::srv_enable_allied_auto_exposure_time_
ros::ServiceServer srv_enable_allied_auto_exposure_time_
Definition: l3cam_ros_node.hpp:331
l3cam_ros::L3Cam::networkDisconnected
void networkDisconnected(int code)
Definition: l3cam_ros_node.cpp:2096
l3cam_ros::L3Cam::rgbDisconnected
void rgbDisconnected(int code)
Definition: l3cam_ros_node.cpp:2139
l3cam_ros::L3Cam::initializeAlliedNarrowServices
void initializeAlliedNarrowServices()
Definition: l3cam_ros_node.cpp:390
l3cam_ros::L3Cam::srv_thermal_configuration_disconnected_
l3cam_ros::SensorDisconnected srv_thermal_configuration_disconnected_
Definition: l3cam_ros_node.hpp:387
l3cam_ros::L3Cam::srv_get_allied_gamma_
ros::ServiceServer srv_get_allied_gamma_
Definition: l3cam_ros_node.hpp:355
l3cam_ros::L3Cam::srv_change_allied_balance_white_auto_rate_
ros::ServiceServer srv_change_allied_balance_white_auto_rate_
Definition: l3cam_ros_node.hpp:343
l3cam_ros::L3Cam::srv_get_allied_intensity_controller_target_
ros::ServiceServer srv_get_allied_intensity_controller_target_
Definition: l3cam_ros_node.hpp:367
l3cam_ros::L3Cam::changeRgbCameraGamma
bool changeRgbCameraGamma(l3cam_ros::ChangeRgbCameraGamma::Request &req, l3cam_ros::ChangeRgbCameraGamma::Response &res)
Definition: l3cam_ros_node.cpp:1410
L3CAM_ROS_INTERRUPTED
#define L3CAM_ROS_INTERRUPTED
Definition: l3cam_ros_errors.hpp:30
l3cam_ros::L3Cam::client_rgb_configuration_disconnected_
ros::ServiceClient client_rgb_configuration_disconnected_
Definition: l3cam_ros_node.hpp:382
l3cam_ros::L3Cam::srv_get_allied_intensity_auto_precedence_
ros::ServiceServer srv_get_allied_intensity_auto_precedence_
Definition: l3cam_ros_node.hpp:359
l3cam_ros::L3Cam::m_status
LibL3CamStatus m_status
Definition: l3cam_ros_node.hpp:147
l3cam_ros
Definition: l3cam_ros_node.hpp:133
l3cam_ros::L3Cam::srv_get_version_
ros::ServiceServer srv_get_version_
Definition: l3cam_ros_node.hpp:274
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
ros::ok
ROSCPP_DECL bool ok()
l3cam_ros::L3Cam::srv_pointcloud_configuration_disconnected_
l3cam_ros::SensorDisconnected srv_pointcloud_configuration_disconnected_
Definition: l3cam_ros_node.hpp:375
l3cam_ros::L3Cam::srv_get_device_status_
ros::ServiceServer srv_get_device_status_
Definition: l3cam_ros_node.hpp:280
l3cam_ros::L3Cam::getSensorsAvailable
bool getSensorsAvailable(l3cam_ros::GetSensorsAvailable::Request &req, l3cam_ros::GetSensorsAvailable::Response &res)
Definition: l3cam_ros_node.cpp:1034
l3cam_ros::L3Cam::srv_change_polarimetric_gain_
ros::ServiceServer srv_change_polarimetric_gain_
Definition: l3cam_ros_node.hpp:307
l3cam_ros::L3Cam::changeAlliedCameraHue
bool changeAlliedCameraHue(l3cam_ros::ChangeAlliedCameraHue::Request &req, l3cam_ros::ChangeAlliedCameraHue::Response &res)
Definition: l3cam_ros_node.cpp:1606
l3cam_ros::L3Cam::timeout_secs_
int timeout_secs_
Definition: l3cam_ros_node.hpp:404
l3cam_ros::L3Cam::getAlliedCameraSaturation
bool getAlliedCameraSaturation(l3cam_ros::GetAlliedCameraSaturation::Request &req, l3cam_ros::GetAlliedCameraSaturation::Response &res)
Definition: l3cam_ros_node.cpp:1884
l3cam_ros::L3Cam::srv_get_device_info_
ros::ServiceServer srv_get_device_info_
Definition: l3cam_ros_node.hpp:279
terminated_status
@ terminated_status
Definition: l3cam_ros_utils.hpp:42
l3cam_ros::L3Cam::client_pol_configuration_disconnected_
ros::ServiceClient client_pol_configuration_disconnected_
Definition: l3cam_ros_node.hpp:378
l3cam_ros::L3Cam::startDevice
bool startDevice(l3cam_ros::StartDevice::Request &req, l3cam_ros::StartDevice::Response &res)
Definition: l3cam_ros_node.cpp:1182
l3cam_ros::L3Cam::srv_power_off_device_
ros::ServiceServer srv_power_off_device_
Definition: l3cam_ros_node.hpp:286
l3cam_ros::L3Cam::srv_change_distance_range_
ros::ServiceServer srv_change_distance_range_
Definition: l3cam_ros_node.hpp:295
l3cam_ros::L3Cam::enableRgbCameraAutoExposureTime
bool enableRgbCameraAutoExposureTime(l3cam_ros::EnableRgbCameraAutoExposureTime::Request &req, l3cam_ros::EnableRgbCameraAutoExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1434
ros::ServiceClient::getService
std::string getService()
l3cam_ros::L3Cam::getAlliedCameraHue
bool getAlliedCameraHue(l3cam_ros::GetAlliedCameraHue::Request &req, l3cam_ros::GetAlliedCameraHue::Response &res)
Definition: l3cam_ros_node.cpp:1916
l3cam_ros::L3Cam::changeRgbCameraSharpness
bool changeRgbCameraSharpness(l3cam_ros::ChangeRgbCameraSharpness::Request &req, l3cam_ros::ChangeRgbCameraSharpness::Response &res)
Definition: l3cam_ros_node.cpp:1404
l3cam_ros::L3Cam::polDisconnected
void polDisconnected(int code)
Definition: l3cam_ros_node.cpp:2122
l3cam_ros::L3Cam::srv_change_allied_balance_ratio_
ros::ServiceServer srv_change_allied_balance_ratio_
Definition: l3cam_ros_node.hpp:342
l3cam_ros::L3Cam::srv_get_allied_auto_gain_range_
ros::ServiceServer srv_get_allied_auto_gain_range_
Definition: l3cam_ros_node.hpp:354
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros::L3Cam::loadAlliedWideDefaultParams
void loadAlliedWideDefaultParams()
Definition: l3cam_ros_node.cpp:760
l3cam_ros::L3Cam::changeNetworkConfiguration
bool changeNetworkConfiguration(l3cam_ros::ChangeNetworkConfiguration::Request &req, l3cam_ros::ChangeNetworkConfiguration::Response &res)
Definition: l3cam_ros_node.cpp:1159
l3cam_ros::L3Cam::changeAlliedCameraGamma
bool changeAlliedCameraGamma(l3cam_ros::ChangeAlliedCameraGamma::Request &req, l3cam_ros::ChangeAlliedCameraGamma::Response &res)
Definition: l3cam_ros_node.cpp:1574
l3cam_ros::L3Cam::getAlliedCameraAutoGain
bool getAlliedCameraAutoGain(l3cam_ros::GetAlliedCameraAutoGain::Request &req, l3cam_ros::GetAlliedCameraAutoGain::Response &res)
Definition: l3cam_ros_node.cpp:1833
l3cam_ros::L3Cam::getNetworkConfiguration
bool getNetworkConfiguration(l3cam_ros::GetNetworkConfiguration::Request &req, l3cam_ros::GetNetworkConfiguration::Response &res)
Definition: l3cam_ros_node.cpp:1146
l3cam_ros::L3Cam::changeAlliedCameraSaturation
bool changeAlliedCameraSaturation(l3cam_ros::ChangeAlliedCameraSaturation::Request &req, l3cam_ros::ChangeAlliedCameraSaturation::Response &res)
Definition: l3cam_ros_node.cpp:1590
l3cam_ros::L3Cam::changeDistanceRange
bool changeDistanceRange(l3cam_ros::ChangeDistanceRange::Request &req, l3cam_ros::ChangeDistanceRange::Response &res)
Definition: l3cam_ros_node.cpp:1284
l3cam_ros::L3Cam::client_lidar_stream_disconnected_
ros::ServiceClient client_lidar_stream_disconnected_
Definition: l3cam_ros_node.hpp:372
l3cam_ros::L3Cam::changeAutobiasValue
bool changeAutobiasValue(l3cam_ros::ChangeAutobiasValue::Request &req, l3cam_ros::ChangeAutobiasValue::Response &res)
Definition: l3cam_ros_node.cpp:1308
l3cam_ros::L3Cam::srv_rgb_configuration_disconnected_
l3cam_ros::SensorDisconnected srv_rgb_configuration_disconnected_
Definition: l3cam_ros_node.hpp:383
l3cam_ros::L3Cam::srv_change_rgb_gain_
ros::ServiceServer srv_change_rgb_gain_
Definition: l3cam_ros_node.hpp:318
l3cam_ros::L3Cam::client_rgb_narrow_stream_disconnected_
ros::ServiceClient client_rgb_narrow_stream_disconnected_
Definition: l3cam_ros_node.hpp:380
l3cam_ros::L3Cam::initializeLidarServices
void initializeLidarServices()
Definition: l3cam_ros_node.cpp:283
l3cam_ros::L3Cam::srv_get_network_configuration_
ros::ServiceServer srv_get_network_configuration_
Definition: l3cam_ros_node.hpp:284
l3cam_ros::L3Cam::srv_change_allied_intensity_controller_target_
ros::ServiceServer srv_change_allied_intensity_controller_target_
Definition: l3cam_ros_node.hpp:346
l3cam_ros::L3Cam::loadLidarDefaultParams
void loadLidarDefaultParams()
Definition: l3cam_ros_node.cpp:552
l3cam_ros::L3Cam::client_thermal_stream_disconnected_
ros::ServiceClient client_thermal_stream_disconnected_
Definition: l3cam_ros_node.hpp:384
l3cam_ros::L3Cam::enableAlliedCameraAutoGain
bool enableAlliedCameraAutoGain(l3cam_ros::EnableAlliedCameraAutoGain::Request &req, l3cam_ros::EnableAlliedCameraAutoGain::Response &res)
Definition: l3cam_ros_node.cpp:1542
l3cam_ros::L3Cam::changeThermalCameraTemperatureFilter
bool changeThermalCameraTemperatureFilter(l3cam_ros::ChangeThermalCameraTemperatureFilter::Request &req, l3cam_ros::ChangeThermalCameraTemperatureFilter::Response &res)
Definition: l3cam_ros_node.cpp:1459
l3cam_ros::L3Cam::getVersion
bool getVersion(l3cam_ros::GetVersion::Request &req, l3cam_ros::GetVersion::Response &res)
Definition: l3cam_ros_node.cpp:966
l3cam_ros::L3Cam::changePolarimetricCameraExposureTime
bool changePolarimetricCameraExposureTime(l3cam_ros::ChangePolarimetricCameraExposureTime::Request &req, l3cam_ros::ChangePolarimetricCameraExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1372
l3cam_ros::L3Cam::srv_enable_allied_auto_white_balance_
ros::ServiceServer srv_enable_allied_auto_white_balance_
Definition: l3cam_ros_node.hpp:340
l3cam_ros::L3Cam::changeAlliedCameraBalanceRatioSelector
bool changeAlliedCameraBalanceRatioSelector(l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Request &req, l3cam_ros::ChangeAlliedCameraBalanceRatioSelector::Response &res)
Definition: l3cam_ros_node.cpp:1654
l3cam_ros::L3Cam::changePointcloudColorRange
bool changePointcloudColorRange(l3cam_ros::ChangePointcloudColorRange::Request &req, l3cam_ros::ChangePointcloudColorRange::Response &res)
Definition: l3cam_ros_node.cpp:1278
l3cam_ros::L3Cam::m_thermal_sensor
sensor * m_thermal_sensor
Definition: l3cam_ros_node.hpp:398
l3cam_ros::L3Cam::srv_change_thermal_colormap_
ros::ServiceServer srv_change_thermal_colormap_
Definition: l3cam_ros_node.hpp:324
l3cam_ros::L3Cam::srv_change_polarimetric_auto_exposure_time_range_
ros::ServiceServer srv_change_polarimetric_auto_exposure_time_range_
Definition: l3cam_ros_node.hpp:309
l3cam_ros::L3Cam::stopDevice
bool stopDevice(l3cam_ros::StopDevice::Request &req, l3cam_ros::StopDevice::Response &res)
Definition: l3cam_ros_node.cpp:1193
l3cam_ros::L3Cam::getAlliedCameraMaxDriverBuffersCount
bool getAlliedCameraMaxDriverBuffersCount(l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Request &req, l3cam_ros::GetAlliedCameraMaxDriverBuffersCount::Response &res)
Definition: l3cam_ros_node.cpp:2079
undefined_status
@ undefined_status
Definition: l3cam_ros_utils.hpp:36
l3cam_ros::L3Cam::loadAlliedNarrowDefaultParams
void loadAlliedNarrowDefaultParams()
Definition: l3cam_ros_node.cpp:859
l3cam_ros::L3Cam::enableThermalCameraTemperatureDataUdp
bool enableThermalCameraTemperatureDataUdp(l3cam_ros::EnableThermalCameraTemperatureDataUdp::Request &req, l3cam_ros::EnableThermalCameraTemperatureDataUdp::Response &res)
Definition: l3cam_ros_node.cpp:1471
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::L3Cam::srv_get_allied_balance_white_auto_tolerance_
ros::ServiceServer srv_get_allied_balance_white_auto_tolerance_
Definition: l3cam_ros_node.hpp:364
l3cam_ros::L3Cam::enableThermalCameraTemperatureFilter
bool enableThermalCameraTemperatureFilter(l3cam_ros::EnableThermalCameraTemperatureFilter::Request &req, l3cam_ros::EnableThermalCameraTemperatureFilter::Response &res)
Definition: l3cam_ros_node.cpp:1453
l3cam_ros::L3Cam::srv_start_device_
ros::ServiceServer srv_start_device_
Definition: l3cam_ros_node.hpp:287
l3cam_ros::L3Cam::enablePolarimetricCameraAutoExposureTime
bool enablePolarimetricCameraAutoExposureTime(l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Request &req, l3cam_ros::EnablePolarimetricCameraAutoExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1360
l3cam_ros::L3Cam::changeRgbCameraBrightness
bool changeRgbCameraBrightness(l3cam_ros::ChangeRgbCameraBrightness::Request &req, l3cam_ros::ChangeRgbCameraBrightness::Response &res)
Definition: l3cam_ros_node.cpp:1386
l3cam_ros::L3Cam::srv_enable_thermal_temperature_filter_
ros::ServiceServer srv_enable_thermal_temperature_filter_
Definition: l3cam_ros_node.hpp:325
l3cam_ros::L3Cam::srv_change_autobias_value_
ros::ServiceServer srv_change_autobias_value_
Definition: l3cam_ros_node.hpp:299
l3cam_ros::L3Cam::srv_get_allied_max_driver_buffers_count_
ros::ServiceServer srv_get_allied_max_driver_buffers_count_
Definition: l3cam_ros_node.hpp:368
l3cam_ros::L3Cam::srv_enable_polarimetric_auto_exposure_time_
ros::ServiceServer srv_enable_polarimetric_auto_exposure_time_
Definition: l3cam_ros_node.hpp:308
l3cam_ros::L3Cam::changePolarimetricCameraGain
bool changePolarimetricCameraGain(l3cam_ros::ChangePolarimetricCameraGain::Request &req, l3cam_ros::ChangePolarimetricCameraGain::Response &res)
Definition: l3cam_ros_node.cpp:1354
l3cam_ros::L3Cam::srv_get_allied_sharpness_
ros::ServiceServer srv_get_allied_sharpness_
Definition: l3cam_ros_node.hpp:357
l3cam_ros::L3Cam::initializeThermalServices
void initializeThermalServices()
Definition: l3cam_ros_node.cpp:332
l3cam_ros::L3Cam::startStream
bool startStream(l3cam_ros::StartStream::Request &req, l3cam_ros::StartStream::Response &res)
Definition: l3cam_ros_node.cpp:1209
l3cam_ros::L3Cam::L3Cam
L3Cam()
Definition: l3cam_ros_node.cpp:45
l3cam_ros::L3Cam::m_allied_narrow_sensor
sensor * m_allied_narrow_sensor
Definition: l3cam_ros_node.hpp:401
l3cam_ros::L3Cam::m_lidar_sensor
sensor * m_lidar_sensor
Definition: l3cam_ros_node.hpp:395
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
l3cam_ros::L3Cam::enablePolarimetricCameraAutoGain
bool enablePolarimetricCameraAutoGain(l3cam_ros::EnablePolarimetricCameraAutoGain::Request &req, l3cam_ros::EnablePolarimetricCameraAutoGain::Response &res)
Definition: l3cam_ros_node.cpp:1342
l3cam_ros::L3Cam::srv_get_allied_intensity_controller_region_
ros::ServiceServer srv_get_allied_intensity_controller_region_
Definition: l3cam_ros_node.hpp:366
l3cam_ros::L3Cam::srv_change_rgb_gamma_
ros::ServiceServer srv_change_rgb_gamma_
Definition: l3cam_ros_node.hpp:317
l3cam_ros::L3Cam::srv_pol_wide_stream_disconnected_
l3cam_ros::SensorDisconnected srv_pol_wide_stream_disconnected_
Definition: l3cam_ros_node.hpp:377
l3cam_ros::L3Cam::srv_narrow_configuration_disconnected_
l3cam_ros::SensorDisconnected srv_narrow_configuration_disconnected_
Definition: l3cam_ros_node.hpp:391
l3cam_ros::L3Cam::m_av_sensors
sensor m_av_sensors[6]
Definition: l3cam_ros_node.hpp:393
l3cam_ros::L3Cam::srv_set_rgb_default_settings_
ros::ServiceServer srv_set_rgb_default_settings_
Definition: l3cam_ros_node.hpp:312
l3cam_ros::L3Cam::srv_change_thermal_processing_pipeline_
ros::ServiceServer srv_change_thermal_processing_pipeline_
Definition: l3cam_ros_node.hpp:327
l3cam_ros::L3Cam::srv_get_autobias_value_
ros::ServiceServer srv_get_autobias_value_
Definition: l3cam_ros_node.hpp:300
l3cam_ros::L3Cam::loadThermalDefaultParams
void loadThermalDefaultParams()
Definition: l3cam_ros_node.cpp:725
l3cam_ros::L3Cam::changeAlliedCameraExposureTime
bool changeAlliedCameraExposureTime(l3cam_ros::ChangeAlliedCameraExposureTime::Request &req, l3cam_ros::ChangeAlliedCameraExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1478
l3cam_ros::L3Cam::srv_get_allied_auto_exposure_time_
ros::ServiceServer srv_get_allied_auto_exposure_time_
Definition: l3cam_ros_node.hpp:350
l3cam_ros::L3Cam::srv_change_allied_balance_white_auto_tolerance_
ros::ServiceServer srv_change_allied_balance_white_auto_tolerance_
Definition: l3cam_ros_node.hpp:344
l3cam_ros::L3Cam::startDeviceStream
int startDeviceStream()
Definition: l3cam_ros_node.cpp:173
l3cam_ros::L3Cam::srv_network_disconnected_
l3cam_ros::SensorDisconnected srv_network_disconnected_
Definition: l3cam_ros_node.hpp:371
l3cam_ros::L3Cam::initializeServices
void initializeServices()
Definition: l3cam_ros_node.cpp:228
l3cam_ros::L3Cam::srv_wide_configuration_disconnected_
l3cam_ros::SensorDisconnected srv_wide_configuration_disconnected_
Definition: l3cam_ros_node.hpp:389
l3cam_ros::L3Cam::getAlliedCameraAutoGainRange
bool getAlliedCameraAutoGainRange(l3cam_ros::GetAlliedCameraAutoGainRange::Request &req, l3cam_ros::GetAlliedCameraAutoGainRange::Response &res)
Definition: l3cam_ros_node.cpp:1852
l3cam_ros::L3Cam::loadRgbDefaultParams
void loadRgbDefaultParams()
Definition: l3cam_ros_node.cpp:665
l3cam_ros::L3Cam::initializeRgbServices
void initializeRgbServices()
Definition: l3cam_ros_node.cpp:314
l3cam_ros::L3Cam::changePolarimetricCameraAutoGainRange
bool changePolarimetricCameraAutoGainRange(l3cam_ros::ChangePolarimetricCameraAutoGainRange::Request &req, l3cam_ros::ChangePolarimetricCameraAutoGainRange::Response &res)
Definition: l3cam_ros_node.cpp:1348
l3cam_ros::L3Cam::srv_change_streaming_protocol_
ros::ServiceServer srv_change_streaming_protocol_
Definition: l3cam_ros_node.hpp:282
l3cam_ros::L3Cam::getAlliedCameraBalanceRatioSelector
bool getAlliedCameraBalanceRatioSelector(l3cam_ros::GetAlliedCameraBalanceRatioSelector::Request &req, l3cam_ros::GetAlliedCameraBalanceRatioSelector::Response &res)
Definition: l3cam_ros_node.cpp:1967
l3cam_ros::L3Cam::initializeAlliedWideServices
void initializeAlliedWideServices()
Definition: l3cam_ros_node.cpp:344
l3cam_ros::L3Cam
Definition: l3cam_ros_node.hpp:135
l3cam_ros::L3Cam::srv_find_devices_
ros::ServiceServer srv_find_devices_
Definition: l3cam_ros_node.hpp:277
l3cam_ros::L3Cam::changeStreamingProtocol
bool changeStreamingProtocol(l3cam_ros::ChangeStreamingProtocol::Request &req, l3cam_ros::ChangeStreamingProtocol::Response &res)
Definition: l3cam_ros_node.cpp:1051
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::L3Cam::changeAlliedCameraIntensityAutoPrecedence
bool changeAlliedCameraIntensityAutoPrecedence(l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Request &req, l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence::Response &res)
Definition: l3cam_ros_node.cpp:1622
l3cam_ros::L3Cam::srv_get_allied_balance_ratio_
ros::ServiceServer srv_get_allied_balance_ratio_
Definition: l3cam_ros_node.hpp:362
l3cam_ros::L3Cam::enableAutoBias
bool enableAutoBias(l3cam_ros::EnableAutoBias::Request &req, l3cam_ros::EnableAutoBias::Response &res)
Definition: l3cam_ros_node.cpp:1296
l3cam_ros::L3Cam::disconnectAll
void disconnectAll(int code)
Definition: l3cam_ros_node.cpp:198
l3cam_ros::L3Cam::srv_change_allied_intensity_auto_precedence_
ros::ServiceServer srv_change_allied_intensity_auto_precedence_
Definition: l3cam_ros_node.hpp:339
l3cam_ros::L3Cam::srv_libl3cam_status_
ros::ServiceServer srv_libl3cam_status_
Definition: l3cam_ros_node.hpp:273
L3CAM_ROS_FIND_DEVICES_TIMEOUT_ERROR
#define L3CAM_ROS_FIND_DEVICES_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:28
l3cam_ros::L3Cam::getAutobiasValue
bool getAutobiasValue(l3cam_ros::GetAutobiasValue::Request &req, l3cam_ros::GetAutobiasValue::Response &res)
Definition: l3cam_ros_node.cpp:1314
l3cam_ros::L3Cam::srv_change_polarimetric_exposure_time_
ros::ServiceServer srv_change_polarimetric_exposure_time_
Definition: l3cam_ros_node.hpp:310
l3cam_ros::L3Cam::m_allied_wide_sensor
sensor * m_allied_wide_sensor
Definition: l3cam_ros_node.hpp:400
l3cam_ros::L3Cam::srv_change_thermal_temperature_filter_
ros::ServiceServer srv_change_thermal_temperature_filter_
Definition: l3cam_ros_node.hpp:326
l3cam_ros::L3Cam::srv_enable_auto_bias_
ros::ServiceServer srv_enable_auto_bias_
Definition: l3cam_ros_node.hpp:297
l3cam_ros::L3Cam::getAlliedCameraBalanceWhiteAutoTolerance
bool getAlliedCameraBalanceWhiteAutoTolerance(l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Request &req, l3cam_ros::GetAlliedCameraBalanceWhiteAutoTolerance::Response &res)
Definition: l3cam_ros_node.cpp:2015
l3cam_ros::L3Cam::changeRgbCameraSaturation
bool changeRgbCameraSaturation(l3cam_ros::ChangeRgbCameraSaturation::Request &req, l3cam_ros::ChangeRgbCameraSaturation::Response &res)
Definition: l3cam_ros_node.cpp:1398
l3cam_ros::L3Cam::changeAlliedCameraBalanceRatio
bool changeAlliedCameraBalanceRatio(l3cam_ros::ChangeAlliedCameraBalanceRatio::Request &req, l3cam_ros::ChangeAlliedCameraBalanceRatio::Response &res)
Definition: l3cam_ros_node.cpp:1670
l3cam_ros::L3Cam::changeAlliedCameraAutoExposureTimeRange
bool changeAlliedCameraAutoExposureTimeRange(l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Request &req, l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange::Response &res)
Definition: l3cam_ros_node.cpp:1510
l3cam_ros::L3Cam::alliedwideDisconnected
void alliedwideDisconnected(int code)
Definition: l3cam_ros_node.cpp:2173
l3cam_ros::L3Cam::m_econ_wide_sensor
sensor * m_econ_wide_sensor
Definition: l3cam_ros_node.hpp:397
l3cam_ros::L3Cam::findDevices
bool findDevices(l3cam_ros::FindDevices::Request &req, l3cam_ros::FindDevices::Response &res)
Definition: l3cam_ros_node.cpp:1003
l3cam_ros::L3Cam::srv_get_allied_auto_gain_
ros::ServiceServer srv_get_allied_auto_gain_
Definition: l3cam_ros_node.hpp:353
l3cam_ros::L3Cam::alliedNarrowDisconnect
void alliedNarrowDisconnect(int code)
Definition: l3cam_ros_node.cpp:2190
l3cam_ros::L3Cam::changePolarimetricCameraBrightness
bool changePolarimetricCameraBrightness(l3cam_ros::ChangePolarimetricCameraBrightness::Request &req, l3cam_ros::ChangePolarimetricCameraBrightness::Response &res)
Definition: l3cam_ros_node.cpp:1330
l3cam_ros::L3Cam::getAlliedCameraAutoExposureTimeRange
bool getAlliedCameraAutoExposureTimeRange(l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Request &req, l3cam_ros::GetAlliedCameraAutoExposureTimeRange::Response &res)
Definition: l3cam_ros_node.cpp:1801
l3cam_ros::L3Cam::initialize
bool initialize(l3cam_ros::Initialize::Request &req, l3cam_ros::Initialize::Response &res)
Definition: l3cam_ros_node.cpp:973
l3cam_ros::L3Cam::changeThermalCameraColormap
bool changeThermalCameraColormap(l3cam_ros::ChangeThermalCameraColormap::Request &req, l3cam_ros::ChangeThermalCameraColormap::Response &res)
Definition: l3cam_ros_node.cpp:1447
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
l3cam_ros::L3Cam::srv_change_rgb_brightness_
ros::ServiceServer srv_change_rgb_brightness_
Definition: l3cam_ros_node.hpp:313
l3cam_ros::L3Cam::getAlliedCameraBalanceRatio
bool getAlliedCameraBalanceRatio(l3cam_ros::GetAlliedCameraBalanceRatio::Request &req, l3cam_ros::GetAlliedCameraBalanceRatio::Response &res)
Definition: l3cam_ros_node.cpp:1983
l3cam_ros::L3Cam::srv_get_allied_balance_white_auto_rate_
ros::ServiceServer srv_get_allied_balance_white_auto_rate_
Definition: l3cam_ros_node.hpp:363
connected_status
@ connected_status
Definition: l3cam_ros_utils.hpp:38
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
l3cam_ros::L3Cam::srv_get_allied_gain_
ros::ServiceServer srv_get_allied_gain_
Definition: l3cam_ros_node.hpp:352
l3cam_ros::L3Cam::srv_rgb_narrow_stream_disconnected_
l3cam_ros::SensorDisconnected srv_rgb_narrow_stream_disconnected_
Definition: l3cam_ros_node.hpp:381
l3cam_ros::L3Cam::srv_change_allied_saturation_
ros::ServiceServer srv_change_allied_saturation_
Definition: l3cam_ros_node.hpp:337
l3cam_ros::L3Cam::srv_change_polarimetric_auto_gain_range_
ros::ServiceServer srv_change_polarimetric_auto_gain_range_
Definition: l3cam_ros_node.hpp:306
l3cam_ros::L3Cam::srv_get_allied_black_level_
ros::ServiceServer srv_get_allied_black_level_
Definition: l3cam_ros_node.hpp:348
l3cam_ros::L3Cam::terminate
bool terminate(l3cam_ros::Terminate::Request &req, l3cam_ros::Terminate::Response &res)
Definition: l3cam_ros_node.cpp:980
l3cam_ros::L3Cam::srv_get_allied_auto_mode_region_
ros::ServiceServer srv_get_allied_auto_mode_region_
Definition: l3cam_ros_node.hpp:365
l3cam_ros::L3Cam::getRtspPipeline
bool getRtspPipeline(l3cam_ros::GetRtspPipeline::Request &req, l3cam_ros::GetRtspPipeline::Response &res)
Definition: l3cam_ros_node.cpp:1108
ros::Duration::sleep
bool sleep() const
l3cam_ros::L3Cam::srv_pol_configuration_disconnected_
l3cam_ros::SensorDisconnected srv_pol_configuration_disconnected_
Definition: l3cam_ros_node.hpp:379
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
l3cam_ros::L3Cam::srv_change_allied_balance_ratio_selector_
ros::ServiceServer srv_change_allied_balance_ratio_selector_
Definition: l3cam_ros_node.hpp:341
l3cam_ros::L3Cam::changeAlliedCameraAutoGainRange
bool changeAlliedCameraAutoGainRange(l3cam_ros::ChangeAlliedCameraAutoGainRange::Request &req, l3cam_ros::ChangeAlliedCameraAutoGainRange::Response &res)
Definition: l3cam_ros_node.cpp:1558
l3cam_ros::L3Cam::srv_get_rtsp_pipeline_
ros::ServiceServer srv_get_rtsp_pipeline_
Definition: l3cam_ros_node.hpp:283
l3cam_ros::L3Cam::errorNotification
static void errorNotification(const int32_t *error)
Definition: l3cam_ros_node.cpp:2207
l3cam_ros::L3Cam::srv_enable_thermal_temperature_data_udp_
ros::ServiceServer srv_enable_thermal_temperature_data_udp_
Definition: l3cam_ros_node.hpp:328
l3cam_ros::L3Cam::getAlliedCameraBlackLevel
bool getAlliedCameraBlackLevel(l3cam_ros::GetAlliedCameraBlackLevel::Request &req, l3cam_ros::GetAlliedCameraBlackLevel::Response &res)
Definition: l3cam_ros_node.cpp:1750
l3cam_ros::L3Cam::getAlliedCameraSharpness
bool getAlliedCameraSharpness(l3cam_ros::GetAlliedCameraSharpness::Request &req, l3cam_ros::GetAlliedCameraSharpness::Response &res)
Definition: l3cam_ros_node.cpp:1900
l3cam_ros::L3Cam::srv_thermal_stream_disconnected_
l3cam_ros::SensorDisconnected srv_thermal_stream_disconnected_
Definition: l3cam_ros_node.hpp:385
l3cam_ros::L3Cam::m_num_devices
int m_num_devices
Definition: l3cam_ros_node.hpp:403
l3cam_ros::L3Cam::srv_set_bias_short_range_
ros::ServiceServer srv_set_bias_short_range_
Definition: l3cam_ros_node.hpp:296
l3cam_ros::L3Cam::srv_get_allied_auto_exposure_time_range_
ros::ServiceServer srv_get_allied_auto_exposure_time_range_
Definition: l3cam_ros_node.hpp:351
l3cam_ros::L3Cam::srv_get_allied_auto_white_balance_
ros::ServiceServer srv_get_allied_auto_white_balance_
Definition: l3cam_ros_node.hpp:360
l3cam_ros::L3Cam::srv_change_allied_auto_exposure_time_range_
ros::ServiceServer srv_change_allied_auto_exposure_time_range_
Definition: l3cam_ros_node.hpp:332
l3cam_ros::L3Cam::srv_get_sensors_available_
ros::ServiceServer srv_get_sensors_available_
Definition: l3cam_ros_node.hpp:281
ROS_INFO
#define ROS_INFO(...)
l3cam_ros::L3Cam::srv_enable_rgb_auto_white_balance_
ros::ServiceServer srv_enable_rgb_auto_white_balance_
Definition: l3cam_ros_node.hpp:319
l3cam_ros::L3Cam::getAlliedCameraAutoExposureTime
bool getAlliedCameraAutoExposureTime(l3cam_ros::GetAlliedCameraAutoExposureTime::Request &req, l3cam_ros::GetAlliedCameraAutoExposureTime::Response &res)
Definition: l3cam_ros_node.cpp:1782
l3cam_ros::L3Cam::enableAlliedCameraAutoWhiteBalance
bool enableAlliedCameraAutoWhiteBalance(l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Request &req, l3cam_ros::EnableAlliedCameraAutoWhiteBalance::Response &res)
Definition: l3cam_ros_node.cpp:1638
ros::Duration
l3cam_ros::L3Cam::m_rgb_sensor
sensor * m_rgb_sensor
Definition: l3cam_ros_node.hpp:396
l3cam_ros::L3Cam::client_wide_configuration_disconnected_
ros::ServiceClient client_wide_configuration_disconnected_
Definition: l3cam_ros_node.hpp:388
l3cam_ros::L3Cam::srv_change_rgb_saturation_
ros::ServiceServer srv_change_rgb_saturation_
Definition: l3cam_ros_node.hpp:315
l3cam_ros::L3Cam::changeBiasValue
bool changeBiasValue(l3cam_ros::ChangeBiasValue::Request &req, l3cam_ros::ChangeBiasValue::Response &res)
Definition: l3cam_ros_node.cpp:1302
streaming_status
@ streaming_status
Definition: l3cam_ros_utils.hpp:41
l3cam_ros::L3Cam::thermalDisconnected
void thermalDisconnected(int code)
Definition: l3cam_ros_node.cpp:2156
l3cam_ros::L3Cam::srv_get_device_temperatures_
ros::ServiceServer srv_get_device_temperatures_
Definition: l3cam_ros_node.hpp:291
l3cam_ros::L3Cam::libL3camStatus
bool libL3camStatus(l3cam_ros::LibL3camStatus::Request &req, l3cam_ros::LibL3camStatus::Response &res)
Definition: l3cam_ros_node.cpp:959
l3cam_ros::L3Cam::srv_get_local_server_address_
ros::ServiceServer srv_get_local_server_address_
Definition: l3cam_ros_node.hpp:278
l3cam_ros::L3Cam::changeAlliedCameraIntensityControllerTarget
bool changeAlliedCameraIntensityControllerTarget(l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Request &req, l3cam_ros::ChangeAlliedCameraIntensityControllerTarget::Response &res)
Definition: l3cam_ros_node.cpp:1734
l3cam_ros::L3Cam::getAlliedCameraBalanceWhiteAutoRate
bool getAlliedCameraBalanceWhiteAutoRate(l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Request &req, l3cam_ros::GetAlliedCameraBalanceWhiteAutoRate::Response &res)
Definition: l3cam_ros_node.cpp:1999
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
l3cam_ros::L3Cam::loadNetworkDefaultParams
void loadNetworkDefaultParams()
Definition: l3cam_ros_node.cpp:538
l3cam_ros::L3Cam::stopStream
bool stopStream(l3cam_ros::StopStream::Request &req, l3cam_ros::StopStream::Response &res)
Definition: l3cam_ros_node.cpp:1220
l3cam_ros::L3Cam::getAlliedCameraAutoWhiteBalance
bool getAlliedCameraAutoWhiteBalance(l3cam_ros::GetAlliedCameraAutoWhiteBalance::Request &req, l3cam_ros::GetAlliedCameraAutoWhiteBalance::Response &res)
Definition: l3cam_ros_node.cpp:1948
l3cam_ros::L3Cam::srv_get_allied_exposure_time_
ros::ServiceServer srv_get_allied_exposure_time_
Definition: l3cam_ros_node.hpp:349
l3cam_ros::L3Cam::setBiasShortRange
bool setBiasShortRange(l3cam_ros::SetBiasShortRange::Request &req, l3cam_ros::SetBiasShortRange::Response &res)
Definition: l3cam_ros_node.cpp:1290
l3cam_ros::L3Cam::changeAlliedCameraBalanceWhiteAutoRate
bool changeAlliedCameraBalanceWhiteAutoRate(l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Request &req, l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate::Response &res)
Definition: l3cam_ros_node.cpp:1686
l3cam_ros::L3Cam::srv_change_allied_intensity_controller_region_
ros::ServiceServer srv_change_allied_intensity_controller_region_
Definition: l3cam_ros_node.hpp:345
l3cam_ros::L3Cam::changeRgbCameraGain
bool changeRgbCameraGain(l3cam_ros::ChangeRgbCameraGain::Request &req, l3cam_ros::ChangeRgbCameraGain::Response &res)
Definition: l3cam_ros_node.cpp:1416
l3cam_ros::L3Cam::srv_stop_device_
ros::ServiceServer srv_stop_device_
Definition: l3cam_ros_node.hpp:288
l3cam_ros::L3Cam::getAlliedCameraGamma
bool getAlliedCameraGamma(l3cam_ros::GetAlliedCameraGamma::Request &req, l3cam_ros::GetAlliedCameraGamma::Response &res)
Definition: l3cam_ros_node.cpp:1868
l3cam_ros::L3Cam::srv_get_allied_balance_ratio_selector_
ros::ServiceServer srv_get_allied_balance_ratio_selector_
Definition: l3cam_ros_node.hpp:361
l3cam_ros::L3Cam::getDeviceTemperatures
bool getDeviceTemperatures(l3cam_ros::GetDeviceTemperatures::Request &req, l3cam_ros::GetDeviceTemperatures::Response &res)
Definition: l3cam_ros_node.cpp:1231
l3cam_ros::L3Cam::srv_change_rgb_contrast_
ros::ServiceServer srv_change_rgb_contrast_
Definition: l3cam_ros_node.hpp:314
l3cam_ros::L3Cam::srv_change_pointcloud_color_
ros::ServiceServer srv_change_pointcloud_color_
Definition: l3cam_ros_node.hpp:293
l3cam_ros::L3Cam::srv_change_polarimetric_black_level_
ros::ServiceServer srv_change_polarimetric_black_level_
Definition: l3cam_ros_node.hpp:304
l3cam_ros::L3Cam::m_polarimetric_sensor
sensor * m_polarimetric_sensor
Definition: l3cam_ros_node.hpp:399


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