#include <base_local_planner/goal_functions.h>#include <ros/ros.h>#include <tf/transform_listener.h>#include <tf/transform_datatypes.h>#include <nav_msgs/Odometry.h>#include <nav_msgs/Path.h>#include <geometry_msgs/PoseStamped.h>#include <geometry_msgs/Twist.h>#include <geometry_msgs/Point.h>#include <string>#include <cmath>#include <angles/angles.h>#include <costmap_2d/costmap_2d.h>#include <costmap_2d/costmap_2d_ros.h>

Go to the source code of this file.
Namespaces | |
| namespace | base_local_planner |
Functions | |
| double | base_local_planner::distance (double x1, double y1, double x2, double y2) |
| Compute the distance between two points. | |
| bool | base_local_planner::goalOrientationReached (const tf::Stamped< tf::Pose > &global_pose, double goal_th, double yaw_goal_tolerance) |
| Check if the goal orientation has been achieved. | |
| bool | base_local_planner::goalPositionReached (const tf::Stamped< tf::Pose > &global_pose, double goal_x, double goal_y, double xy_goal_tolerance) |
| Check if the goal position has been achieved. | |
| bool | base_local_planner::isGoalReached (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap_ros, const std::string &global_frame, const nav_msgs::Odometry &base_odom, double rot_stopped_vel, double trans_stopped_vel, double xy_goal_tolerance, double yaw_goal_tolerance) |
| Check if the goal pose has been achieved. | |
| void | base_local_planner::prunePlan (const tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan) |
| Trim off parts of the global plan that are far enough behind the robot. | |
| void | base_local_planner::publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub, double r, double g, double b, double a) |
| Publish a plan for visualization purposes. | |
| bool | base_local_planner::stopped (const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity) |
| Check whether the robot is stopped or not. | |
| bool | base_local_planner::transformGlobalPlan (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan) |
| Transforms the global plan of the robot from the planner frame to the local frame. | |