31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/ThermalConfig.h"
35 #include <beamagine.h>
36 #include <beamErrors.h>
38 #include "l3cam_ros/GetSensorsAvailable.h"
39 #include "l3cam_ros/ChangeThermalCameraColormap.h"
40 #include "l3cam_ros/EnableThermalCameraTemperatureFilter.h"
41 #include "l3cam_ros/ChangeThermalCameraTemperatureFilter.h"
42 #include "l3cam_ros/ChangeThermalCameraProcessingPipeline.h"
43 #include "l3cam_ros/EnableThermalCameraTemperatureDataUdp.h"
44 #include "l3cam_ros/ChangeStreamingProtocol.h"
45 #include "l3cam_ros/GetRtspPipeline.h"
47 #include "l3cam_ros/SensorDisconnected.h"
58 client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>(
"/L3Cam/l3cam_ros_node/get_sensors_available");
59 client_colormap_ = serviceClient<l3cam_ros::ChangeThermalCameraColormap>(
"/L3Cam/l3cam_ros_node/change_thermal_colormap");
61 client_temperature_filter_ = serviceClient<l3cam_ros::ChangeThermalCameraTemperatureFilter>(
"/L3Cam/l3cam_ros_node/change_thermal_temperature_filter");
62 client_processing_pipeline_ = serviceClient<l3cam_ros::ChangeThermalCameraProcessingPipeline>(
"/L3Cam/l3cam_ros_node/change_thermal_processing_pipeline");
63 client_temperature_data_udp_ = serviceClient<l3cam_ros::EnableThermalCameraTemperatureDataUdp>(
"/L3Cam/l3cam_ros_node/enable_thermal_temperature_data_udp");
80 server_ =
new dynamic_reconfigure::Server<l3cam_ros::ThermalConfig>;
101 template <
typename T>
102 void loadParam(
const std::string ¶m_name, T ¶m_var,
const T &default_val)
104 std::string full_param_name;
108 if (!
getParam(full_param_name, param_var))
116 param_var = default_val;
183 int error = L3CAM_OK;
203 config.thermal_rtsp_pipeline =
"";
210 config.thermal_rtsp_pipeline =
"";
220 int error = L3CAM_OK;
267 int error = L3CAM_OK;
296 int error = L3CAM_OK;
325 int error = L3CAM_OK;
358 int error = L3CAM_OK;
387 int error = L3CAM_OK;
417 int error = L3CAM_OK;
470 dynamic_reconfigure::Server<l3cam_ros::ThermalConfig> *
server_;
505 int main(
int argc,
char **argv)
507 ros::init(argc, argv,
"thermal_configuration");
513 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
519 int error = L3CAM_OK;
520 bool sensor_is_available =
false;
522 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
524 error =
node->srv_get_sensors_.response.error;
528 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
530 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_thermal &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
532 sensor_is_available =
true;
548 if (sensor_is_available)
550 ROS_INFO(
"Thermal configuration is available");
557 node->setDynamicReconfigure();