41 #ifndef MBF_UTILITY__NAVIGATION_UTILITY_H_ 42 #define MBF_UTILITY__NAVIGATION_UTILITY_H_ 44 #include <geometry_msgs/PoseStamped.h> 67 const std::string &target_frame,
69 const geometry_msgs::PointStamped &in,
70 geometry_msgs::PointStamped &out);
82 const std::string &target_frame,
84 const geometry_msgs::PoseStamped &in,
85 geometry_msgs::PoseStamped &out);
97 const std::string &robot_frame,
98 const std::string &global_frame,
100 geometry_msgs::PoseStamped &robot_pose);
107 double distance(
const geometry_msgs::PoseStamped &pose1,
const geometry_msgs::PoseStamped &pose2);
115 double angle(
const geometry_msgs::PoseStamped &pose1,
const geometry_msgs::PoseStamped &pose2);
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.