Go to the documentation of this file.
11 #include <std_srvs/SetBool.h>
18 #include <realsense2_camera/Extrinsics.h>
19 #include <realsense2_camera/IMUInfo.h>
21 #include <eigen3/Eigen/Geometry>
24 #include <std_srvs/Empty.h>
68 virtual void onInit()
override;
const std::string response
const std::vector< stream_index_pair > IMAGE_STREAMS
const stream_index_pair FISHEYE1
GLenum GLenum GLsizei const GLuint GLboolean enabled
const stream_index_pair INFRA1
const stream_index_pair INFRA2
virtual void toggleSensors(bool enabled)=0
void getDevice(rs2::device_list list)
ros::WallTimer _init_timer
const stream_index_pair CONFIDENCE
void tryGetLogSeverity(rs2_log_severity &severity) const
static std::string parse_usb_port(std::string line)
void change_device_callback(rs2::event_information &info)
bool toggle_sensor_callback(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::ServiceServer toggle_sensor_srv
virtual ~InterfaceRealSenseNode()=default
virtual void onInit() override
std::pair< rs2_stream, int > stream_index_pair
virtual ~RealSenseNodeFactory()
ros::ServiceServer _reset_srv
virtual void registerDynamicReconfigCb(ros::NodeHandle &nh)=0
GLenum GLuint GLenum severity
virtual void publishTopics()=0
const stream_index_pair ACCEL
const stream_index_pair DEPTH
void initialize(const ros::WallTimerEvent &ignored)
const stream_index_pair GYRO
const stream_index_pair FISHEYE
const std::vector< stream_index_pair > HID_STREAMS
std::shared_ptr< InterfaceRealSenseNode > _realSenseNode
const stream_index_pair COLOR
bool handleReset(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
const stream_index_pair POSE
std::thread _query_thread
const stream_index_pair FISHEYE2
const stream_index_pair INFRA0
realsense2_camera
Author(s): Sergey Dorodnicov
, Doron Hirshberg
autogenerated on Fri Mar 25 2022 02:15:35