1 #include "../include/t265_realsense_node.h" 8 const std::string& serial_no) :
20 std::string calib_odom_file;
21 _pnh.
param(
"calib_odom_file", calib_odom_file, std::string(
""));
22 if (calib_odom_file.empty())
24 ROS_INFO(
"No calib_odom_file. No input odometry accepted.");
27 std::ifstream calibrationFile(calib_odom_file);
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" );
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());
39 ROS_FATAL_STREAM(
"Format error in calibration_odometry file: " << calib_odom_file);
40 throw std::runtime_error(
"Format error in calibration_odometry file" );
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))
76 std::string topic_odom_in;
86 rs2_vector velocity {-(float)(msg->twist.twist.linear.y),
87 (float)(msg->twist.twist.linear.z),
88 -(float)(msg->twist.twist.linear.x)};
90 ROS_DEBUG_STREAM(
"Add odom: " << velocity.x <<
", " << velocity.y <<
", " << velocity.z);
98 quaternion_optical.
setRPY(M_PI / 2, 0.0, -M_PI / 2);
99 float3 zero_trans{0, 0, 0};
108 catch (std::exception&
e)
110 if (!strcmp(e.what(),
"Requested extrinsics are not available!"))
113 ex =
rs2_extrinsics({{1, 0, 0, 0, 1, 0, 0, 0, 1}, {0,0,0}});
122 Q = quaternion_optical *
Q * quaternion_optical.
inverse();
GLenum GLuint GLenum severity
void log_to_callback(rs2_log_severity min_severity, S callback)
tf::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const
RS2_OPTION_MOTION_MODULE_TEMPERATURE
void summary(unsigned char lvl, const std::string s)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void warningDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
T265RealsenseNode(ros::NodeHandle &nodeHandle, ros::NodeHandle &privateNodeHandle, rs2::device dev, const std::string &serial_no)
diagnostic_updater::Updater callback_updater
std::string _base_frame_id
RS2_OPTION_ASIC_TEMPERATURE
virtual void publishTopics() override
void add(const std::string &name, TaskFunction f)
ros::Subscriber _odom_subscriber
void initializeOdometryInput()
std::pair< rs2_stream, int > stream_index_pair
#define ROS_FATAL_STREAM(args)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::NodeHandle & _node_handle
GLenum GLenum GLsizei const GLuint GLboolean enabled
void odom_in_callback(const nav_msgs::Odometry::ConstPtr &msg)
#define ROS_WARN_STREAM(args)
const std::string DEFAULT_TOPIC_ODOM_IN
#define ROS_DEBUG_STREAM(args)
Quaternion inverse() const
bool load_wheel_odometery_config(const std::vector< uint8_t > &odometry_config_buf) const
rs2::wheel_odometer _wo_snr
#define ROS_INFO_STREAM(args)
std::vector< rs2_option > _monitor_options
std::map< stream_index_pair, std::string > _frame_id
const stream_index_pair POSE
void calcAndPublishStaticTransform(const stream_index_pair &stream, const rs2::stream_profile &base_profile) override
void publish_static_tf(const ros::Time &t, const float3 &trans, const tf::Quaternion &q, const std::string &from, const std::string &to)
bool send_wheel_odometry(uint8_t wo_sensor_id, uint32_t frame_num, const rs2_vector &translational_velocity)
rs2::stream_profile getAProfile(const stream_index_pair &stream)
std::map< stream_index_pair, std::string > _optical_frame_id
virtual void toggleSensors(bool enabled) override
virtual void publishTopics() override
std::map< stream_index_pair, std::string > _depth_aligned_frame_id