Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <ros/ros.h>
00029 #include <nav_msgs/Odometry.h>
00030 #include <tf2_ros/transform_broadcaster.h>
00031 #include <rtabmap_ros/MsgConversion.h>
00032
00033 class OdomMsgToTF
00034 {
00035
00036 public:
00037 OdomMsgToTF() :
00038 frameId_(""),
00039 odomFrameId_("")
00040 {
00041 ros::NodeHandle pnh("~");
00042 pnh.param("frame_id", frameId_, frameId_);
00043 pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
00044
00045 ros::NodeHandle nh;
00046 odomTopic_ = nh.subscribe("odom", 1, &OdomMsgToTF::odomReceivedCallback, this);
00047 }
00048
00049 virtual ~OdomMsgToTF(){}
00050
00051 void odomReceivedCallback(const nav_msgs::OdometryConstPtr & msg)
00052 {
00053 if(frameId_.empty())
00054 {
00055 frameId_ = msg->child_frame_id;
00056 }
00057 if(odomFrameId_.empty())
00058 {
00059 odomFrameId_ = msg->header.frame_id;
00060 }
00061 geometry_msgs::TransformStamped t;
00062 rtabmap::Transform pose = rtabmap_ros::transformFromPoseMsg(msg->pose.pose);
00063 if(pose.isNull())
00064 {
00065 ROS_WARN("Odometry received is null! Cannot send tf...");
00066 }
00067 else
00068 {
00069 t.child_frame_id = frameId_;
00070 t.header.frame_id = odomFrameId_;
00071 t.header.stamp = msg->header.stamp;
00072 rtabmap_ros::transformToGeometryMsg(pose, t.transform);
00073 tfBroadcaster_.sendTransform(t);
00074 }
00075 }
00076
00077 private:
00078 std::string frameId_;
00079 std::string odomFrameId_;
00080
00081 ros::Subscriber odomTopic_;
00082 tf2_ros::TransformBroadcaster tfBroadcaster_;
00083 };
00084
00085
00086 int main(int argc, char** argv)
00087 {
00088 ros::init(argc, argv, "odom_msg_to_tf");
00089 OdomMsgToTF odomToTf;
00090 ros::spin();
00091 return 0;
00092 }