tf_help.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
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 the copyright holder 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 HOLDER 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 
00035 #ifndef NAV_2D_UTILS_TF_HELP_H
00036 #define NAV_2D_UTILS_TF_HELP_H
00037 
00038 #include <nav_core2/common.h>
00039 #include <nav_2d_utils/conversions.h>
00040 #include <geometry_msgs/PoseStamped.h>
00041 #include <nav_2d_msgs/Pose2DStamped.h>
00042 #include <string>
00043 
00044 namespace nav_2d_utils
00045 {
00057 bool transformPose(const TFListenerPtr tf, const std::string frame,
00058                    const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose,
00059                    const bool extrapolation_fallback = true)
00060 {
00061   if (in_pose.header.frame_id == frame)
00062   {
00063     out_pose = in_pose;
00064     return true;
00065   }
00066 
00067   try
00068   {
00069     tf->transformPose(frame, in_pose, out_pose);
00070     return true;
00071   }
00072   catch (tf::ExtrapolationException& ex)
00073   {
00074     if (!extrapolation_fallback)
00075       throw;
00076     geometry_msgs::PoseStamped latest_in_pose;
00077     latest_in_pose.header.frame_id = in_pose.header.frame_id;
00078     latest_in_pose.pose = in_pose.pose;
00079     tf->transformPose(frame, latest_in_pose, out_pose);
00080     return true;
00081   }
00082   catch (tf::TransformException& ex)
00083   {
00084     ROS_ERROR("Exception in transformPose: %s", ex.what());
00085     return false;
00086   }
00087   return false;
00088 }
00089 
00101 bool transformPose(const TFListenerPtr tf, const std::string frame,
00102                    const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose,
00103                    const bool extrapolation_fallback = true)
00104 {
00105   geometry_msgs::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
00106   geometry_msgs::PoseStamped out_3d_pose;
00107 
00108   bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback);
00109   if (ret)
00110   {
00111     out_pose = poseStampedToPose2D(out_3d_pose);
00112   }
00113   return ret;
00114 }
00115 
00116 geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped& pose,
00117                                            const std::string& frame_id)
00118 {
00119   nav_2d_msgs::Pose2DStamped local_pose;
00120   nav_2d_utils::transformPose(tf, frame_id, pose, local_pose);
00121   return local_pose.pose;
00122 }
00123 
00124 }  // namespace nav_2d_utils
00125 
00126 #endif  // NAV_2D_UTILS_TF_HELP_H


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:09:36