navigation_utility.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * navigation_utility.cpp
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
41 #include <tf/tf.h>
42 
44 
45 namespace mbf_utility
46 {
47 
48 bool getRobotPose(const TF &tf,
49  const std::string &robot_frame,
50  const std::string &global_frame,
51  const ros::Duration &timeout,
52  geometry_msgs::PoseStamped &robot_pose)
53 {
54  geometry_msgs::PoseStamped local_pose;
55  local_pose.header.frame_id = robot_frame;
56  local_pose.header.stamp = ros::Time(0); // most recent available
57  local_pose.pose.orientation.w = 1.0;
58  bool success = transformPose(tf,
59  global_frame,
60  timeout,
61  local_pose,
62  robot_pose);
63  if (success && ros::Time::now() - robot_pose.header.stamp > timeout)
64  {
65  ROS_WARN("Most recent robot pose is %gs old (tolerance %gs)",
66  (ros::Time::now() - robot_pose.header.stamp).toSec(), timeout.toSec());
67  return false;
68  }
69  return success;
70 }
71 
72 bool transformPose(const TF &tf,
73  const std::string &target_frame,
74  const ros::Duration &timeout,
75  const geometry_msgs::PoseStamped &in,
76  geometry_msgs::PoseStamped &out)
77 {
78  std::string error_msg;
79 
80 #ifdef USE_OLD_TF
81  bool success = tf.waitForTransform(target_frame,
82  in.header.frame_id,
83  in.header.stamp,
84  timeout,
85  ros::Duration(0.01),
86  &error_msg);
87 #else
88  bool success = tf.canTransform(target_frame,
89  in.header.frame_id,
90  in.header.stamp,
91  timeout,
92  &error_msg);
93 #endif
94 
95  if (!success)
96  {
97  ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame
98  << "': " << error_msg);
99  return false;
100  }
101 
102  try
103  {
104 #ifdef USE_OLD_TF
105  tf.transformPose(target_frame, in, out);
106 #else
107  tf.transform(in, out, target_frame);
108 #endif
109  }
110  catch (const TFException &ex)
111  {
112  ROS_WARN_STREAM("Failed to transform pose from frame '" << in.header.frame_id << " ' into frame '"
113  << target_frame << "' with exception: " << ex.what());
114  return false;
115  }
116  return true;
117 }
118 
119 bool transformPoint(const TF &tf,
120  const std::string &target_frame,
121  const ros::Duration &timeout,
122  const geometry_msgs::PointStamped &in,
123  geometry_msgs::PointStamped &out)
124 {
125  std::string error_msg;
126 
127 #ifdef USE_OLD_TF
128  bool success = tf.waitForTransform(target_frame,
129  in.header.frame_id,
130  in.header.stamp,
131  timeout,
132  ros::Duration(0.01),
133  &error_msg);
134 #else
135  bool success = tf.canTransform(target_frame,
136  in.header.frame_id,
137  in.header.stamp,
138  timeout,
139  &error_msg);
140 #endif
141 
142  if (!success)
143  {
144  ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame
145  << "': " << error_msg);
146  return false;
147  }
148 
149  try
150  {
151 #ifdef USE_OLD_TF
152  tf.transformPoint(target_frame, in, out);
153 #else
154  tf.transform(in, out, target_frame);
155 #endif
156  }
157  catch (const TFException &ex)
158  {
159  ROS_WARN_STREAM("Failed to transform point from frame '" << in.header.frame_id << " ' into frame '"
160  << target_frame << "' with exception: " << ex.what());
161  return false;
162  }
163  return true;
164 }
165 
166 double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
167 {
168  const geometry_msgs::Point &p1 = pose1.pose.position;
169  const geometry_msgs::Point &p2 = pose2.pose.position;
170  const double dx = p1.x - p2.x;
171  const double dy = p1.y - p2.y;
172  const double dz = p1.z - p2.z;
173  return sqrt(dx * dx + dy * dy + dz * dz);
174 }
175 
176 double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
177 {
178  const geometry_msgs::Quaternion &q1 = pose1.pose.orientation;
179  const geometry_msgs::Quaternion &q2 = pose2.pose.orientation;
180  tf::Quaternion rot1, rot2;
181  tf::quaternionMsgToTF(q1, rot1);
182  tf::quaternionMsgToTF(q2, rot2);
183  return rot1.angleShortestPath(rot2);
184 }
185 
186 } /* namespace mbf_utility */
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
computes the smallest angle between two poses.
bool transformPoint(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PointStamped &in, geometry_msgs::PointStamped &out)
Transforms a point from one frame into another.
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
bool getRobotPose(const TF &tf, const std::string &robot_frame, const std::string &global_frame, const ros::Duration &timeout, geometry_msgs::PoseStamped &robot_pose)
Computes the robot pose.
#define ROS_WARN(...)
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
#define ROS_WARN_STREAM(args)
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
Computes the Euclidean-distance between two poses.
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
static Time now()
tfScalar angleShortestPath(const Quaternion &q) const
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, geometry_msgs::PoseStamped &out)
Transforms a pose from one frame into another.


mbf_utility
Author(s): Sebastian Pütz
autogenerated on Fri Nov 6 2020 03:56:22