thermal_configuration.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 <iostream>
29 #include <ros/ros.h>
30 
31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/ThermalConfig.h"
33 
34 #include <libL3Cam.h>
35 #include <beamagine.h>
36 #include <beamErrors.h>
37 
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"
46 
47 #include "l3cam_ros/SensorDisconnected.h"
48 
49 #include "l3cam_ros_utils.hpp"
50 
51 namespace l3cam_ros
52 {
54  {
55  public:
56  explicit ThermalConfiguration() : ros::NodeHandle("~")
57  {
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");
60  client_enable_temperature_filter_ = serviceClient<l3cam_ros::EnableThermalCameraTemperatureFilter>("/L3Cam/l3cam_ros_node/enable_thermal_temperature_filter");
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");
64  client_change_streaming_protocol_ = serviceClient<l3cam_ros::ChangeStreamingProtocol>("/L3Cam/l3cam_ros_node/change_streaming_protocol");
65  client_get_rtsp_pipeline_ = serviceClient<l3cam_ros::GetRtspPipeline>("/L3Cam/l3cam_ros_node/get_rtsp_pipeline");
66 
68 
69  // Create service server
71 
72  m_default_configured = false;
73  m_shutdown_requested = false;
74  }
75 
77  {
78  // Dynamic reconfigure callback
79  // server_ is a pointer so we only declare it if sensor is available and reconfigure should be available
80  server_ = new dynamic_reconfigure::Server<l3cam_ros::ThermalConfig>;
81  server_->setCallback(std::bind(&ThermalConfiguration::parametersCallback, this, std::placeholders::_1, std::placeholders::_2));
82  }
83 
84  void spin()
85  {
86  while (ros::ok() && !m_shutdown_requested)
87  {
88  ros::spinOnce();
89  ros::Duration(0.1).sleep();
90  }
91 
92  ros::shutdown();
93  }
94 
96  l3cam_ros::GetSensorsAvailable srv_get_sensors_;
97 
99 
100  private:
101  template <typename T>
102  void loadParam(const std::string &param_name, T &param_var, const T &default_val)
103  {
104  std::string full_param_name;
105 
106  if (searchParam(param_name, full_param_name))
107  {
108  if (!getParam(full_param_name, param_var))
109  {
110  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
111  }
112  }
113  else
114  {
115  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
116  param_var = default_val;
117  }
118  }
119 
121  {
122  // Get and save parameters
123  loadParam("timeout_secs", timeout_secs_, 60);
124  loadParam("thermal_colormap", thermal_colormap_, 1);
125  loadParam("thermal_temperature_filter", thermal_temperature_filter_, false);
126  loadParam("thermal_temperature_filter_min", thermal_temperature_filter_min_, 0);
127  loadParam("thermal_temperature_filter_max", thermal_temperature_filter_max_, 50);
128  loadParam("thermal_processing_pipeline", thermal_processing_pipeline_, 1);
129  loadParam("thermal_temperature_data_udp", thermal_temperature_data_udp_, false);
130  loadParam("thermal_streaming_protocol", thermal_streaming_protocol_, 0);
131  }
132 
133  void configureDefault(l3cam_ros::ThermalConfig &config)
134  {
135  // Configure default params to dynamix reconfigure if inside range
136  if (thermal_colormap_ >= 0 || thermal_colormap_ <= 8)
137  {
138  config.thermal_colormap = thermal_colormap_;
139  }
140  else
141  {
142  thermal_colormap_ = config.thermal_colormap;
143  }
144 
145  config.thermal_temperature_filter = thermal_temperature_filter_;
146 
148  {
149  config.thermal_temperature_filter_min = thermal_temperature_filter_min_;
150  }
151  else
152  {
153  thermal_temperature_filter_min_ = config.thermal_temperature_filter_min;
154  }
156  {
157  config.thermal_temperature_filter_max = thermal_temperature_filter_max_;
158  }
159  else
160  {
161  thermal_temperature_filter_max_ = config.thermal_temperature_filter_max;
162  }
163 
165  {
166  config.thermal_processing_pipeline = thermal_processing_pipeline_;
167  }
168  else
169  {
170  thermal_processing_pipeline_ = config.thermal_processing_pipeline;
171  }
172 
174  {
175  config.thermal_streaming_protocol = thermal_streaming_protocol_;
176  }
177  else
178  {
179  thermal_streaming_protocol_ = config.thermal_streaming_protocol;
180  }
181 
182  // Get pipeline
183  int error = L3CAM_OK;
184  ros::Duration timeout_duration(timeout_secs_);
185  if (!client_get_rtsp_pipeline_.waitForExistence(timeout_duration))
186  {
187  ROS_ERROR_STREAM(this->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
188  }
189  else
190  {
191  srv_get_rtsp_pipeline_.request.sensor_type = (int)sensorTypes::sensor_thermal;
193  {
194  error = srv_get_rtsp_pipeline_.response.error;
195  if (!error)
196  {
198  config.thermal_rtsp_pipeline = srv_get_rtsp_pipeline_.response.pipeline;
199  }
200  else
201  {
202  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting RTSP pipeline: " << getErrorDescription(error));
203  config.thermal_rtsp_pipeline = "";
205  }
206  }
207  else
208  {
209  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service get_rtsp_pipeline");
210  config.thermal_rtsp_pipeline = "";
212  }
213  }
214 
215  m_default_configured = true;
216  }
217 
218  void parametersCallback(l3cam_ros::ThermalConfig &config, uint32_t level)
219  {
220  int error = L3CAM_OK;
221 
223  {
224  configureDefault(config);
225  }
226  else
227  {
228  // Filter by parameter and call service
229  switch (level)
230  {
231  case 0: // thermal_colormap
232  error = callThermalColormap(config);
233  break;
234  case 1: // thermal_temperature_filter
235  error = callThermalTemperatureFilter(config);
236  break;
237  case 2: // thermal_temperature_filter_min
238  error = callThermalTemperatureFilterRange(config);
239  break;
240  case 3: // thermal_temperature_filter_max
241  error = callThermalTemperatureFilterRange(config);
242  break;
243  case 4: // thermal_processing_pipeline
244  error = callThermalProcessingPipeline(config);
245  break;
246  case 5: // thermal_temperature_data_udp
247  error = callThermalTemperatureDataUdp(config);
248  break;
249  case 6: // thermal_streaming_protocol
250  error = callThermalStreamingProtocol(config);
251  break;
252  case 7: // thermal_rtsp_pipeline
253  error = callThermalRtspPipeline(config);
254  break;
255  }
256  }
257 
258  if (error)
259  {
260  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while changing parameter: " << getErrorDescription(error));
261  }
262  }
263 
264  // Service calls
265  int callThermalColormap(l3cam_ros::ThermalConfig &config)
266  {
267  int error = L3CAM_OK;
268 
269  srv_colormap_.request.colormap = config.thermal_colormap;
271  {
272  error = srv_colormap_.response.error;
273  if (!error)
274  {
275  // Parameter changed successfully, save value
276  thermal_colormap_ = config.thermal_colormap;
277  }
278  else
279  {
280  // Parameter could not be changed, reset parameter to value before change
281  config.thermal_colormap = thermal_colormap_;
282  }
283  }
284  else
285  {
286  // Service could not be called, reset parameter to value before change
287  config.thermal_colormap = thermal_colormap_;
289  }
290 
291  return error;
292  }
293 
294  int callThermalTemperatureFilter(l3cam_ros::ThermalConfig &config)
295  {
296  int error = L3CAM_OK;
297 
298  srv_enable_temperature_filter_.request.enabled = config.thermal_temperature_filter;
300  {
301  error = srv_enable_temperature_filter_.response.error;
302  if (!error)
303  {
304  // Parameter changed successfully, save value
305  thermal_temperature_filter_ = config.thermal_temperature_filter;
306  }
307  else
308  {
309  // Parameter could not be changed, reset parameter to value before change
310  config.thermal_temperature_filter = thermal_temperature_filter_;
311  }
312  }
313  else
314  {
315  // Service could not be called, reset parameter to value before change
316  config.thermal_temperature_filter = thermal_temperature_filter_;
318  }
319 
320  return error;
321  }
322 
323  int callThermalTemperatureFilterRange(l3cam_ros::ThermalConfig &config)
324  {
325  int error = L3CAM_OK;
326 
327  srv_temperature_filter_.request.min_temperature = config.thermal_temperature_filter_min;
328  srv_temperature_filter_.request.max_temperature = config.thermal_temperature_filter_max;
330  {
331  error = srv_temperature_filter_.response.error;
332  if (!error)
333  {
334  // Parameter changed successfully, save value
335  thermal_temperature_filter_min_ = config.thermal_temperature_filter_min;
336  thermal_temperature_filter_max_ = config.thermal_temperature_filter_max;
337  }
338  else
339  {
340  // Parameter could not be changed, reset parameter to value before change
341  config.thermal_temperature_filter_min = thermal_temperature_filter_min_;
342  config.thermal_temperature_filter_max = thermal_temperature_filter_max_;
343  }
344  }
345  else
346  {
347  // Service could not be called, reset parameter to value before change
348  config.thermal_temperature_filter_min = thermal_temperature_filter_min_;
349  config.thermal_temperature_filter_max = thermal_temperature_filter_max_;
351  }
352 
353  return error;
354  }
355 
356  int callThermalProcessingPipeline(l3cam_ros::ThermalConfig &config)
357  {
358  int error = L3CAM_OK;
359 
360  srv_processing_pipeline_.request.pipeline = config.thermal_processing_pipeline;
362  {
363  error = srv_processing_pipeline_.response.error;
364  if (!error)
365  {
366  // Parameter changed successfully, save value
367  thermal_processing_pipeline_ = config.thermal_processing_pipeline;
368  }
369  else
370  {
371  // Parameter could not be changed, reset parameter to value before change
372  config.thermal_processing_pipeline = thermal_processing_pipeline_;
373  }
374  }
375  else
376  {
377  // Service could not be called, reset parameter to value before change
378  config.thermal_processing_pipeline = thermal_processing_pipeline_;
380  }
381 
382  return error;
383  }
384 
385  int callThermalTemperatureDataUdp(l3cam_ros::ThermalConfig &config)
386  {
387  int error = L3CAM_OK;
388 
389  srv_temperature_data_udp_.request.enabled = config.thermal_temperature_data_udp;
391  {
392  error = srv_temperature_data_udp_.response.error;
393  if (!error)
394  {
395  // Parameter changed successfully, save value
396  thermal_temperature_data_udp_ = config.thermal_temperature_data_udp;
397  }
398  else
399  {
400  // Parameter could not be changed, reset parameter to value before change
401  config.thermal_temperature_data_udp = thermal_temperature_data_udp_;
402  }
403  }
404  else
405  {
406  // Service could not be called, reset parameter to value before change
407  config.thermal_temperature_data_udp = thermal_temperature_data_udp_;
409  }
410 
411  return error;
412  }
413 
414 
415  int callThermalStreamingProtocol(l3cam_ros::ThermalConfig &config)
416  {
417  int error = L3CAM_OK;
418 
419  srv_change_streaming_protocol_.request.protocol = config.thermal_streaming_protocol;
420  srv_change_streaming_protocol_.request.sensor_type = (int)sensorTypes::sensor_thermal;
422  {
423  error = srv_change_streaming_protocol_.response.error;
424  if (!error)
425  {
426  // Parameter changed successfully, save value
427  thermal_streaming_protocol_ = config.thermal_streaming_protocol;
428  }
429  else
430  {
431  // Parameter could not be changed, reset parameter to value before change
432  config.thermal_streaming_protocol = thermal_streaming_protocol_;
433  }
434  }
435  else
436  {
437  // Service could not be called, reset parameter to value before change
438  config.thermal_streaming_protocol = thermal_streaming_protocol_;
440  }
441 
442  return error;
443  }
444 
445  int callThermalRtspPipeline(l3cam_ros::ThermalConfig &config)
446  {
447  // Read-only
448  ROS_WARN_STREAM(this->getNamespace() << " The RTSP Pipeline parameter is read-only, only changeable at launch");
449  config.thermal_rtsp_pipeline = thermal_rtsp_pipeline_;
450 
451  return L3CAM_OK;
452  }
453 
454  bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
455  {
456  ROS_BMG_UNUSED(res);
457  if (req.code == 0)
458  {
459  ROS_INFO_STREAM("Exiting " << this->getNamespace() << " cleanly.");
460  }
461  else
462  {
463  ROS_WARN_STREAM("Exiting " << this->getNamespace() << ". Sensor got disconnected with error " << req.code << ": " << getErrorDescription(req.code));
464  }
465 
466  m_shutdown_requested = true;
467  return true;
468  }
469 
470  dynamic_reconfigure::Server<l3cam_ros::ThermalConfig> *server_;
471 
473  l3cam_ros::ChangeThermalCameraColormap srv_colormap_;
475  l3cam_ros::EnableThermalCameraTemperatureFilter srv_enable_temperature_filter_;
477  l3cam_ros::ChangeThermalCameraTemperatureFilter srv_temperature_filter_;
479  l3cam_ros::ChangeThermalCameraProcessingPipeline srv_processing_pipeline_;
481  l3cam_ros::EnableThermalCameraTemperatureDataUdp srv_temperature_data_udp_;
483  l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_;
485  l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_;
486 
488 
497 
500 
501  }; // class ThermalConfiguration
502 
503 } // namespace l3cam_ros
504 
505 int main(int argc, char **argv)
506 {
507  ros::init(argc, argv, "thermal_configuration");
508 
510 
511  // Check if service is available
512  ros::Duration timeout_duration(node->timeout_secs_);
513  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
514  {
515  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
517  }
518 
519  int error = L3CAM_OK;
520  bool sensor_is_available = false;
521  // Shutdown if sensor is not available or if error returned
522  if (node->client_get_sensors_.call(node->srv_get_sensors_))
523  {
524  error = node->srv_get_sensors_.response.error;
525 
526  if (!error)
527  {
528  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
529  {
530  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_thermal && node->srv_get_sensors_.response.sensors[i].sensor_available)
531  {
532  sensor_is_available = true;
533  }
534  }
535  }
536  else
537  {
538  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability: " << getErrorDescription(error));
539  return error;
540  }
541  }
542  else
543  {
544  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
546  }
547 
548  if (sensor_is_available)
549  {
550  ROS_INFO("Thermal configuration is available");
551  }
552  else
553  {
554  return 0;
555  }
556 
557  node->setDynamicReconfigure();
558 
559  node->spin();
560 
561  ros::shutdown();
562  return 0;
563 }
l3cam_ros::ThermalConfiguration::thermal_rtsp_pipeline_
std::string thermal_rtsp_pipeline_
Definition: thermal_configuration.cpp:496
l3cam_ros::ThermalConfiguration
Definition: thermal_configuration.cpp:53
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
l3cam_ros::ThermalConfiguration::client_colormap_
ros::ServiceClient client_colormap_
Definition: thermal_configuration.cpp:472
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::ThermalConfiguration::ThermalConfiguration
ThermalConfiguration()
Definition: thermal_configuration.cpp:56
l3cam_ros::ThermalConfiguration::thermal_temperature_filter_
bool thermal_temperature_filter_
Definition: thermal_configuration.cpp:490
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
l3cam_ros::ThermalConfiguration::client_temperature_filter_
ros::ServiceClient client_temperature_filter_
Definition: thermal_configuration.cpp:476
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
l3cam_ros::ThermalConfiguration::timeout_secs_
int timeout_secs_
Definition: thermal_configuration.cpp:98
ros.h
l3cam_ros::ThermalConfiguration::spin
void spin()
Definition: thermal_configuration.cpp:84
ros::spinOnce
ROSCPP_DECL void spinOnce()
l3cam_ros::ThermalConfiguration::srv_enable_temperature_filter_
l3cam_ros::EnableThermalCameraTemperatureFilter srv_enable_temperature_filter_
Definition: thermal_configuration.cpp:475
l3cam_ros::ThermalConfiguration::client_temperature_data_udp_
ros::ServiceClient client_temperature_data_udp_
Definition: thermal_configuration.cpp:480
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
l3cam_ros::ThermalConfiguration::thermal_processing_pipeline_
int thermal_processing_pipeline_
Definition: thermal_configuration.cpp:493
l3cam_ros::ThermalConfiguration::server_
dynamic_reconfigure::Server< l3cam_ros::ThermalConfig > * server_
Definition: thermal_configuration.cpp:470
l3cam_ros::ThermalConfiguration::m_shutdown_requested
bool m_shutdown_requested
Definition: thermal_configuration.cpp:499
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros::ThermalConfiguration::srv_processing_pipeline_
l3cam_ros::ChangeThermalCameraProcessingPipeline srv_processing_pipeline_
Definition: thermal_configuration.cpp:479
l3cam_ros
Definition: l3cam_ros_node.hpp:133
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
l3cam_ros::ThermalConfiguration::setDynamicReconfigure
void setDynamicReconfigure()
Definition: thermal_configuration.cpp:76
ros::ok
ROSCPP_DECL bool ok()
l3cam_ros::L3Cam::timeout_secs_
int timeout_secs_
Definition: l3cam_ros_node.hpp:404
l3cam_ros::ThermalConfiguration::client_processing_pipeline_
ros::ServiceClient client_processing_pipeline_
Definition: thermal_configuration.cpp:478
l3cam_ros::ThermalConfiguration::client_get_rtsp_pipeline_
ros::ServiceClient client_get_rtsp_pipeline_
Definition: thermal_configuration.cpp:484
ros::ServiceServer
l3cam_ros::ThermalConfiguration::srv_get_rtsp_pipeline_
l3cam_ros::GetRtspPipeline srv_get_rtsp_pipeline_
Definition: thermal_configuration.cpp:485
l3cam_ros::ThermalConfiguration::callThermalTemperatureDataUdp
int callThermalTemperatureDataUdp(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:385
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros::ThermalConfiguration::srv_colormap_
l3cam_ros::ChangeThermalCameraColormap srv_colormap_
Definition: thermal_configuration.cpp:473
l3cam_ros::ThermalConfiguration::thermal_colormap_
int thermal_colormap_
Definition: thermal_configuration.cpp:489
l3cam_ros_utils.hpp
l3cam_ros::ThermalConfiguration::srv_temperature_filter_
l3cam_ros::ChangeThermalCameraTemperatureFilter srv_temperature_filter_
Definition: thermal_configuration.cpp:477
l3cam_ros::ThermalConfiguration::thermal_temperature_data_udp_
bool thermal_temperature_data_udp_
Definition: thermal_configuration.cpp:494
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::ThermalConfiguration::callThermalColormap
int callThermalColormap(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:265
ros::ServiceClient
l3cam_ros::ThermalConfiguration::srv_get_sensors_
l3cam_ros::GetSensorsAvailable srv_get_sensors_
Definition: thermal_configuration.cpp:96
l3cam_ros::ThermalConfiguration::callThermalTemperatureFilterRange
int callThermalTemperatureFilterRange(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:323
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
l3cam_ros::ThermalConfiguration::client_get_sensors_
ros::ServiceClient client_get_sensors_
Definition: thermal_configuration.cpp:95
l3cam_ros::ThermalConfiguration::callThermalProcessingPipeline
int callThermalProcessingPipeline(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:356
l3cam_ros::ThermalConfiguration::thermal_temperature_filter_min_
int thermal_temperature_filter_min_
Definition: thermal_configuration.cpp:491
ros::NodeHandle::NodeHandle
NodeHandle(const NodeHandle &parent, const std::string &ns)
l3cam_ros::ThermalConfiguration::srv_temperature_data_udp_
l3cam_ros::EnableThermalCameraTemperatureDataUdp srv_temperature_data_udp_
Definition: thermal_configuration.cpp:481
l3cam_ros::ThermalConfiguration::srv_sensor_disconnected_
ros::ServiceServer srv_sensor_disconnected_
Definition: thermal_configuration.cpp:487
l3cam_ros::ThermalConfiguration::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: thermal_configuration.cpp:102
l3cam_ros::ThermalConfiguration::m_default_configured
bool m_default_configured
Definition: thermal_configuration.cpp:498
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::ThermalConfiguration::srv_change_streaming_protocol_
l3cam_ros::ChangeStreamingProtocol srv_change_streaming_protocol_
Definition: thermal_configuration.cpp:483
l3cam_ros::ThermalConfiguration::configureDefault
void configureDefault(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:133
l3cam_ros::ThermalConfiguration::thermal_streaming_protocol_
int thermal_streaming_protocol_
Definition: thermal_configuration.cpp:495
l3cam_ros::ThermalConfiguration::callThermalStreamingProtocol
int callThermalStreamingProtocol(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:415
l3cam_ros::ThermalConfiguration::client_enable_temperature_filter_
ros::ServiceClient client_enable_temperature_filter_
Definition: thermal_configuration.cpp:474
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
l3cam_ros::ThermalConfiguration::callThermalRtspPipeline
int callThermalRtspPipeline(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:445
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
main
int main(int argc, char **argv)
Definition: thermal_configuration.cpp:505
ros::Duration::sleep
bool sleep() const
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ROS_INFO
#define ROS_INFO(...)
l3cam_ros::ThermalConfiguration::loadDefaultParams
void loadDefaultParams()
Definition: thermal_configuration.cpp:120
l3cam_ros::ThermalConfiguration::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: thermal_configuration.cpp:454
ros::Duration
l3cam_ros::ThermalConfiguration::parametersCallback
void parametersCallback(l3cam_ros::ThermalConfig &config, uint32_t level)
Definition: thermal_configuration.cpp:218
l3cam_ros::ThermalConfiguration::client_change_streaming_protocol_
ros::ServiceClient client_change_streaming_protocol_
Definition: thermal_configuration.cpp:482
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
l3cam_ros::ThermalConfiguration::callThermalTemperatureFilter
int callThermalTemperatureFilter(l3cam_ros::ThermalConfig &config)
Definition: thermal_configuration.cpp:294
ros::NodeHandle
l3cam_ros::ThermalConfiguration::thermal_temperature_filter_max_
int thermal_temperature_filter_max_
Definition: thermal_configuration.cpp:492


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