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 
42 
43 namespace mbf_utility
44 {
45 
46 bool getRobotPose(const TF &tf,
47  const std::string &robot_frame,
48  const std::string &global_frame,
49  const ros::Duration &timeout,
50  geometry_msgs::PoseStamped &robot_pose)
51 {
52  tf::Stamped<tf::Pose> local_pose;
53  local_pose.setIdentity();
54  local_pose.frame_id_ = robot_frame;
55  geometry_msgs::PoseStamped local_pose_msg;
56  tf::poseStampedTFToMsg(local_pose, local_pose_msg);
57  return transformPose(tf,
58  global_frame,
59  ros::Time(0), // most recent available
60  timeout,
61  local_pose_msg,
62  global_frame,
63  robot_pose);
64 }
65 
66 bool transformPose(const TF &tf,
67  const std::string &target_frame,
68  const ros::Time &target_time,
69  const ros::Duration &timeout,
70  const geometry_msgs::PoseStamped &in,
71  const std::string &fixed_frame,
72  geometry_msgs::PoseStamped &out)
73 {
74  std::string error_msg;
75 
76 #ifdef USE_OLD_TF
77  bool success = tf.waitForTransform(target_frame,
78  target_time,
79  in.header.frame_id,
80  in.header.stamp,
81  fixed_frame,
82  timeout,
83  ros::Duration(0.01),
84  &error_msg);
85 #else
86  bool success = tf.canTransform(target_frame,
87  target_time,
88  in.header.frame_id,
89  in.header.stamp,
90  fixed_frame,
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, target_time, in, fixed_frame, out);
106 #else
107  tf.transform(in, out, target_frame, target_time, fixed_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::Time &target_time,
122  const ros::Duration &timeout,
123  const geometry_msgs::PointStamped &in,
124  const std::string &fixed_frame,
125  geometry_msgs::PointStamped &out)
126 {
127  std::string error_msg;
128 
129 #ifdef USE_OLD_TF
130  bool success = tf.waitForTransform(target_frame,
131  target_time,
132  in.header.frame_id,
133  in.header.stamp,
134  fixed_frame,
135  timeout,
136  ros::Duration(0.01),
137  &error_msg);
138 #else
139  bool success = tf.canTransform(target_frame,
140  target_time,
141  in.header.frame_id,
142  in.header.stamp,
143  fixed_frame,
144  timeout,
145  &error_msg);
146 #endif
147 
148  if (!success)
149  {
150  ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame
151  << "': " << error_msg);
152  return false;
153  }
154 
155  try
156  {
157 #ifdef USE_OLD_TF
158  tf.transformPoint(target_frame, target_time, in, fixed_frame, out);
159 #else
160  tf.transform(in, out, target_frame, target_time, fixed_frame);
161 #endif
162  }
163  catch (const TFException &ex)
164  {
165  ROS_WARN_STREAM("Failed to transform point from frame '" << in.header.frame_id << " ' into frame '"
166  << target_frame << "' with exception: " << ex.what());
167  return false;
168  }
169  return true;
170 }
171 
172 double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
173 {
174  const geometry_msgs::Point &p1 = pose1.pose.position;
175  const geometry_msgs::Point &p2 = pose2.pose.position;
176  const double dx = p1.x - p2.x;
177  const double dy = p1.y - p2.y;
178  const double dz = p1.z - p2.z;
179  return sqrt(dx * dx + dy * dy + dz * dz);
180 }
181 
182 double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
183 {
184  const geometry_msgs::Quaternion &q1 = pose1.pose.orientation;
185  const geometry_msgs::Quaternion &q2 = pose2.pose.orientation;
186  tf::Quaternion rot1, rot2;
187  tf::quaternionMsgToTF(q1, rot1);
188  tf::quaternionMsgToTF(q2, rot2);
189  return rot1.angleShortestPath(rot2);
190 }
191 
192 } /* namespace mbf_utility */
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
computes the smallest angle between two poses.
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
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.
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.
std::string frame_id_
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
tfScalar angleShortestPath(const Quaternion &q) const
bool transformPoint(const TF &tf, const std::string &target_frame, const ros::Time &target_time, const ros::Duration &timeout, const geometry_msgs::PointStamped &in, const std::string &fixed_frame, geometry_msgs::PointStamped &out)
Transforms a point from one frame into another.
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Time &target_time, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, const std::string &fixed_frame, geometry_msgs::PoseStamped &out)
Transforms a pose from one frame into another.


mbf_utility
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:32