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>
43 #include <string>
44 
45 namespace nav_2d_utils
46 {
58 bool transformPose(const TFListenerPtr tf, const std::string frame,
59  const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose,
60  const bool extrapolation_fallback = true)
61 {
62  if (in_pose.header.frame_id == frame)
63  {
64  out_pose = in_pose;
65  return true;
66  }
67 
68  try
69  {
70  tf->transform(in_pose, out_pose, frame);
71  return true;
72  }
73  catch (tf::ExtrapolationException& ex)
74  {
75  if (!extrapolation_fallback)
76  throw;
77  geometry_msgs::PoseStamped latest_in_pose;
78  latest_in_pose.header.frame_id = in_pose.header.frame_id;
79  latest_in_pose.pose = in_pose.pose;
80  tf->transform(latest_in_pose, out_pose, frame);
81  return true;
82  }
83  catch (tf::TransformException& ex)
84  {
85  ROS_ERROR("Exception in transformPose: %s", ex.what());
86  return false;
87  }
88  return false;
89 }
90 
102 bool transformPose(const TFListenerPtr tf, const std::string frame,
103  const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose,
104  const bool extrapolation_fallback = true)
105 {
106  geometry_msgs::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
107  geometry_msgs::PoseStamped out_3d_pose;
108 
109  bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback);
110  if (ret)
111  {
112  out_pose = poseStampedToPose2D(out_3d_pose);
113  }
114  return ret;
115 }
116 
117 geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped& pose,
118  const std::string& frame_id)
119 {
120  nav_2d_msgs::Pose2DStamped local_pose;
121  nav_2d_utils::transformPose(tf, frame_id, pose, local_pose);
122  return local_pose.pose;
123 }
124 
125 } // namespace nav_2d_utils
126 
127 #endif // NAV_2D_UTILS_TF_HELP_H
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
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:58
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped &pose, const std::string &frame_id)
Definition: tf_help.h:117
#define ROS_ERROR(...)


nav_2d_utils
Author(s):
autogenerated on Mon Feb 28 2022 23:32:46