00001 #include "../include/t265_realsense_node.h"
00002
00003 using namespace realsense2_camera;
00004
00005 T265RealsenseNode::T265RealsenseNode(ros::NodeHandle& nodeHandle,
00006 ros::NodeHandle& privateNodeHandle,
00007 rs2::device dev,
00008 const std::string& serial_no) :
00009 BaseRealSenseNode(nodeHandle, privateNodeHandle, dev, serial_no),
00010 _wo_snr(dev.first<rs2::wheel_odometer>()),
00011 _use_odom_in(false)
00012 {
00013 initializeOdometryInput();
00014 }
00015
00016 void T265RealsenseNode::initializeOdometryInput()
00017 {
00018 std::string calib_odom_file;
00019 _pnh.param("calib_odom_file", calib_odom_file, std::string(""));
00020 if (calib_odom_file.empty())
00021 {
00022 ROS_INFO("No calib_odom_file. No input odometry accepted.");
00023 return;
00024 }
00025 std::ifstream calibrationFile(calib_odom_file);
00026 if (not calibrationFile)
00027 {
00028 ROS_FATAL_STREAM("calibration_odometry file not found. calib_odom_file = " << calib_odom_file);
00029 throw std::runtime_error("calibration_odometry file not found" );
00030 }
00031 const std::string json_str((std::istreambuf_iterator<char>(calibrationFile)),
00032 std::istreambuf_iterator<char>());
00033 const std::vector<uint8_t> wo_calib(json_str.begin(), json_str.end());
00034
00035 if (!_wo_snr.load_wheel_odometery_config(wo_calib))
00036 {
00037 ROS_FATAL_STREAM("Format error in calibration_odometry file: " << calib_odom_file);
00038 throw std::runtime_error("Format error in calibration_odometry file" );
00039 }
00040 _use_odom_in = true;
00041 }
00042
00043 void T265RealsenseNode::publishTopics()
00044 {
00045 BaseRealSenseNode::publishTopics();
00046 setupSubscribers();
00047 }
00048
00049 void T265RealsenseNode::setupSubscribers()
00050 {
00051 if (not _use_odom_in) return;
00052
00053 std::string topic_odom_in;
00054 _pnh.param("topic_odom_in", topic_odom_in, DEFAULT_TOPIC_ODOM_IN);
00055 ROS_INFO_STREAM("Subscribing to in_odom topic: " << topic_odom_in);
00056
00057 _odom_subscriber = _node_handle.subscribe(topic_odom_in, 1, &T265RealsenseNode::odom_in_callback, this);
00058 }
00059
00060 void T265RealsenseNode::odom_in_callback(const nav_msgs::Odometry::ConstPtr& msg)
00061 {
00062 ROS_DEBUG("Got in_odom message");
00063 rs2_vector velocity {-(float)(msg->twist.twist.linear.y),
00064 (float)(msg->twist.twist.linear.z),
00065 -(float)(msg->twist.twist.linear.x)};
00066
00067 ROS_DEBUG_STREAM("Add odom: " << velocity.x << ", " << velocity.y << ", " << velocity.z);
00068 _wo_snr.send_wheel_odometry(0, 0, velocity);
00069 }
00070
00071 void T265RealsenseNode::calcAndPublishStaticTransform(const stream_index_pair& stream, const rs2::stream_profile& base_profile)
00072 {
00073
00074 tf::Quaternion quaternion_optical;
00075 quaternion_optical.setRPY(M_PI / 2, 0.0, -M_PI / 2);
00076 float3 zero_trans{0, 0, 0};
00077
00078 ros::Time transform_ts_ = ros::Time::now();
00079
00080 rs2_extrinsics ex;
00081 try
00082 {
00083 ex = getAProfile(stream).get_extrinsics_to(base_profile);
00084 }
00085 catch (std::exception& e)
00086 {
00087 if (!strcmp(e.what(), "Requested extrinsics are not available!"))
00088 {
00089 ROS_WARN_STREAM(e.what() << " : using unity as default.");
00090 ex = rs2_extrinsics({{1, 0, 0, 0, 1, 0, 0, 0, 1}, {0,0,0}});
00091 }
00092 else
00093 {
00094 throw e;
00095 }
00096 }
00097
00098 auto Q = rotationMatrixToQuaternion(ex.rotation);
00099 Q = quaternion_optical * Q * quaternion_optical.inverse();
00100 float3 trans{ex.translation[0], ex.translation[1], ex.translation[2]};
00101 if (stream == POSE)
00102 {
00103 Q = Q.inverse();
00104 publish_static_tf(transform_ts_, trans, Q, _frame_id[stream], _base_frame_id);
00105 }
00106 else
00107 {
00108 publish_static_tf(transform_ts_, trans, Q, _base_frame_id, _frame_id[stream]);
00109 publish_static_tf(transform_ts_, zero_trans, quaternion_optical, _frame_id[stream], _optical_frame_id[stream]);
00110
00111
00112 if (_align_depth && _depth_aligned_frame_id.find(stream) != _depth_aligned_frame_id.end())
00113 {
00114 publish_static_tf(transform_ts_, trans, Q, _base_frame_id, _depth_aligned_frame_id[stream]);
00115 publish_static_tf(transform_ts_, zero_trans, quaternion_optical, _depth_aligned_frame_id[stream], _optical_frame_id[stream]);
00116 }
00117 }
00118 }