t265_realsense_node.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 namespace realsense2_camera
6 {
8  {
9  public:
11  ros::NodeHandle& privateNodeHandle,
13  const std::string& serial_no);
14  virtual void toggleSensors(bool enabled) override;
15  virtual void publishTopics() override;
16 
17  protected:
18  void calcAndPublishStaticTransform(const stream_index_pair& stream, const rs2::stream_profile& base_profile) override;
19 
20  private:
22  void setupSubscribers();
23  void handleWarning();
24  void odom_in_callback(const nav_msgs::Odometry::ConstPtr& msg);
27 
31  std::string _T265_fault;
32  };
33 }
rs2::device
realsense2_camera::T265RealsenseNode::handleWarning
void handleWarning()
Definition: t265_realsense_node.cpp:56
realsense2_camera::T265RealsenseNode::_odom_subscriber
ros::Subscriber _odom_subscriber
Definition: t265_realsense_node.h:28
enabled
GLenum GLenum GLsizei const GLuint GLboolean enabled
msg
msg
rs2::wheel_odometer
rs2::stream_profile
realsense2_camera::T265RealsenseNode::setupSubscribers
void setupSubscribers()
Definition: t265_realsense_node.cpp:72
realsense2_camera::T265RealsenseNode::odom_in_callback
void odom_in_callback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: t265_realsense_node.cpp:83
realsense2_camera::T265RealsenseNode::T265RealsenseNode
T265RealsenseNode(ros::NodeHandle &nodeHandle, ros::NodeHandle &privateNodeHandle, rs2::device dev, const std::string &serial_no)
Definition: t265_realsense_node.cpp:5
diagnostic_updater::Updater
realsense2_camera::T265RealsenseNode::calcAndPublishStaticTransform
void calcAndPublishStaticTransform(const stream_index_pair &stream, const rs2::stream_profile &base_profile) override
Definition: t265_realsense_node.cpp:94
realsense2_camera::BaseRealSenseNode
Definition: base_realsense_node.h:120
base_realsense_node.h
dev
dev
realsense2_camera::stream_index_pair
std::pair< rs2_stream, int > stream_index_pair
Definition: constants.h:99
realsense2_camera::T265RealsenseNode::_T265_fault
std::string _T265_fault
Definition: t265_realsense_node.h:31
stream
GLuint GLuint stream
realsense2_camera::T265RealsenseNode::_wo_snr
rs2::wheel_odometer _wo_snr
Definition: t265_realsense_node.h:29
realsense2_camera::T265RealsenseNode::initializeOdometryInput
void initializeOdometryInput()
Definition: t265_realsense_node.cpp:18
realsense2_camera::T265RealsenseNode::toggleSensors
virtual void toggleSensors(bool enabled) override
Definition: t265_realsense_node.cpp:45
realsense2_camera
Definition: base_realsense_node.h:27
realsense2_camera::T265RealsenseNode
Definition: t265_realsense_node.h:7
realsense2_camera::T265RealsenseNode::_use_odom_in
bool _use_odom_in
Definition: t265_realsense_node.h:30
diagnostic_updater::DiagnosticStatusWrapper
realsense2_camera::T265RealsenseNode::publishTopics
virtual void publishTopics() override
Definition: t265_realsense_node.cpp:50
realsense2_camera::T265RealsenseNode::warningDiagnostic
void warningDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: t265_realsense_node.cpp:143
ros::NodeHandle
ros::Subscriber
realsense2_camera::T265RealsenseNode::callback_updater
diagnostic_updater::Updater callback_updater
Definition: t265_realsense_node.h:26


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