OdomMsgToTFNode.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 }


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49