00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2012, PAL Robotics, S.L. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of PAL Robotics, S.L. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00044 #include <ros/ros.h> 00045 #include <tf/transform_broadcaster.h> 00046 #include <geometry_msgs/Pose.h> 00047 #include <string> 00048 00049 std::string parent_name; 00050 std::string child_name; 00051 bool pose_received; 00052 geometry_msgs::Pose last_pose; 00053 00054 void poseCallback(const geometry_msgs::Pose &msg) 00055 { 00056 last_pose = msg; 00057 pose_received = true; 00058 } 00059 00060 int main(int argc, char** argv){ 00061 ros::init(argc, argv, "pose2Tf"); 00062 ros::NodeHandle nh; 00063 if(argc < 3) 00064 { 00065 ROS_ERROR("pose2Tf node requires a parent and a child name to publish to tf."); 00066 return -1; 00067 } 00068 00069 parent_name = std::string(argv[1]); 00070 child_name = std::string(argv[2]); 00071 00072 pose_received = false; 00073 ros::Subscriber sub = nh.subscribe("/pose", 10, &poseCallback); 00074 static tf::TransformBroadcaster br; 00075 00076 while(ros::ok()) 00077 { 00078 ros::spinOnce(); 00079 if(pose_received) 00080 { 00081 tf::Transform target_transform; 00082 tf::poseMsgToTF(last_pose, target_transform); 00083 br.sendTransform(tf::StampedTransform( 00084 target_transform, ros::Time::now(), 00085 parent_name, child_name)); 00086 } 00087 } 00088 00089 return 0; 00090 };