sensor_stream.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 "sensor_stream.hpp"
29 
30 namespace l3cam_ros
31 {
32  SensorStream::SensorStream() : ros::NodeHandle("~")
33  {
34  client_get_sensors_ = this->serviceClient<l3cam_ros::GetSensorsAvailable>("/L3Cam/l3cam_ros_node/get_sensors_available");
35 
36  loadParam("timeout_secs", timeout_secs_, 60);
37  }
38 
40  {
41  while (ros::ok() && !m_shutdown_requested)
42  {
43 
44  ros::spinOnce();
45  ros::Duration(0.1).sleep();
46  }
47 
48  ros::shutdown();
49  }
50 
51  void SensorStream::declareServiceServers(const std::string &sensor)
52  {
53  srv_sensor_disconnected_ = this->advertiseService(sensor + "_stream_disconnected", &SensorStream::sensorDisconnectedCallback, this);
54  }
55 
56  template <typename T>
57  void SensorStream::loadParam(const std::string &param_name, T &param_var, const T &default_val)
58  {
59  std::string full_param_name;
60 
61  if (searchParam(param_name, full_param_name))
62  {
63  if (!getParam(full_param_name, param_var))
64  {
65  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
66  }
67  }
68  else
69  {
70  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
71  param_var = default_val;
72  }
73  }
74 
75  bool SensorStream::sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
76  {
77  ROS_BMG_UNUSED(res);
78  stopListening();
79 
80  if (req.code == 0)
81  {
82  ROS_INFO_STREAM("Exiting " << this->getNamespace() << " cleanly.");
83  }
84  else
85  {
86  ROS_WARN_STREAM("Exiting " << this->getNamespace() << ". Sensor got disconnected with error " << req.code << ": " << getErrorDescription(req.code));
87  }
88 
89  m_shutdown_requested = true;
90  return true;
91  }
92 
93 } // namespace l3cam_ros
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::SensorStream::timeout_secs_
int timeout_secs_
Definition: sensor_stream.hpp:53
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
l3cam_ros::SensorStream::spin
void spin()
Definition: sensor_stream.cpp:39
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
l3cam_ros::SensorStream::stopListening
virtual void stopListening()=0
l3cam_ros
Definition: l3cam_ros_node.hpp:133
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
ros::ok
ROSCPP_DECL bool ok()
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros::SensorStream::m_shutdown_requested
bool m_shutdown_requested
Definition: sensor_stream.hpp:63
l3cam_ros::SensorStream::SensorStream
SensorStream()
Definition: sensor_stream.cpp:32
l3cam_ros::SensorStream::declareServiceServers
void declareServiceServers(const std::string &sensor)
Definition: sensor_stream.cpp:51
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::SensorStream::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: sensor_stream.cpp:57
l3cam_ros::SensorStream::srv_sensor_disconnected_
ros::ServiceServer srv_sensor_disconnected_
Definition: sensor_stream.hpp:61
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
sensor_stream.hpp
l3cam_ros::SensorStream::client_get_sensors_
ros::ServiceClient client_get_sensors_
Definition: sensor_stream.hpp:50
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::SensorStream::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: sensor_stream.cpp:75
ros::Duration::sleep
bool sleep() const
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ros::Duration


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