tf_help.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV_2D_UTILS_TF_HELP_H
36 #define NAV_2D_UTILS_TF_HELP_H
37 
38 #include <nav_core2/common.h>
40 #include <geometry_msgs/PoseStamped.h>
41 #include <nav_2d_msgs/Pose2DStamped.h>
42 #include <string>
43 
44 namespace nav_2d_utils
45 {
57 bool transformPose(const TFListenerPtr tf, const std::string frame,
58  const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose,
59  const bool extrapolation_fallback = true)
60 {
61  if (in_pose.header.frame_id == frame)
62  {
63  out_pose = in_pose;
64  return true;
65  }
66 
67  try
68  {
69  tf->transformPose(frame, in_pose, out_pose);
70  return true;
71  }
72  catch (tf::ExtrapolationException& ex)
73  {
74  if (!extrapolation_fallback)
75  throw;
76  geometry_msgs::PoseStamped latest_in_pose;
77  latest_in_pose.header.frame_id = in_pose.header.frame_id;
78  latest_in_pose.pose = in_pose.pose;
79  tf->transformPose(frame, latest_in_pose, out_pose);
80  return true;
81  }
82  catch (tf::TransformException& ex)
83  {
84  ROS_ERROR("Exception in transformPose: %s", ex.what());
85  return false;
86  }
87  return false;
88 }
89 
101 bool transformPose(const TFListenerPtr tf, const std::string frame,
102  const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose,
103  const bool extrapolation_fallback = true)
104 {
105  geometry_msgs::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
106  geometry_msgs::PoseStamped out_3d_pose;
107 
108  bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback);
109  if (ret)
110  {
111  out_pose = poseStampedToPose2D(out_3d_pose);
112  }
113  return ret;
114 }
115 
116 geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped& pose,
117  const std::string& frame_id)
118 {
119  nav_2d_msgs::Pose2DStamped local_pose;
120  nav_2d_utils::transformPose(tf, frame_id, pose, local_pose);
121  return local_pose.pose;
122 }
123 
124 } // namespace nav_2d_utils
125 
126 #endif // NAV_2D_UTILS_TF_HELP_H
bool transformPose(const TFListenerPtr tf, const std::string frame, const geometry_msgs::PoseStamped &in_pose, geometry_msgs::PoseStamped &out_pose, const bool extrapolation_fallback=true)
Transform a PoseStamped from one frame to another while catching exceptions.
Definition: tf_help.h:57
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
Definition: conversions.cpp:71
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
Definition: conversions.cpp:90
geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped &pose, const std::string &frame_id)
Definition: tf_help.h:116
std::shared_ptr< tf::TransformListener > TFListenerPtr
#define ROS_ERROR(...)


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:06:11