Functions | |
double | angle (const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) |
computes the smallest angle between two poses. | |
double | distance (const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) |
Computes the Euclidean-distance between two poses. | |
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 | 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. |
double mbf_utility::angle | ( | const geometry_msgs::PoseStamped & | pose1, |
const geometry_msgs::PoseStamped & | pose2 | ||
) |
computes the smallest angle between two poses.
pose1 | pose 1 |
pose2 | pose 2 |
Definition at line 182 of file navigation_utility.cpp.
double mbf_utility::distance | ( | const geometry_msgs::PoseStamped & | pose1, |
const geometry_msgs::PoseStamped & | pose2 | ||
) |
Computes the Euclidean-distance between two poses.
pose1 | pose 1 |
pose2 | pose 2 |
Definition at line 172 of file navigation_utility.cpp.
bool mbf_utility::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.
tf_listener | TransformListener. |
robot_frame | frame of the robot. |
global_frame | global frame in which the robot is located. |
timeout | Timeout for looking up the transformation. |
robot_pose | the computed rebot pose in the global frame. |
Definition at line 46 of file navigation_utility.cpp.
bool mbf_utility::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.
tf_listener | TransformListener. |
target_frame | Target frame for the point. |
target_time | Time, in that the frames should be used. |
timeout | Timeout for looking up the transformation. |
in | Point to transform. |
fixed_frame | Fixed frame of the source and target frame. |
out | Transformed point. |
Definition at line 119 of file navigation_utility.cpp.
bool mbf_utility::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.
tf_listener | TransformListener. |
target_frame | Target frame for the pose. |
target_time | Time, in that the frames should be used. |
timeout | Timeout for looking up the transformation. |
in | Pose to transform. |
fixed_frame | Fixed frame of the source and target frame. |
out | Transformed pose. |
Definition at line 66 of file navigation_utility.cpp.