Classes | |
| struct | ExePathException | 
| struct | GetPathException | 
| struct | RecoveryException | 
| class | RobotInformation | 
Functions | |
| double | angle (const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) | 
| computes the smallest angle between two poses.  More... | |
| double | distance (const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) | 
| Computes the Euclidean-distance between two poses.  More... | |
| 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.  More... | |
| static bool | isNormalized (const geometry_msgs::Quaternion &_q, double _epsilon) | 
| Returns true, if the given quaternion is normalized.  More... | |
| 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.  More... | |
| 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.  More... | |
| 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 197 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 187 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 50 of file navigation_utility.cpp.
      
  | 
  static | 
Returns true, if the given quaternion is normalized.
| _q | The quaternion to check. | 
| _epsilon | The epsilon (squared distance to 1). | 
Definition at line 80 of file navigation_utility.cpp.
| bool mbf_utility::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.
| tf_listener | TransformListener. | 
| target_frame | Target frame for the point. | 
| timeout | Timeout for looking up the transformation. | 
| in | Point to transform. | 
| out | Transformed point. | 
Definition at line 140 of file navigation_utility.cpp.
| bool mbf_utility::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.
| tf_listener | TransformListener. | 
| target_frame | Target frame for the pose. | 
| timeout | Timeout for looking up the transformation. | 
| in | Pose to transform. | 
| out | Transformed pose. | 
Definition at line 86 of file navigation_utility.cpp.