Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #ifndef MBF_UTILITY__NAVIGATION_UTILITY_H_
00042 #define MBF_UTILITY__NAVIGATION_UTILITY_H_
00043
00044 #include <geometry_msgs/PoseStamped.h>
00045 #include <ros/duration.h>
00046 #include <ros/time.h>
00047 #include <string>
00048 #include <tf/transform_listener.h>
00049 #include <tf2/convert.h>
00050 #include <tf2_ros/buffer.h>
00051 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00052
00053 #include <mbf_utility/types.h>
00054
00055 namespace mbf_utility
00056 {
00057
00069 bool transformPoint(const TF &tf,
00070 const std::string &target_frame,
00071 const ros::Time &target_time,
00072 const ros::Duration &timeout,
00073 const geometry_msgs::PointStamped &in,
00074 const std::string &fixed_frame,
00075 geometry_msgs::PointStamped &out);
00076
00088 bool transformPose(const TF &tf,
00089 const std::string &target_frame,
00090 const ros::Time &target_time,
00091 const ros::Duration &timeout,
00092 const geometry_msgs::PoseStamped &in,
00093 const std::string &fixed_frame,
00094 geometry_msgs::PoseStamped &out);
00095
00105 bool getRobotPose(const TF &tf,
00106 const std::string &robot_frame,
00107 const std::string &global_frame,
00108 const ros::Duration &timeout,
00109 geometry_msgs::PoseStamped &robot_pose);
00116 double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2);
00117
00124 double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2);
00125
00126 }
00127
00128 #endif