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 <tf/tf.h>
00031 #include <tf/transform_broadcaster.h>
00032 #include <rtabmap_ros/MsgConversion.h>
00033
00034 class OdomMsgToTF
00035 {
00036
00037 public:
00038 OdomMsgToTF() :
00039 frameId_(""),
00040 odomFrameId_("")
00041 {
00042 ros::NodeHandle pnh("~");
00043 pnh.param("frame_id", frameId_, frameId_);
00044 pnh.param("odom_frame_id", odomFrameId_, odomFrameId_);
00045
00046 ros::NodeHandle nh;
00047 odomTopic_ = nh.subscribe("odom", 1, &OdomMsgToTF::odomReceivedCallback, this);
00048 }
00049
00050 virtual ~OdomMsgToTF(){}
00051
00052 void odomReceivedCallback(const nav_msgs::OdometryConstPtr & msg)
00053 {
00054 if(frameId_.empty())
00055 {
00056 frameId_ = msg->child_frame_id;
00057 }
00058 if(odomFrameId_.empty())
00059 {
00060 odomFrameId_ = msg->header.frame_id;
00061 }
00062 tf::StampedTransform t;
00063 rtabmap::Transform pose = rtabmap_ros::transformFromPoseMsg(msg->pose.pose);
00064 if(pose.isNull())
00065 {
00066 ROS_WARN("Odometry received is null! Cannot send tf...");
00067 }
00068 else
00069 {
00070 rtabmap_ros::transformToTF(pose, t);
00071 tfBroadcaster_.sendTransform(tf::StampedTransform (t, msg->header.stamp, odomFrameId_, frameId_));
00072 }
00073 }
00074
00075 private:
00076 std::string frameId_;
00077 std::string odomFrameId_;
00078
00079 ros::Subscriber odomTopic_;
00080 tf::TransformBroadcaster tfBroadcaster_;
00081 };
00082
00083
00084 int main(int argc, char** argv)
00085 {
00086 ros::init(argc, argv, "odom_msg_to_tf");
00087 OdomMsgToTF odomToTf;
00088 ros::spin();
00089 return 0;
00090 }