31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/AlliedWideConfig.h"
35 #include <beamagine.h>
36 #include <beamErrors.h>
38 #include "l3cam_ros/GetSensorsAvailable.h"
39 #include "l3cam_ros/ChangeAlliedCameraExposureTime.h"
40 #include "l3cam_ros/EnableAlliedCameraAutoExposureTime.h"
41 #include "l3cam_ros/ChangeAlliedCameraAutoExposureTimeRange.h"
42 #include "l3cam_ros/ChangeAlliedCameraGain.h"
43 #include "l3cam_ros/EnableAlliedCameraAutoGain.h"
44 #include "l3cam_ros/ChangeAlliedCameraAutoGainRange.h"
45 #include "l3cam_ros/ChangeAlliedCameraGamma.h"
46 #include "l3cam_ros/ChangeAlliedCameraSaturation.h"
47 #include "l3cam_ros/ChangeAlliedCameraHue.h"
48 #include "l3cam_ros/ChangeAlliedCameraIntensityAutoPrecedence.h"
49 #include "l3cam_ros/EnableAlliedCameraAutoWhiteBalance.h"
50 #include "l3cam_ros/ChangeAlliedCameraBalanceRatioSelector.h"
51 #include "l3cam_ros/ChangeAlliedCameraBalanceRatio.h"
52 #include "l3cam_ros/ChangeAlliedCameraBalanceWhiteAutoRate.h"
53 #include "l3cam_ros/ChangeAlliedCameraBalanceWhiteAutoTolerance.h"
54 #include "l3cam_ros/ChangeAlliedCameraIntensityControllerRegion.h"
55 #include "l3cam_ros/ChangeAlliedCameraIntensityControllerTarget.h"
56 #include "l3cam_ros/ChangeStreamingProtocol.h"
57 #include "l3cam_ros/GetRtspPipeline.h"
58 #include "l3cam_ros/GetAlliedCameraExposureTime.h"
59 #include "l3cam_ros/GetAlliedCameraGain.h"
61 #include "l3cam_ros/SensorDisconnected.h"
73 client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>(
"/L3Cam/l3cam_ros_node/get_sensors_available");
74 client_exposure_time_ = serviceClient<l3cam_ros::ChangeAlliedCameraExposureTime>(
"/L3Cam/l3cam_ros_node/change_allied_exposure_time");
76 client_auto_exposure_time_range_ = serviceClient<l3cam_ros::ChangeAlliedCameraAutoExposureTimeRange>(
"/L3Cam/l3cam_ros_node/change_allied_auto_exposure_time_range");
77 client_gain_ = serviceClient<l3cam_ros::ChangeAlliedCameraGain>(
"/L3Cam/l3cam_ros_node/change_allied_gain");
78 client_enable_auto_gain_ = serviceClient<l3cam_ros::EnableAlliedCameraAutoGain>(
"/L3Cam/l3cam_ros_node/enable_allied_auto_gain");
79 client_auto_gain_range_ = serviceClient<l3cam_ros::ChangeAlliedCameraAutoGainRange>(
"/L3Cam/l3cam_ros_node/change_allied_auto_gain_range");
80 client_gamma_ = serviceClient<l3cam_ros::ChangeAlliedCameraGamma>(
"/L3Cam/l3cam_ros_node/change_allied_gamma");
81 client_saturation_ = serviceClient<l3cam_ros::ChangeAlliedCameraSaturation>(
"/L3Cam/l3cam_ros_node/change_allied_saturation");
82 client_hue_ = serviceClient<l3cam_ros::ChangeAlliedCameraHue>(
"/L3Cam/l3cam_ros_node/change_allied_hue");
83 client_intensity_auto_precedence_ = serviceClient<l3cam_ros::ChangeAlliedCameraIntensityAutoPrecedence>(
"/L3Cam/l3cam_ros_node/change_allied_intensity_auto_precedence");
85 client_balance_ratio_selector_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceRatioSelector>(
"/L3Cam/l3cam_ros_node/change_allied_balance_ratio_selector");
86 client_balance_ratio_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceRatio>(
"/L3Cam/l3cam_ros_node/change_allied_balance_ratio");
87 client_balance_white_auto_rate_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoRate>(
"/L3Cam/l3cam_ros_node/change_allied_balance_white_auto_rate");
88 client_balance_white_auto_tolerance_ = serviceClient<l3cam_ros::ChangeAlliedCameraBalanceWhiteAutoTolerance>(
"/L3Cam/l3cam_ros_node/change_allied_balance_white_auto_tolerance");
89 client_intensity_controller_region_ = serviceClient<l3cam_ros::ChangeAlliedCameraIntensityControllerRegion>(
"/L3Cam/l3cam_ros_node/change_allied_intensity_controller_region");
90 client_intensity_controller_target_ = serviceClient<l3cam_ros::ChangeAlliedCameraIntensityControllerTarget>(
"/L3Cam/l3cam_ros_node/change_allied_intensity_controller_target");
93 client_get_exposure_time_ = serviceClient<l3cam_ros::GetAlliedCameraExposureTime>(
"/L3Cam/l3cam_ros_node/get_allied_exposure_time");
94 client_get_gain_ = serviceClient<l3cam_ros::GetAlliedCameraGain>(
"/L3Cam/l3cam_ros_node/get_allied_gain");
109 server_ =
new dynamic_reconfigure::Server<l3cam_ros::AlliedWideConfig>;
130 template <
typename T>
131 void loadParam(
const std::string ¶m_name, T ¶m_var,
const T &default_val)
133 std::string full_param_name;
137 if (!
getParam(full_param_name, param_var))
145 param_var = default_val;
345 int error = L3CAM_OK;
365 config.allied_wide_rtsp_pipeline =
"";
372 config.allied_wide_rtsp_pipeline =
"";
382 int error = L3CAM_OK;
468 int error = L3CAM_OK;
470 if (!config.allied_wide_auto_exposure_time)
506 int error = L3CAM_OK;
557 int error = L3CAM_OK;
559 if (config.allied_wide_auto_exposure_time)
590 ROS_WARN_STREAM(this->
getNamespace() <<
" Allied Wide camera auto exposure time must be enabled to change auto exposure time range");
600 int error = L3CAM_OK;
602 if (!config.allied_wide_auto_gain)
604 srv_gain_.request.gain = config.allied_wide_gain;
605 srv_gain_.request.allied_type = alliedCamerasIds::wide_camera;
638 int error = L3CAM_OK;
651 srv_get_gain_.request.allied_type = alliedCamerasIds::wide_camera;
689 int error = L3CAM_OK;
691 if (config.allied_wide_auto_gain)
732 int error = L3CAM_OK;
734 srv_gamma_.request.gamma = config.allied_wide_gamma;
735 srv_gamma_.request.allied_type = alliedCamerasIds::wide_camera;
762 int error = L3CAM_OK;
790 int callHue(l3cam_ros::AlliedWideConfig &config)
792 int error = L3CAM_OK;
794 srv_hue_.request.hue = config.allied_wide_hue;
795 srv_hue_.request.allied_type = alliedCamerasIds::wide_camera;
822 int error = L3CAM_OK;
852 int error = L3CAM_OK;
882 int error = L3CAM_OK;
912 int error = L3CAM_OK;
942 int error = L3CAM_OK;
972 int error = L3CAM_OK;
1002 int error = L3CAM_OK;
1032 int error = L3CAM_OK;
1062 int error = L3CAM_OK;
1115 dynamic_reconfigure::Server<l3cam_ros::AlliedWideConfig> *
server_;
1193 ros::init(argc, argv,
"allied_wide_configuration");
1199 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
1205 int error = L3CAM_OK;
1206 bool sensor_is_available =
false;
1208 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
1210 error =
node->srv_get_sensors_.response.error;
1214 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
1216 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_allied_wide &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
1218 sensor_is_available =
true;
1234 if (sensor_is_available)
1236 ROS_INFO(
"Allied Wide camera configuration is available");
1243 node->setDynamicReconfigure();