Provides a simple global planner that will compute a valid goal point for the local planner by walking back along the vector between the robot and the user-specified goal point until a valid cost is found. More...
#include <carrot_planner.h>

Public Member Functions | |
| CarrotPlanner () | |
| Constructor for the CarrotPlanner. More... | |
| CarrotPlanner (std::string name, costmap_2d::Costmap2DROS *costmap_ros) | |
| Constructor for the CarrotPlanner. More... | |
| void | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) |
| Initialization function for the CarrotPlanner. More... | |
| bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) |
| Given a goal pose in the world, compute a plan. More... | |
Public Member Functions inherited from nav_core::BaseGlobalPlanner | |
| virtual bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost) |
| virtual | ~BaseGlobalPlanner () |
Private Member Functions | |
| double | footprintCost (double x_i, double y_i, double theta_i) |
| Checks the legality of the robot footprint at a position and orientation using the world model. More... | |
Private Attributes | |
| costmap_2d::Costmap2D * | costmap_ |
| costmap_2d::Costmap2DROS * | costmap_ros_ |
| bool | initialized_ |
| double | min_dist_from_robot_ |
| double | step_size_ |
| base_local_planner::WorldModel * | world_model_ |
| The world model that the controller will use. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from nav_core::BaseGlobalPlanner | |
| BaseGlobalPlanner () | |
Provides a simple global planner that will compute a valid goal point for the local planner by walking back along the vector between the robot and the user-specified goal point until a valid cost is found.
Definition at line 58 of file carrot_planner.h.
| carrot_planner::CarrotPlanner::CarrotPlanner | ( | ) |
Constructor for the CarrotPlanner.
Definition at line 45 of file carrot_planner.cpp.
| carrot_planner::CarrotPlanner::CarrotPlanner | ( | std::string | name, |
| costmap_2d::Costmap2DROS * | costmap_ros | ||
| ) |
Constructor for the CarrotPlanner.
| name | The name of this planner |
| costmap_ros | A pointer to the ROS wrapper of the costmap to use for planning |
Definition at line 48 of file carrot_planner.cpp.
|
private |
Checks the legality of the robot footprint at a position and orientation using the world model.
| x_i | The x position of the robot |
| y_i | The y position of the robot |
| theta_i | The orientation of the robot |
Definition at line 70 of file carrot_planner.cpp.
|
virtual |
Initialization function for the CarrotPlanner.
| name | The name of this planner |
| costmap_ros | A pointer to the ROS wrapper of the costmap to use for planning |
Implements nav_core::BaseGlobalPlanner.
Definition at line 53 of file carrot_planner.cpp.
|
virtual |
Given a goal pose in the world, compute a plan.
| start | The start pose |
| goal | The goal pose |
| plan | The plan... filled by the planner |
Implements nav_core::BaseGlobalPlanner.
Definition at line 87 of file carrot_planner.cpp.
|
private |
Definition at line 91 of file carrot_planner.h.
|
private |
Definition at line 89 of file carrot_planner.h.
|
private |
Definition at line 103 of file carrot_planner.h.
|
private |
Definition at line 90 of file carrot_planner.h.
|
private |
Definition at line 90 of file carrot_planner.h.
|
private |
The world model that the controller will use.
Definition at line 92 of file carrot_planner.h.