sensor_stream.hpp
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 <ros/ros.h>
29 #include <iostream>
30 
31 #include "l3cam_ros/GetSensorsAvailable.h"
32 #include "l3cam_ros/SensorDisconnected.h"
33 
34 #include "l3cam_ros_utils.hpp"
35 
36 namespace l3cam_ros
37 {
39  {
40  protected:
41  explicit SensorStream();
42 
43  virtual void stopListening() = 0;
44 
45  public:
46  void spin();
47 
48  void declareServiceServers(const std::string &sensor);
49 
51  l3cam_ros::GetSensorsAvailable srv_get_sensors_;
52 
54 
55  private:
56  template <typename T>
57  void loadParam(const std::string &param_name, T &param_var, const T &default_val);
58 
59  bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res);
60 
62 
64 
65  }; // class SensorStream
66 
67 } // namespace l3cam_ros
l3cam_ros::SensorStream
Definition: sensor_stream.hpp:38
l3cam_ros::SensorStream::timeout_secs_
int timeout_secs_
Definition: sensor_stream.hpp:53
ros.h
l3cam_ros::SensorStream::spin
void spin()
Definition: sensor_stream.cpp:39
l3cam_ros::SensorStream::stopListening
virtual void stopListening()=0
l3cam_ros
Definition: l3cam_ros_node.hpp:133
ros::ServiceServer
l3cam_ros::SensorStream::srv_get_sensors_
l3cam_ros::GetSensorsAvailable srv_get_sensors_
Definition: sensor_stream.hpp:51
l3cam_ros_utils.hpp
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::ServiceClient
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
l3cam_ros::SensorStream::client_get_sensors_
ros::ServiceClient client_get_sensors_
Definition: sensor_stream.hpp:50
l3cam_ros::SensorStream::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: sensor_stream.cpp:75
ros::NodeHandle


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