realsense_node_factory.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2018 Intel Corporation. All Rights Reserved
3 
4 #pragma once
5 
7 #include <nodelet/nodelet.h>
9 #include <ros/ros.h>
10 #include <ros/package.h>
11 #include <std_srvs/SetBool.h>
12 #include <librealsense2/rs.hpp>
13 #include <librealsense2/rsutil.h>
16 #include <cv_bridge/cv_bridge.h>
18 #include <realsense2_camera/Extrinsics.h>
19 #include <realsense2_camera/IMUInfo.h>
20 #include <csignal>
21 #include <eigen3/Eigen/Geometry>
22 #include <fstream>
23 #include <thread>
24 #include <std_srvs/Empty.h>
25 
26 namespace realsense2_camera
27 {
40 
41  const std::vector<stream_index_pair> IMAGE_STREAMS = {DEPTH, INFRA0, INFRA1, INFRA2,
42  COLOR,
43  FISHEYE,
45 
46  const std::vector<stream_index_pair> HID_STREAMS = {GYRO, ACCEL, POSE};
47 
49  {
50  public:
51  virtual void publishTopics() = 0;
52  virtual void toggleSensors(bool enabled) = 0;
53  virtual void registerDynamicReconfigCb(ros::NodeHandle& nh) = 0;
54  virtual ~InterfaceRealSenseNode() = default;
55  };
56 
58  {
59  public:
61  virtual ~RealSenseNodeFactory();
62 
63  private:
64  void closeDevice();
65  void StartDevice();
68  virtual void onInit() override;
69  void initialize(const ros::WallTimerEvent &ignored);
71  void reset();
72  bool handleReset(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
73  static std::string parse_usb_port(std::string line);
74  bool toggle_sensor_callback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res);
75 
77  std::shared_ptr<InterfaceRealSenseNode> _realSenseNode;
79  std::string _serial_no;
80  std::string _usb_port_id;
81  std::string _device_type;
83  std::thread _query_thread;
84  bool _is_alive;
88 
89  };
90 }//end namespace
rs2::device
response
const std::string response
realsense2_camera::IMAGE_STREAMS
const std::vector< stream_index_pair > IMAGE_STREAMS
Definition: realsense_node_factory.h:41
realsense2_camera::RealSenseNodeFactory::closeDevice
void closeDevice()
realsense2_camera::FISHEYE1
const stream_index_pair FISHEYE1
Definition: realsense_node_factory.h:34
enabled
GLenum GLenum GLsizei const GLuint GLboolean enabled
realsense2_camera::INFRA1
const stream_index_pair INFRA1
Definition: realsense_node_factory.h:31
realsense2_camera::INFRA2
const stream_index_pair INFRA2
Definition: realsense_node_factory.h:32
RS2_STREAM_POSE
RS2_STREAM_POSE
realsense2_camera::InterfaceRealSenseNode::toggleSensors
virtual void toggleSensors(bool enabled)=0
realsense2_camera::RealSenseNodeFactory::getDevice
void getDevice(rs2::device_list list)
Definition: realsense_node_factory.cpp:87
realsense2_camera::RealSenseNodeFactory::_init_timer
ros::WallTimer _init_timer
Definition: realsense_node_factory.h:86
rs_processing.hpp
list
realsense2_camera::RealSenseNodeFactory::_is_alive
bool _is_alive
Definition: realsense_node_factory.h:84
ros.h
info
def info(*args)
realsense2_camera::CONFIDENCE
const stream_index_pair CONFIDENCE
Definition: realsense_node_factory.h:39
realsense2_camera::RealSenseNodeFactory::tryGetLogSeverity
void tryGetLogSeverity(rs2_log_severity &severity) const
Definition: realsense_node_factory.cpp:429
realsense2_camera::RealSenseNodeFactory::_initial_reset
bool _initial_reset
Definition: realsense_node_factory.h:82
rs2::device_list
ros::WallTimer
realsense2_camera::RealSenseNodeFactory::parse_usb_port
static std::string parse_usb_port(std::string line)
Definition: realsense_node_factory.cpp:65
realsense2_camera::RealSenseNodeFactory::change_device_callback
void change_device_callback(rs2::event_information &info)
Definition: realsense_node_factory.cpp:220
RS2_STREAM_FISHEYE
RS2_STREAM_FISHEYE
rs2_log_severity
rs2_log_severity
RS2_STREAM_COLOR
RS2_STREAM_COLOR
realsense2_camera::RealSenseNodeFactory::toggle_sensor_callback
bool toggle_sensor_callback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
Definition: realsense_node_factory.cpp:229
realsense2_camera::RealSenseNodeFactory::StartDevice
void StartDevice()
Definition: realsense_node_factory.cpp:347
ros::ServiceServer
realsense2_camera::RealSenseNodeFactory::_device_type
std::string _device_type
Definition: realsense_node_factory.h:81
realsense2_camera::RealSenseNodeFactory::toggle_sensor_srv
ros::ServiceServer toggle_sensor_srv
Definition: realsense_node_factory.h:85
class_list_macros.h
realsense2_camera::RealSenseNodeFactory::_ctx
rs2::context _ctx
Definition: realsense_node_factory.h:78
rs_advanced_mode.hpp
realsense2_camera::InterfaceRealSenseNode::~InterfaceRealSenseNode
virtual ~InterfaceRealSenseNode()=default
realsense2_camera::RealSenseNodeFactory::onInit
virtual void onInit() override
Definition: realsense_node_factory.cpp:240
realsense2_camera::stream_index_pair
std::pair< rs2_stream, int > stream_index_pair
Definition: constants.h:99
realsense2_camera::RealSenseNodeFactory::~RealSenseNodeFactory
virtual ~RealSenseNodeFactory()
Definition: realsense_node_factory.cpp:56
RS2_STREAM_GYRO
RS2_STREAM_GYRO
RS2_STREAM_CONFIDENCE
RS2_STREAM_CONFIDENCE
realsense2_camera::RealSenseNodeFactory::_reset_srv
ros::ServiceServer _reset_srv
Definition: realsense_node_factory.h:87
realsense2_camera::RealSenseNodeFactory
Definition: realsense_node_factory.h:57
realsense2_camera::InterfaceRealSenseNode::registerDynamicReconfigCb
virtual void registerDynamicReconfigCb(ros::NodeHandle &nh)=0
res
GLuint res
severity
GLenum GLuint GLenum severity
realsense2_camera::InterfaceRealSenseNode::publishTopics
virtual void publishTopics()=0
RS2_STREAM_DEPTH
RS2_STREAM_DEPTH
rsutil.h
realsense2_camera::RealSenseNodeFactory::_device
rs2::device _device
Definition: realsense_node_factory.h:76
line
string line
realsense2_camera::RealSenseNodeFactory::reset
void reset()
Definition: realsense_node_factory.cpp:398
realsense2_camera::RealSenseNodeFactory::_usb_port_id
std::string _usb_port_id
Definition: realsense_node_factory.h:80
realsense2_camera::ACCEL
const stream_index_pair ACCEL
Definition: realsense_node_factory.h:37
package.h
realsense2_camera::DEPTH
const stream_index_pair DEPTH
Definition: realsense_node_factory.h:29
image_transport.h
realsense2_camera::RealSenseNodeFactory::_serial_no
std::string _serial_no
Definition: realsense_node_factory.h:79
ros::WallTimerEvent
nodelet::Nodelet
RS2_STREAM_ACCEL
RS2_STREAM_ACCEL
realsense2_camera::RealSenseNodeFactory::initialize
void initialize(const ros::WallTimerEvent &ignored)
Definition: realsense_node_factory.cpp:246
realsense2_camera::GYRO
const stream_index_pair GYRO
Definition: realsense_node_factory.h:36
realsense2_camera
Definition: base_realsense_node.h:27
rs2::context
constants.h
rs2::event_information
realsense2_camera::FISHEYE
const stream_index_pair FISHEYE
Definition: realsense_node_factory.h:33
nodelet.h
realsense2_camera::HID_STREAMS
const std::vector< stream_index_pair > HID_STREAMS
Definition: realsense_node_factory.h:46
realsense2_camera::RealSenseNodeFactory::_realSenseNode
std::shared_ptr< InterfaceRealSenseNode > _realSenseNode
Definition: realsense_node_factory.h:77
rs.hpp
cv_bridge.h
realsense2_camera::RealSenseNodeFactory::RealSenseNodeFactory
RealSenseNodeFactory()
Definition: realsense_node_factory.cpp:32
realsense2_camera::COLOR
const stream_index_pair COLOR
Definition: realsense_node_factory.h:28
RS2_STREAM_INFRARED
RS2_STREAM_INFRARED
realsense2_camera::RealSenseNodeFactory::handleReset
bool handleReset(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Definition: realsense_node_factory.cpp:423
realsense2_camera::POSE
const stream_index_pair POSE
Definition: realsense_node_factory.h:38
realsense2_camera::RealSenseNodeFactory::_query_thread
std::thread _query_thread
Definition: realsense_node_factory.h:83
realsense2_camera::FISHEYE2
const stream_index_pair FISHEYE2
Definition: realsense_node_factory.h:35
realsense2_camera::INFRA0
const stream_index_pair INFRA0
Definition: realsense_node_factory.h:30
realsense2_camera::InterfaceRealSenseNode
Definition: realsense_node_factory.h:48
ros::NodeHandle


realsense2_camera
Author(s): Sergey Dorodnicov , Doron Hirshberg
autogenerated on Fri Mar 25 2022 02:15:35