t265_realsense_node.cpp
Go to the documentation of this file.
2 
3 using namespace realsense2_camera;
4 
6  ros::NodeHandle& privateNodeHandle,
7  rs2::device dev,
8  const std::string& serial_no) :
9  BaseRealSenseNode(nodeHandle, privateNodeHandle, dev, serial_no),
10  _wo_snr(dev.first<rs2::wheel_odometer>()),
11  _use_odom_in(false)
12  {
15  handleWarning();
16  }
17 
19 {
20  std::string calib_odom_file;
21  _pnh.param("calib_odom_file", calib_odom_file, std::string(""));
22  if (calib_odom_file.empty())
23  {
24  ROS_INFO("No calib_odom_file. No input odometry accepted.");
25  return;
26  }
27  std::ifstream calibrationFile(calib_odom_file);
28  if (!calibrationFile)
29  {
30  ROS_FATAL_STREAM("calibration_odometry file not found. calib_odom_file = " << calib_odom_file);
31  throw std::runtime_error("calibration_odometry file not found" );
32  }
33  const std::string json_str((std::istreambuf_iterator<char>(calibrationFile)),
34  std::istreambuf_iterator<char>());
35  const std::vector<uint8_t> wo_calib(json_str.begin(), json_str.end());
36 
37  if (!_wo_snr.load_wheel_odometery_config(wo_calib))
38  {
39  ROS_FATAL_STREAM("Format error in calibration_odometry file: " << calib_odom_file);
40  throw std::runtime_error("Format error in calibration_odometry file" );
41  }
42  _use_odom_in = true;
43 }
44 
46 {
47  ROS_WARN_STREAM("toggleSensors method not implemented for T265");
48 }
49 
51 {
54 }
55 
57 {
58  rs2::log_to_callback( rs2_log_severity::RS2_LOG_SEVERITY_WARN, [&]
59  ( rs2_log_severity severity, rs2::log_message const & msg ) noexcept {
60  _T265_fault = msg.raw();
61  std::array<std::string, 2> list_of_fault{"SLAM_ERROR", "Stream transfer failed, exiting"};
62  auto it = std::find_if(begin(list_of_fault), end(list_of_fault),
63  [&](const std::string& s) {return _T265_fault.find(s) != std::string::npos; });
64  if (it != end(list_of_fault))
65  {
68  }
69  });
70 }
71 
73 {
74  if (!_use_odom_in) return;
75 
76  std::string topic_odom_in;
77  _pnh.param("topic_odom_in", topic_odom_in, DEFAULT_TOPIC_ODOM_IN);
78  ROS_INFO_STREAM("Subscribing to in_odom topic: " << topic_odom_in);
79 
81 }
82 
83 void T265RealsenseNode::odom_in_callback(const nav_msgs::Odometry::ConstPtr& msg)
84 {
85  ROS_DEBUG("Got in_odom message");
86  rs2_vector velocity {-(float)(msg->twist.twist.linear.y),
87  (float)(msg->twist.twist.linear.z),
88  -(float)(msg->twist.twist.linear.x)};
89 
90  ROS_DEBUG_STREAM("Add odom: " << velocity.x << ", " << velocity.y << ", " << velocity.z);
91  _wo_snr.send_wheel_odometry(0, 0, velocity);
92 }
93 
95 {
96  // Transform base to stream
97  tf::Quaternion quaternion_optical;
98  quaternion_optical.setRPY(M_PI / 2, 0.0, -M_PI / 2); //Pose To ROS
99  float3 zero_trans{0, 0, 0};
100 
101  ros::Time transform_ts_ = ros::Time::now();
102 
103  rs2_extrinsics ex;
104  try
105  {
106  ex = getAProfile(stream).get_extrinsics_to(base_profile);
107  }
108  catch (std::exception& e)
109  {
110  if (!strcmp(e.what(), "Requested extrinsics are not available!"))
111  {
112  ROS_WARN_STREAM(e.what() << " : using unity as default.");
113  ex = rs2_extrinsics({{1, 0, 0, 0, 1, 0, 0, 0, 1}, {0,0,0}});
114  }
115  else
116  {
117  throw e;
118  }
119  }
120 
122  Q = quaternion_optical * Q * quaternion_optical.inverse();
123  float3 trans{ex.translation[0], ex.translation[1], ex.translation[2]};
124  if (stream == POSE)
125  {
126  Q = Q.inverse();
127  publish_static_tf(transform_ts_, trans, Q, _frame_id[stream], _base_frame_id);
128  }
129  else
130  {
131  publish_static_tf(transform_ts_, trans, Q, _base_frame_id, _frame_id[stream]);
132  publish_static_tf(transform_ts_, zero_trans, quaternion_optical, _frame_id[stream], _optical_frame_id[stream]);
133 
134  // Add align_depth_to if exist:
136  {
138  publish_static_tf(transform_ts_, zero_trans, quaternion_optical, _depth_aligned_frame_id[stream], _optical_frame_id[stream]);
139  }
140  }
141 }
142 
144 {
145  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, _T265_fault);
146 }
rs2::device
realsense2_camera::T265RealsenseNode::handleWarning
void handleWarning()
Definition: t265_realsense_node.cpp:56
rs2_vector
realsense2_camera::T265RealsenseNode::_odom_subscriber
ros::Subscriber _odom_subscriber
Definition: t265_realsense_node.h:28
enabled
GLenum GLenum GLsizei const GLuint GLboolean enabled
status
status
msg
msg
rs2_extrinsics::translation
float translation[3]
rs2_extrinsics
rs2::stream_profile
realsense2_camera::T265RealsenseNode::setupSubscribers
void setupSubscribers()
Definition: t265_realsense_node.cpp:72
diagnostic_updater::Updater::force_update
void force_update()
realsense2_camera::BaseRealSenseNode::_node_handle
ros::NodeHandle & _node_handle
Definition: base_realsense_node.h:165
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
realsense2_camera::T265RealsenseNode::odom_in_callback
void odom_in_callback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: t265_realsense_node.cpp:83
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
realsense2_camera::BaseRealSenseNode::_frame_id
std::map< stream_index_pair, std::string > _frame_id
Definition: base_realsense_node.h:162
realsense2_camera::BaseRealSenseNode::_align_depth
bool _align_depth
Definition: base_realsense_node.h:166
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
Q
Q
tf::Quaternion::inverse
Quaternion inverse() const
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
rs2_log_severity
rs2_log_severity
rs2::stream_profile::get_extrinsics_to
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
wheel_odometer
wheel_odometer
rs2::wheel_odometer::send_wheel_odometry
bool send_wheel_odometry(uint8_t wo_sensor_id, uint32_t frame_num, const rs2_vector &translational_velocity)
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
dev
dev
rs2::wheel_odometer::load_wheel_odometery_config
bool load_wheel_odometery_config(const std::vector< uint8_t > &odometry_config_buf) const
realsense2_camera::stream_index_pair
std::pair< rs2_stream, int > stream_index_pair
Definition: constants.h:99
begin
not_this_one begin(...)
realsense2_camera::T265RealsenseNode::_T265_fault
std::string _T265_fault
Definition: t265_realsense_node.h:31
ROS_DEBUG
#define ROS_DEBUG(...)
stream
GLuint GLuint stream
realsense2_camera::T265RealsenseNode::_wo_snr
rs2::wheel_odometer _wo_snr
Definition: t265_realsense_node.h:29
rs2_extrinsics::rotation
float rotation[9]
realsense2_camera::T265RealsenseNode::initializeOdometryInput
void initializeOdometryInput()
Definition: t265_realsense_node.cpp:18
rs2
RS2_OPTION_ASIC_TEMPERATURE
RS2_OPTION_ASIC_TEMPERATURE
severity
GLenum GLuint GLenum severity
realsense2_camera::BaseRealSenseNode::_depth_aligned_frame_id
std::map< stream_index_pair, std::string > _depth_aligned_frame_id
Definition: base_realsense_node.h:164
rs2::log_message
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
realsense2_camera::BaseRealSenseNode::_monitor_options
std::vector< rs2_option > _monitor_options
Definition: base_realsense_node.h:167
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
realsense2_camera::BaseRealSenseNode::_base_frame_id
std::string _base_frame_id
Definition: base_realsense_node.h:160
realsense2_camera::BaseRealSenseNode::float3
Definition: base_realsense_node.h:137
realsense2_camera::T265RealsenseNode::toggleSensors
virtual void toggleSensors(bool enabled) override
Definition: t265_realsense_node.cpp:45
realsense2_camera::DEFAULT_TOPIC_ODOM_IN
const std::string DEFAULT_TOPIC_ODOM_IN
Definition: constants.h:96
ros::Time
realsense2_camera
Definition: base_realsense_node.h:27
realsense2_camera::BaseRealSenseNode::_optical_frame_id
std::map< stream_index_pair, std::string > _optical_frame_id
Definition: base_realsense_node.h:163
realsense2_camera::BaseRealSenseNode::publish_static_tf
void publish_static_tf(const ros::Time &t, const float3 &trans, const tf::Quaternion &q, const std::string &from, const std::string &to)
Definition: base_realsense_node.cpp:1981
first
GLint first
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
realsense2_camera::T265RealsenseNode::_use_odom_in
bool _use_odom_in
Definition: t265_realsense_node.h:30
diagnostic_updater::DiagnosticStatusWrapper
realsense2_camera::BaseRealSenseNode::_pnh
ros::NodeHandle _pnh
Definition: base_realsense_node.h:165
e
e
realsense2_camera::BaseRealSenseNode::publishTopics
virtual void publishTopics() override
Definition: base_realsense_node.cpp:240
realsense2_camera::POSE
const stream_index_pair POSE
Definition: realsense_node_factory.h:38
realsense2_camera::BaseRealSenseNode::getAProfile
rs2::stream_profile getAProfile(const stream_index_pair &stream)
Definition: base_realsense_node.cpp:2324
rs2::log_to_callback
void log_to_callback(rs2_log_severity min_severity, S callback)
end
GLuint GLuint end
ROS_INFO
#define ROS_INFO(...)
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
realsense2_camera::T265RealsenseNode::publishTopics
virtual void publishTopics() override
Definition: t265_realsense_node.cpp:50
s
GLdouble s
tf::Quaternion
RS2_OPTION_MOTION_MODULE_TEMPERATURE
RS2_OPTION_MOTION_MODULE_TEMPERATURE
realsense2_camera::T265RealsenseNode::warningDiagnostic
void warningDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: t265_realsense_node.cpp:143
ros::NodeHandle
t265_realsense_node.h
realsense2_camera::BaseRealSenseNode::rotationMatrixToQuaternion
tf::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const
Definition: base_realsense_node.cpp:1969
ros::Time::now
static Time now()
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