33 #include <libL3Cam_allied.h>
34 #include <libL3Cam_econ.h>
35 #include <libL3Cam_polarimetric.h>
36 #include <libL3Cam_thermal.h>
37 #include <beamErrors.h>
39 #include "l3cam_ros/Sensor.h"
69 std::cout <<
"Terminating..." << std::endl;
77 std::cout <<
"Terminated." << std::endl;
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);
91 if (local_address ==
"" || device_address ==
"")
93 error = INITIALIZE(NULL, NULL);
97 error = INITIALIZE(&local_address[0], &device_address[0]);
124 <<
", serial number " << std::string(
m_devices[0].serial_number)
125 <<
", app version " << std::string(
m_devices[0].app_version));
128 error = GET_DEVICE_STATUS(
m_devices[0], &status);
138 for (
int i = 0; i < num_sensors; ++i)
145 case sensor_econ_rgb:
154 case sensor_allied_wide:
157 case sensor_allied_narrow:
160 case sensor_econ_wide:
166 ROS_INFO_STREAM(num_sensors << ((num_sensors == 1) ?
" sensor" :
" sensors") <<
" available");
175 int error = L3CAM_OK;
193 ROS_INFO(
"Device streaming ready\n");
438 if (error != L3CAM_OK)
446 template <
typename T>
449 std::string full_param_name;
453 if (!
getParam(full_param_name, param_var))
461 param_var = default_val;
535 ROS_INFO(
"Default parameters loaded");
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);
546 param(
"/ip_address", std::string(ip_address));
547 param(
"/netmask", std::string(netmask));
548 param(
"/gateway", std::string(gateway));
554 int pointcloud_color;
555 loadParam(
"pointcloud_color", pointcloud_color, 0);
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);
567 bool bias_short_range;
568 loadParam(
"bias_short_range", bias_short_range,
false);
575 int bias_value_right;
576 loadParam(
"bias_value_right", bias_value_right, 1580);
579 loadParam(
"bias_value_left", bias_value_left, 1380);
584 int autobias_value_right;
585 loadParam(
"autobias_value_right", autobias_value_right, 50);
587 int autobias_value_left;
588 loadParam(
"autobias_value_left", autobias_value_left, 50);
591 int lidar_streaming_protocol;
592 loadParam(
"lidar_streaming_protocol", lidar_streaming_protocol, 0);
593 if (lidar_streaming_protocol == 1)
598 std::string lidar_rtsp_pipeline;
599 loadParam(
"lidar_rtsp_pipeline", lidar_rtsp_pipeline, std::string(
""));
600 if (lidar_rtsp_pipeline !=
"")
602 char *pipeline = &lidar_rtsp_pipeline[0];
609 int polarimetric_brightness;
610 loadParam(
"polarimetric_brightness", polarimetric_brightness, 127);
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);
618 if (polarimetric_auto_gain)
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");
628 double polarimetric_gain;
629 loadParam(
"polarimetric_gain", polarimetric_gain, 24.0);
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)
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");
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");
649 int polarimetric_streaming_protocol;
650 loadParam(
"polarimetric_streaming_protocol", polarimetric_streaming_protocol, 0);
651 if (polarimetric_streaming_protocol == 1)
656 std::string polarimetric_rtsp_pipeline;
657 loadParam(
"polarimetric_rtsp_pipeline", polarimetric_rtsp_pipeline, std::string(
""));
658 if (polarimetric_rtsp_pipeline !=
"")
660 char *pipeline = &polarimetric_rtsp_pipeline[0];
668 param(
"/l3cam_ros_nod/rgb_brightness", rgb_brightness, 0);
671 param(
"/l3cam_ros_nod/rgb_contrast", rgb_contrast, 10);
674 param(
"/l3cam_ros_nod/rgb_saturation", rgb_saturation, 16);
677 loadParam(
"rgb_sharpness", rgb_sharpness, 16);
685 bool rgb_auto_white_balance;
686 loadParam(
"rgb_auto_white_balance", rgb_auto_white_balance,
true);
688 if (!rgb_auto_white_balance)
690 int rgb_white_balance;
691 loadParam(
"rgb_white_balance", rgb_white_balance, 5000);
694 bool rgb_auto_exposure_time;
695 loadParam(
"rgb_auto_exposure_time", rgb_auto_exposure_time,
true);
697 if (!rgb_auto_exposure_time)
699 int rgb_exposure_time;
700 loadParam(
"rgb_exposure_time", rgb_exposure_time, 156);
704 loadParam(
"rgb_resolution", rgb_resolution, 3);
707 loadParam(
"rgb_framerate", rgb_framerate, 10);
709 int rgb_streaming_protocol;
710 loadParam(
"rgb_streaming_protocol", rgb_streaming_protocol, 0);
711 if (rgb_streaming_protocol == 1)
716 std::string rgb_rtsp_pipeline;
717 loadParam(
"rgb_rtsp_pipeline", rgb_rtsp_pipeline, std::string(
""));
718 if (rgb_rtsp_pipeline !=
"")
720 char *pipeline = &rgb_rtsp_pipeline[0];
727 int thermal_colormap;
728 loadParam(
"thermal_colormap", thermal_colormap, 1);
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)
751 std::string thermal_rtsp_pipeline;
752 loadParam(
"thermal_rtsp_pipeline", thermal_rtsp_pipeline, std::string(
""));
753 if (thermal_rtsp_pipeline !=
"")
755 char *pipeline = &thermal_rtsp_pipeline[0];
762 double allied_wide_black_level;
763 loadParam(
"allied_wide_black_level", allied_wide_black_level, 0.);
765 bool allied_wide_auto_exposure_time;
766 loadParam(
"allied_wide_auto_exposure_time", allied_wide_auto_exposure_time,
false);
768 if (allied_wide_auto_exposure_time)
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");
778 double allied_wide_exposure_time;
779 loadParam(
"allied_wide_exposure_time", allied_wide_exposure_time, 4992.32);
782 bool allied_wide_auto_gain;
783 loadParam(
"allied_wide_auto_gain", allied_wide_auto_gain,
false);
785 if (allied_wide_auto_gain)
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.);
795 double allied_wide_gain;
796 loadParam(
"allied_wide_gain", allied_wide_gain, 0.);
799 double allied_wide_gamma;
800 loadParam(
"allied_wide_gamma", allied_wide_gamma, 1.);
802 double allied_wide_saturation;
803 loadParam(
"allied_wide_saturation", allied_wide_saturation, 1.);
805 double allied_wide_sharpness;
806 loadParam(
"allied_wide_sharpness", allied_wide_sharpness, 0.);
808 double allied_wide_hue;
809 loadParam(
"allied_wide_hue", allied_wide_hue, 0.);
811 int allied_wide_intensity_auto_precedence;
812 loadParam(
"allied_wide_intensity_auto_precedence", allied_wide_intensity_auto_precedence, 0);
814 bool allied_wide_auto_white_balance;
815 loadParam(
"allied_wide_auto_white_balance", allied_wide_auto_white_balance,
false);
817 int allied_wide_balance_ratio_selector;
818 loadParam(
"allied_wide_balance_ratio_selector", allied_wide_balance_ratio_selector, 0);
820 double allied_wide_balance_ratio;
821 loadParam(
"allied_wide_balance_ratio", allied_wide_balance_ratio, 2.35498);
823 double allied_wide_balance_white_auto_rate;
824 loadParam(
"allied_wide_balance_white_auto_rate", allied_wide_balance_white_auto_rate, 100.);
826 double allied_wide_balance_white_auto_tolerance;
827 loadParam(
"allied_wide_balance_white_auto_tolerance", allied_wide_balance_white_auto_tolerance, 5.);
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);
834 int allied_wide_intensity_controller_region;
835 loadParam(
"allied_wide_intensity_controller_region", allied_wide_intensity_controller_region, 0);
837 double allied_wide_intensity_controller_target;
838 loadParam(
"allied_wide_intensity_controller_target", allied_wide_intensity_controller_target, 50.);
840 int allied_wide_max_driver_buffers_count;
841 loadParam(
"allied_wide_max_driver_buffers_count", allied_wide_max_driver_buffers_count, 64);
843 int allied_wide_streaming_protocol;
844 loadParam(
"allied_wide_streaming_protocol", allied_wide_streaming_protocol, 0);
845 if (allied_wide_streaming_protocol == 1)
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 !=
"")
854 char *pipeline = &allied_wide_rtsp_pipeline[0];
861 double allied_narrow_black_level;
862 loadParam(
"allied_narrow_black_level", allied_narrow_black_level, 0.);
864 bool allied_narrow_auto_exposure_time;
865 loadParam(
"allied_narrow_auto_exposure_time", allied_narrow_auto_exposure_time,
false);
867 if (allied_narrow_auto_exposure_time)
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);
877 double allied_narrow_exposure_time;
878 loadParam(
"allied_narrow_exposure_time", allied_narrow_exposure_time, 4992.32);
881 bool allied_narrow_auto_gain;
882 loadParam(
"allied_narrow_auto_gain", allied_narrow_auto_gain,
false);
884 if (allied_narrow_auto_gain)
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.);
894 double allied_narrow_gain;
895 loadParam(
"allied_narrow_gain", allied_narrow_gain, 0.);
898 double allied_narrow_gamma;
899 loadParam(
"allied_narrow_gamma", allied_narrow_gamma, 1.);
901 double allied_narrow_saturation;
902 loadParam(
"allied_narrow_saturation", allied_narrow_saturation, 1.);
904 double allied_narrow_sharpness;
905 loadParam(
"allied_narrow_sharpness", allied_narrow_sharpness, 0.);
907 double allied_narrow_hue;
908 loadParam(
"allied_narrow_hue", allied_narrow_hue, 0.);
910 int allied_narrow_intensity_auto_precedence;
911 loadParam(
"allied_narrow_intensity_auto_precedence", allied_narrow_intensity_auto_precedence, 0);
913 bool allied_narrow_auto_white_balance;
914 loadParam(
"allied_narrow_auto_white_balance", allied_narrow_auto_white_balance,
false);
916 int allied_narrow_balance_ratio_selector;
917 loadParam(
"allied_narrow_balance_ratio_selector", allied_narrow_balance_ratio_selector, 0);
919 double allied_narrow_balance_ratio;
920 loadParam(
"allied_narrow_balance_ratio", allied_narrow_balance_ratio, 2.35498);
922 double allied_narrow_balance_white_auto_rate;
923 loadParam(
"allied_narrow_balance_white_auto_rate", allied_narrow_balance_white_auto_rate, 100.);
925 double allied_narrow_balance_white_auto_tolerance;
926 loadParam(
"allied_narrow_balance_white_auto_tolerance", allied_narrow_balance_white_auto_tolerance, 5.);
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);
933 int allied_narrow_intensity_controller_region;
934 loadParam(
"allied_narrow_intensity_controller_region", allied_narrow_intensity_controller_region, 0);
936 double allied_narrow_intensity_controller_target;
937 loadParam(
"allied_narrow_intensity_controller_target", allied_narrow_intensity_controller_target, 50.);
939 int allied_narrow_max_driver_buffers_count;
940 loadParam(
"allied_narrow_max_driver_buffers_count", allied_narrow_max_driver_buffers_count, 64);
942 int allied_narrow_streaming_protocol;
943 loadParam(
"allied_narrow_streaming_protocol", allied_narrow_streaming_protocol, 0);
944 if (allied_narrow_streaming_protocol == 1)
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 !=
"")
953 char *pipeline = &allied_narrow_rtsp_pipeline[0];
966 bool L3Cam::getVersion(l3cam_ros::GetVersion::Request &req, l3cam_ros::GetVersion::Response &res)
969 res.version = GET_VERSION();
973 bool L3Cam::initialize(l3cam_ros::Initialize::Request &req, l3cam_ros::Initialize::Response &res)
976 res.error = INITIALIZE(&req.local_address[0], &req.device_address[0]);
980 bool L3Cam::terminate(l3cam_ros::Terminate::Request &req, l3cam_ros::Terminate::Response &res)
1006 res.error = FIND_DEVICES(&
m_devices[0], &res.num_devices);
1013 res.local_ip_address = GET_LOCAL_SERVER_ADDRESS(
m_devices[0]);
1020 res.ip_address = std::string(
m_devices[0].ip_address);
1022 res.serial_number = std::string(
m_devices[0].serial_number);
1023 res.app_version = std::string(
m_devices[0].app_version);
1030 res.error = GET_DEVICE_STATUS(
m_devices[0], &res.system_status);
1038 res.sensors.resize(res.num_sensors);
1039 for (
int i = 0; i < res.num_sensors; ++i)
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;
1056 streamingProtocols protocol;
1057 switch (req.protocol)
1060 protocol = protocol_raw_udp;
1063 protocol = protocol_gstreamer;
1066 protocol = protocol_raw_udp;
1070 switch (req.sensor_type)
1072 case (
int)sensorTypes::sensor_lidar:
1076 case (
int)sensorTypes::sensor_pol:
1080 case (
int)sensorTypes::sensor_econ_rgb:
1084 case (
int)sensorTypes::sensor_thermal:
1088 case (
int)sensorTypes::sensor_allied_wide:
1092 case (
int)sensorTypes::sensor_allied_narrow:
1096 case (
int)sensorTypes::sensor_econ_wide:
1110 char *pipeline = NULL;
1111 switch (req.sensor_type)
1113 case (
int)sensorTypes::sensor_lidar:
1115 res.pipeline = std::string(pipeline);
1117 case (
int)sensorTypes::sensor_pol:
1119 res.pipeline = std::string(pipeline);
1121 case (
int)sensorTypes::sensor_econ_wide:
1123 res.pipeline = std::string(pipeline);
1125 case (
int)sensorTypes::sensor_thermal:
1127 res.pipeline = std::string(pipeline);
1129 case (
int)sensorTypes::sensor_allied_wide:
1131 res.pipeline = std::string(pipeline);
1133 case (
int)sensorTypes::sensor_allied_narrow:
1135 res.pipeline = std::string(pipeline);
1137 case (
int)sensorTypes::sensor_econ_rgb:
1139 res.pipeline = std::string(pipeline);
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);
1161 if (req.enable_dhcp)
1162 res.error = CHANGE_NETWORK_CONFIGURATION(
m_devices[0], NULL, NULL, NULL,
true);
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);
1234 int32_t *temperatures = (int32_t *)malloc(
sizeof(int32_t) * 11);
1235 int error = GET_DEVICE_TEMPERATURES(
m_devices[0], temperatures);
1237 if (error != L3CAM_OK)
1249 res.allied_wide_temp = 0;
1250 res.allied_narrow_temp = 0;
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;
1274 res.error = CHANGE_POINT_CLOUD_COLOR(
m_devices[0], req.visualization_color);
1280 res.error = CHANGE_POINT_CLOUD_COLOR_RANGE(
m_devices[0], req.min_value, req.max_value);
1286 res.error = CHANGE_DISTANCE_RANGE(
m_devices[0], req.min_value, req.max_value);
1292 res.error = SET_BIAS_SHORT_RANGE(
m_devices[0], req.enabled);
1298 res.error = ENABLE_AUTO_BIAS(
m_devices[0], req.enabled);
1304 res.error = CHANGE_BIAS_VALUE(
m_devices[0], req.index, req.bias);
1310 res.error = CHANGE_AUTOBIAS_VALUE(
m_devices[0], req.index, req.autobias);
1317 res.error = GET_AUTOBIAS_VALUE(
m_devices[0], req.index, gain);
1326 res.error = SET_POLARIMETRIC_CAMERA_DEFAULT_SETTINGS(
m_devices[0]);
1332 res.error = CHANGE_POLARIMETRIC_CAMERA_BRIGHTNESS(
m_devices[0], req.brightness);
1338 res.error = CHANGE_POLARIMETRIC_CAMERA_BLACK_LEVEL(
m_devices[0], req.black_level);
1344 res.error = ENABLE_POLARIMETRIC_CAMERA_AUTO_GAIN(
m_devices[0], req.enabled);
1350 res.error = CHANGE_POLARIMETRIC_CAMERA_AUTO_GAIN_RANGE(
m_devices[0], req.min_gain, req.max_gain);
1356 res.error = CHANGE_POLARIMETRIC_CAMERA_GAIN(
m_devices[0], req.gain);
1362 res.error = ENABLE_POLARIMETRIC_CAMERA_AUTO_EXPOSURE_TIME(
m_devices[0], req.enabled);
1368 res.error = CHANGE_POLARIMETRIC_CAMERA_AUTO_EXPOSURE_TIME_RANGE(
m_devices[0], req.min_exposure, req.max_exposure);
1374 res.error = CHANGE_POLARIMETRIC_CAMERA_EXPOSURE_TIME(
m_devices[0], req.exposure_time);
1382 res.error = SET_RGB_CAMERA_DEFAULT_SETTINGS(
m_devices[0]);
1388 res.error = CHANGE_RGB_CAMERA_BRIGHTNESS(
m_devices[0], req.brightness);
1394 res.error = CHANGE_RGB_CAMERA_CONTRAST(
m_devices[0], req.contrast);
1400 res.error = CHANGE_RGB_CAMERA_SATURATION(
m_devices[0], req.saturation);
1406 res.error = CHANGE_RGB_CAMERA_SHARPNESS(
m_devices[0], req.sharpness);
1412 res.error = CHANGE_RGB_CAMERA_GAMMA(
m_devices[0], req.gamma);
1418 res.error = CHANGE_RGB_CAMERA_GAIN(
m_devices[0], req.gain);
1424 res.error = ENABLE_RGB_CAMERA_AUTO_WHITE_BALANCE(
m_devices[0], req.enabled);
1430 res.error = CHANGE_RGB_CAMERA_WHITE_BALANCE(
m_devices[0], req.white_balance);
1436 res.error = ENABLE_RGB_CAMERA_AUTO_EXPOSURE_TIME(
m_devices[0], req.enabled);
1442 res.error = CHANGE_RGB_CAMERA_EXPOSURE_TIME(
m_devices[0], req.exposure_time);
1449 res.error = CHANGE_THERMAL_CAMERA_COLORMAP(
m_devices[0], (newThermalTypes)req.colormap);
1455 res.error = ENABLE_THERMAL_CAMERA_TEMPERATURE_FILTER(
m_devices[0], req.enabled);
1461 res.error = CHANGE_THERMAL_CAMERA_TEMPERATURE_FILTER(
m_devices[0], req.min_temperature, req.max_temperature);
1467 res.error = CHANGE_THERMAL_CAMERA_PROCESSING_PIPELINE(
m_devices[0], req.pipeline);
1473 res.error = ENABLE_THERMAL_CAMERA_TEMPERATURE_DATA_UDP(
m_devices[0], req.enabled);
1480 switch (req.allied_type)
1482 case alliedCamerasIds::wide_camera:
1485 case alliedCamerasIds::narrow_camera:
1489 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1496 switch (req.allied_type)
1498 case alliedCamerasIds::wide_camera:
1501 case alliedCamerasIds::narrow_camera:
1505 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1512 switch (req.allied_type)
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);
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);
1521 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1528 switch (req.allied_type)
1530 case alliedCamerasIds::wide_camera:
1533 case alliedCamerasIds::narrow_camera:
1537 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1544 switch (req.allied_type)
1546 case alliedCamerasIds::wide_camera:
1549 case alliedCamerasIds::narrow_camera:
1553 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1560 switch (req.allied_type)
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);
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);
1569 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1576 switch (req.allied_type)
1578 case alliedCamerasIds::wide_camera:
1581 case alliedCamerasIds::narrow_camera:
1585 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1592 switch (req.allied_type)
1594 case alliedCamerasIds::wide_camera:
1597 case alliedCamerasIds::narrow_camera:
1601 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1608 switch (req.allied_type)
1610 case alliedCamerasIds::wide_camera:
1613 case alliedCamerasIds::narrow_camera:
1617 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1624 switch (req.allied_type)
1626 case alliedCamerasIds::wide_camera:
1629 case alliedCamerasIds::narrow_camera:
1633 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1640 switch (req.allied_type)
1642 case alliedCamerasIds::wide_camera:
1645 case alliedCamerasIds::narrow_camera:
1649 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1656 switch (req.allied_type)
1658 case alliedCamerasIds::wide_camera:
1661 case alliedCamerasIds::narrow_camera:
1665 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1672 switch (req.allied_type)
1674 case alliedCamerasIds::wide_camera:
1677 case alliedCamerasIds::narrow_camera:
1681 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1688 switch (req.allied_type)
1690 case alliedCamerasIds::wide_camera:
1693 case alliedCamerasIds::narrow_camera:
1697 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1704 switch (req.allied_type)
1706 case alliedCamerasIds::wide_camera:
1709 case alliedCamerasIds::narrow_camera:
1713 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1720 switch (req.allied_type)
1722 case alliedCamerasIds::wide_camera:
1725 case alliedCamerasIds::narrow_camera:
1729 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1736 switch (req.allied_type)
1738 case alliedCamerasIds::wide_camera:
1741 case alliedCamerasIds::narrow_camera:
1745 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1752 switch (req.allied_type)
1754 case alliedCamerasIds::wide_camera:
1757 case alliedCamerasIds::narrow_camera:
1761 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1768 switch (req.allied_type)
1770 case alliedCamerasIds::wide_camera:
1773 case alliedCamerasIds::narrow_camera:
1777 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1785 switch (req.allied_type)
1787 case alliedCamerasIds::wide_camera:
1790 case alliedCamerasIds::narrow_camera:
1794 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1796 res.enabled = enabled;
1803 switch (req.allied_type)
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);
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);
1812 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1819 switch (req.allied_type)
1821 case alliedCamerasIds::wide_camera:
1824 case alliedCamerasIds::narrow_camera:
1828 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1836 switch (req.allied_type)
1838 case alliedCamerasIds::wide_camera:
1841 case alliedCamerasIds::narrow_camera:
1845 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1847 res.enabled = enabled;
1854 switch (req.allied_type)
1856 case alliedCamerasIds::wide_camera:
1859 case alliedCamerasIds::narrow_camera:
1863 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1870 switch (req.allied_type)
1872 case alliedCamerasIds::wide_camera:
1875 case alliedCamerasIds::narrow_camera:
1879 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1886 switch (req.allied_type)
1888 case alliedCamerasIds::wide_camera:
1891 case alliedCamerasIds::narrow_camera:
1895 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1902 switch (req.allied_type)
1904 case alliedCamerasIds::wide_camera:
1907 case alliedCamerasIds::narrow_camera:
1911 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1918 switch (req.allied_type)
1920 case alliedCamerasIds::wide_camera:
1923 case alliedCamerasIds::narrow_camera:
1927 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1934 switch (req.allied_type)
1936 case alliedCamerasIds::wide_camera:
1939 case alliedCamerasIds::narrow_camera:
1943 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1951 switch (req.allied_type)
1953 case alliedCamerasIds::wide_camera:
1956 case alliedCamerasIds::narrow_camera:
1960 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1962 res.enabled = enabled;
1969 switch (req.allied_type)
1971 case alliedCamerasIds::wide_camera:
1974 case alliedCamerasIds::narrow_camera:
1978 res.error = L3CAM_VALUE_OUT_OF_RANGE;
1985 switch (req.allied_type)
1987 case alliedCamerasIds::wide_camera:
1990 case alliedCamerasIds::narrow_camera:
1994 res.error = L3CAM_VALUE_OUT_OF_RANGE;
2001 switch (req.allied_type)
2003 case alliedCamerasIds::wide_camera:
2006 case alliedCamerasIds::narrow_camera:
2010 res.error = L3CAM_VALUE_OUT_OF_RANGE;
2017 switch (req.allied_type)
2019 case alliedCamerasIds::wide_camera:
2022 case alliedCamerasIds::narrow_camera:
2026 res.error = L3CAM_VALUE_OUT_OF_RANGE;
2033 switch (req.allied_type)
2035 case alliedCamerasIds::wide_camera:
2038 case alliedCamerasIds::narrow_camera:
2042 res.error = L3CAM_VALUE_OUT_OF_RANGE;
2049 switch (req.allied_type)
2051 case alliedCamerasIds::wide_camera:
2054 case alliedCamerasIds::narrow_camera:
2058 res.error = L3CAM_VALUE_OUT_OF_RANGE;
2065 switch (req.allied_type)
2067 case alliedCamerasIds::wide_camera:
2070 case alliedCamerasIds::narrow_camera:
2074 res.error = L3CAM_VALUE_OUT_OF_RANGE;
2081 switch (req.allied_type)
2083 case alliedCamerasIds::wide_camera:
2086 case alliedCamerasIds::narrow_camera:
2090 res.error = L3CAM_VALUE_OUT_OF_RANGE;
2210 int errort = *error;
2214 case ERROR_LIDAR_TIMED_OUT:
2217 case ERROR_THERMAL_CAMERA_TIMEOUT:
2227 ros::init(argc, argv,
"l3cam_ros_node");
2233 int error = L3CAM_OK;
2251 if (error == L3CAM_TIMEOUT_ERROR)