transform_listener.h
Go to the documentation of this file.
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 
00032 #ifndef TF_TRANSFORMLISTENER_H
00033 #define TF_TRANSFORMLISTENER_H
00034 
00035 #include "sensor_msgs/PointCloud.h"
00036 #include "std_msgs/Empty.h"
00037 #include "tf/tfMessage.h"
00038 #include "tf/tf.h"
00039 #include "ros/ros.h"
00040 #include "ros/callback_queue.h"
00041 
00042 #include "tf/FrameGraph.h" //frame graph service
00043 #include "boost/thread.hpp"
00044 
00045 namespace tf{
00046 
00051 inline std::string getPrefixParam(ros::NodeHandle & nh) {
00052   std::string param; 
00053   if (!nh.searchParam("tf_prefix", param)) 
00054     return ""; 
00055   
00056   std::string return_val;
00057   nh.getParam(param, return_val);
00058   return return_val;
00059 }
00060 
00063 std::string remap(const std::string& frame_id) __attribute__((deprecated));
00064 
00066 class TransformListener : public Transformer { //subscribes to message and automatically stores incoming data
00067 
00068 public:
00071   TransformListener(ros::Duration max_cache_time = ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread = true);
00072 
00078   TransformListener(const ros::NodeHandle& nh,
00079                     ros::Duration max_cache_time = ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread = true);
00080   
00081   ~TransformListener();
00082 
00083   /* Methods from transformer unhiding them here */
00084   using Transformer::transformQuaternion;
00085   using Transformer::transformVector;
00086   using Transformer::transformPoint;
00087   using Transformer::transformPose;
00088 
00089 
00092   void transformQuaternion(const std::string& target_frame, const geometry_msgs::QuaternionStamped& stamped_in, geometry_msgs::QuaternionStamped& stamped_out) const;
00095   void transformVector(const std::string& target_frame, const geometry_msgs::Vector3Stamped& stamped_in, geometry_msgs::Vector3Stamped& stamped_out) const;
00098   void transformPoint(const std::string& target_frame, const geometry_msgs::PointStamped& stamped_in, geometry_msgs::PointStamped& stamped_out) const;
00101   void transformPose(const std::string& target_frame, const geometry_msgs::PoseStamped& stamped_in, geometry_msgs::PoseStamped& stamped_out) const;
00102 
00105   // http://www.ros.org/wiki/tf/Reviews/2010-03-12_API_Review
00106   //  void transformTwist(const std::string& target_frame, const geometry_msgs::TwistStamped& stamped_in, geometry_msgs::TwistStamped& stamped_out) const;
00107 
00110   void transformQuaternion(const std::string& target_frame, const ros::Time& target_time,
00111                            const geometry_msgs::QuaternionStamped& qin,
00112                            const std::string& fixed_frame, geometry_msgs::QuaternionStamped& qout) const;
00115   void transformVector(const std::string& target_frame, const ros::Time& target_time,
00116                        const geometry_msgs::Vector3Stamped& vin,
00117                            const std::string& fixed_frame, geometry_msgs::Vector3Stamped& vout) const;
00120   void transformPoint(const std::string& target_frame, const ros::Time& target_time,
00121                            const geometry_msgs::PointStamped& pin,
00122                            const std::string& fixed_frame, geometry_msgs::PointStamped& pout) const;
00125   void transformPose(const std::string& target_frame, const ros::Time& target_time,
00126                      const geometry_msgs::PoseStamped& pin,
00127                      const std::string& fixed_frame, geometry_msgs::PoseStamped& pout) const;
00128 
00129 
00132     void transformPointCloud(const std::string& target_frame, const sensor_msgs::PointCloud& pcin, sensor_msgs::PointCloud& pcout) const;
00133 
00136   void transformPointCloud(const std::string& target_frame, const ros::Time& target_time,
00137                            const sensor_msgs::PointCloud& pcin,
00138                            const std::string& fixed_frame, sensor_msgs::PointCloud& pcout) const;
00139 
00140 
00141 
00143 
00144   bool getFrames(tf::FrameGraph::Request& req, tf::FrameGraph::Response& res) 
00145   {
00146     res.dot_graph = allFramesAsDot();
00147     return true;
00148   }
00149 
00150   /* \brief Resolve frame_name into a frame_id using tf_prefix parameter */
00151   std::string resolve(const std::string& frame_name)
00152   {
00153     return tf::resolve(tf_prefix_, frame_name);
00154   };
00155 
00156 protected:
00157   bool ok() const;
00158 
00159 private:
00161   ros::Time last_update_ros_time_;
00162 
00164   void init();
00165   void initWithThread();
00166 
00168   void subscription_callback(const tf::tfMessageConstPtr& msg);
00169 
00171   void transformPointCloud(const std::string & target_frame, const Transform& transform, const ros::Time& target_time, const sensor_msgs::PointCloud& pcin, sensor_msgs::PointCloud& pcout) const;
00172 
00174   std_msgs::Empty empty_;
00175   ros::ServiceServer tf_frames_srv_;
00176 
00177 
00178   ros::CallbackQueue tf_message_callback_queue_;
00179   boost::thread* dedicated_listener_thread_;
00180   ros::NodeHandle node_;
00181   ros::Subscriber message_subscriber_tf_, reset_time_subscriber_;
00182 
00183   void dedicatedListenerThread()
00184   {
00185     while (using_dedicated_thread_)
00186     {
00187       tf_message_callback_queue_.callAvailable(ros::WallDuration(0.01));
00188     }
00189   };
00190 
00191 };
00192 }
00193 
00194 #endif //TF_TRANSFORMLISTENER_H


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 6 2014 00:12:04