navigation_utility.h
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.h
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
41 #ifndef MBF_UTILITY__NAVIGATION_UTILITY_H_
42 #define MBF_UTILITY__NAVIGATION_UTILITY_H_
43 
44 #include <geometry_msgs/PoseStamped.h>
45 #include <ros/duration.h>
46 #include <ros/time.h>
47 #include <string>
48 #include <tf2/convert.h>
49 #include <tf2_ros/buffer.h>
51 
52 #include "mbf_utility/types.h"
53 
54 namespace mbf_utility
55 {
56 
66 bool transformPoint(const TF &tf,
67  const std::string &target_frame,
68  const ros::Duration &timeout,
69  const geometry_msgs::PointStamped &in,
70  geometry_msgs::PointStamped &out);
71 
81 bool transformPose(const TF &tf,
82  const std::string &target_frame,
83  const ros::Duration &timeout,
84  const geometry_msgs::PoseStamped &in,
85  geometry_msgs::PoseStamped &out);
86 
96 bool getRobotPose(const TF &tf,
97  const std::string &robot_frame,
98  const std::string &global_frame,
99  const ros::Duration &timeout,
100  geometry_msgs::PoseStamped &robot_pose);
107 double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2);
108 
115 double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2);
116 
117 } /* namespace mbf_utility */
118 
119 #endif /* navigation_utility.h */
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.
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.
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
Computes the Euclidean-distance between two poses.
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 Mon Feb 28 2022 22:49:48