31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/PolarimetricConfig.h"
35 #include <beamagine.h>
36 #include <beamErrors.h>
38 #include "l3cam_ros/GetSensorsAvailable.h"
39 #include "l3cam_ros/EnablePolarimetricCameraStreamProcessedImage.h"
40 #include "l3cam_ros/ChangePolarimetricCameraProcessType.h"
41 #include "l3cam_ros/ChangePolarimetricCameraBrightness.h"
42 #include "l3cam_ros/ChangePolarimetricCameraBlackLevel.h"
43 #include "l3cam_ros/EnablePolarimetricCameraAutoGain.h"
44 #include "l3cam_ros/ChangePolarimetricCameraAutoGainRange.h"
45 #include "l3cam_ros/ChangePolarimetricCameraGain.h"
46 #include "l3cam_ros/EnablePolarimetricCameraAutoExposureTime.h"
47 #include "l3cam_ros/ChangePolarimetricCameraAutoExposureTimeRange.h"
48 #include "l3cam_ros/ChangePolarimetricCameraExposureTime.h"
49 #include "l3cam_ros/ChangeStreamingProtocol.h"
50 #include "l3cam_ros/GetRtspPipeline.h"
52 #include "l3cam_ros/SensorDisconnected.h"
64 client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>(
"/L3Cam/l3cam_ros_node/get_sensors_available");
65 client_stream_processed_ = serviceClient<l3cam_ros::EnablePolarimetricCameraStreamProcessedImage>(
"/L3Cam/polarimetric_wide_stream/enable_polarimetric_stream_processed_image");
66 client_process_type_ = serviceClient<l3cam_ros::ChangePolarimetricCameraProcessType>(
"/L3Cam/polarimetric_wide_stream/change_polarimetric_process_type");
67 client_brightness_ = serviceClient<l3cam_ros::ChangePolarimetricCameraBrightness>(
"/L3Cam/l3cam_ros_node/change_polarimetric_brightness");
68 client_black_level_ = serviceClient<l3cam_ros::ChangePolarimetricCameraBlackLevel>(
"/L3Cam/l3cam_ros_node/change_polarimetric_black_level");
69 client_enable_auto_gain_ = serviceClient<l3cam_ros::EnablePolarimetricCameraAutoGain>(
"/L3Cam/l3cam_ros_node/enable_polarimetric_auto_gain");
70 client_auto_gain_range_ = serviceClient<l3cam_ros::ChangePolarimetricCameraAutoGainRange>(
"/L3Cam/l3cam_ros_node/change_polarimetric_auto_gain_range");
71 client_gain_ = serviceClient<l3cam_ros::ChangePolarimetricCameraGain>(
"/L3Cam/l3cam_ros_node/change_polarimetric_gain");
72 client_enable_auto_exposure_time_ = serviceClient<l3cam_ros::EnablePolarimetricCameraAutoExposureTime>(
"/L3Cam/l3cam_ros_node/enable_polarimetric_auto_exposure_time");
73 client_auto_exposure_time_range_ = serviceClient<l3cam_ros::ChangePolarimetricCameraAutoExposureTimeRange>(
"/L3Cam/l3cam_ros_node/change_polarimetric_auto_exposure_time_range");
74 client_exposure_time_ = serviceClient<l3cam_ros::ChangePolarimetricCameraExposureTime>(
"/L3Cam/l3cam_ros_node/change_polarimetric_exposure_time");
91 server_ =
new dynamic_reconfigure::Server<l3cam_ros::PolarimetricConfig>;
112 template <
typename T>
113 void loadParam(
const std::string ¶m_name, T ¶m_var,
const T &default_val)
115 std::string full_param_name;
119 if(!
getParam(full_param_name, param_var))
127 param_var = default_val;
250 int error = L3CAM_OK;
270 config.polarimetric_rtsp_pipeline =
"";
277 config.polarimetric_rtsp_pipeline =
"";
287 int error = L3CAM_OK;
352 int error = L3CAM_OK;
381 int error = L3CAM_OK;
410 int error = L3CAM_OK;
439 int error = L3CAM_OK;
468 int error = L3CAM_OK;
497 int error = L3CAM_OK;
539 int error = L3CAM_OK;
543 srv_gain_.request.gain = config.polarimetric_gain;
576 int error = L3CAM_OK;
605 int error = L3CAM_OK;
637 ROS_WARN_STREAM(this->
getNamespace() <<
" Polarimetric camera auto exposure time must be enabled to change auto exposure time range");
647 int error = L3CAM_OK;
684 int error = L3CAM_OK;
738 dynamic_reconfigure::Server<l3cam_ros::PolarimetricConfig> *
server_;
789 int main(
int argc,
char **argv)
791 ros::init(argc, argv,
"polarimetric_configuration");
797 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
803 int error = L3CAM_OK;
804 bool sensor_is_available =
false;
806 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
808 error =
node->srv_get_sensors_.response.error;
812 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
814 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_pol &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
816 sensor_is_available =
true;
832 if (sensor_is_available)
834 ROS_INFO(
"Polarimetric configuration is available");
841 node->setDynamicReconfigure();