$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 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 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00039 #include <flirtlib_ros/common.h> 00040 00041 namespace flirtlib_ros 00042 { 00043 00044 gm::Pose getCurrentPose (const tf::TransformListener& tf, 00045 const std::string& frame) 00046 { 00047 tf::StampedTransform trans; 00048 tf.lookupTransform("/map", frame, ros::Time(), trans); 00049 gm::Pose pose; 00050 tf::poseTFToMsg(trans, pose); 00051 return pose; 00052 } 00053 00054 00055 gm::Pose makePose (const double x, const double y, const double theta) 00056 { 00057 gm::Pose p; 00058 p.position.x = x; 00059 p.position.y = y; 00060 p.orientation = tf::createQuaternionMsgFromYaw(theta); 00061 return p; 00062 } 00063 00064 gm::Pose transformPose (const gm::Pose& p, const OrientedPoint2D& trans) 00065 { 00066 tf::Transform laser_pose(tf::Quaternion(0, 0, 0, 1), tf::Vector3(-0.275, 0, 0)); 00067 tf::Transform tr; 00068 tf::poseMsgToTF(p, tr); 00069 tf::Transform rel(tf::createQuaternionFromYaw(trans.theta), 00070 tf::Vector3(trans.x, trans.y, 0.0)); 00071 gm::Pose ret; 00072 tf::poseTFToMsg(tr*rel*laser_pose, ret); 00073 return ret; 00074 } 00075 00076 gm::Pose transformPose (const tf::Transform& trans, const gm::Pose& pose) 00077 { 00078 tf::Transform p; 00079 tf::poseMsgToTF(pose, p); 00080 gm::Pose ret; 00081 tf::poseTFToMsg(trans*p, ret); 00082 return ret; 00083 } 00084 00085 tf::Transform getLaserOffset (const tf::TransformListener& tf) 00086 { 00087 const std::string LASER_FRAME = "base_laser_link"; 00088 const std::string BASE_FRAME = "base_footprint"; 00089 while (ros::ok()) 00090 { 00091 tf.waitForTransform(LASER_FRAME, BASE_FRAME, ros::Time(), 00092 ros::Duration(5.0)); 00093 try { 00094 tf::StampedTransform trans; 00095 tf.lookupTransform(LASER_FRAME, BASE_FRAME, ros::Time(), 00096 trans); 00097 return trans; 00098 } 00099 catch (tf::TransformException& e) 00100 { 00101 ROS_INFO ("Waiting for transform between %s and %s", 00102 LASER_FRAME.c_str(), BASE_FRAME.c_str()); 00103 } 00104 } 00105 return tf::Transform(); // Should never happen 00106 } 00107 00108 } // namespace