tf_help.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * 2022, Metro Robots
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the copyright holder nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #include <nav_2d_utils/tf_help.h>
37 #include <nav_2d_msgs/Pose2DStamped.h>
40 #include <string>
41 
42 namespace nav_2d_utils
43 {
44 bool transformPose(const TFListenerPtr tf, const std::string frame,
45  const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose,
46  const bool extrapolation_fallback)
47 {
48  if (in_pose.header.frame_id == frame)
49  {
50  out_pose = in_pose;
51  return true;
52  }
53 
54  try
55  {
56  tf->transform(in_pose, out_pose, frame);
57  return true;
58  }
59  catch (tf::ExtrapolationException& ex)
60  {
61  if (!extrapolation_fallback)
62  throw;
63  geometry_msgs::PoseStamped latest_in_pose;
64  latest_in_pose.header.frame_id = in_pose.header.frame_id;
65  latest_in_pose.pose = in_pose.pose;
66  tf->transform(latest_in_pose, out_pose, frame);
67  return true;
68  }
69  catch (tf::TransformException& ex)
70  {
71  ROS_ERROR("Exception in transformPose: %s", ex.what());
72  return false;
73  }
74  return false;
75 }
76 
77 bool transformPose(const TFListenerPtr tf, const std::string frame,
78  const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose,
79  const bool extrapolation_fallback)
80 {
81  geometry_msgs::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose);
82  geometry_msgs::PoseStamped out_3d_pose;
83 
84  bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback);
85  if (ret)
86  {
87  out_pose = poseStampedToPose2D(out_3d_pose);
88  }
89  return ret;
90 }
91 
92 geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped& pose,
93  const std::string& frame_id)
94 {
95  nav_2d_msgs::Pose2DStamped local_pose;
96  nav_2d_utils::transformPose(tf, frame_id, pose, local_pose);
97  return local_pose.pose;
98 }
99 
100 } // namespace nav_2d_utils
conversions.h
nav_2d_utils::poseStampedToPose2D
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
Definition: conversions.cpp:103
nav_2d_utils::transformStampedPose
geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped &pose, const std::string &frame_id)
Transform a Pose2DStamped into another frame.
Definition: tf_help.cpp:92
tf2::ExtrapolationException
TFListenerPtr
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
nav_2d_utils
A set of utility functions for Bounds objects interacting with other messages/types.
Definition: bounds.h:45
tf_help.h
ROS_ERROR
#define ROS_ERROR(...)
tf2_geometry_msgs.h
tf
nav_2d_utils::transformPose
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.cpp:44
tf2::TransformException
nav_2d_utils::pose2DToPoseStamped
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
Definition: conversions.cpp:122


nav_2d_utils
Author(s):
autogenerated on Sun May 18 2025 02:47:23