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. | |
CarrotPlanner (std::string name, costmap_2d::Costmap2DROS *costmap_ros) | |
Constructor for the CarrotPlanner. | |
void | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) |
Initialization function for the CarrotPlanner. | |
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. | |
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. | |
Private Attributes | |
double | circumscribed_radius_ |
costmap_2d::Costmap2D | costmap_ |
costmap_2d::Costmap2DROS * | costmap_ros_ |
std::vector< geometry_msgs::Point > | footprint_spec_ |
The footprint specification of the robot. | |
double | inflation_radius_ |
bool | initialized_ |
double | inscribed_radius_ |
double | min_dist_from_robot_ |
double | step_size_ |
base_local_planner::WorldModel * | world_model_ |
The world model that the controller will use. |
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 60 of file carrot_planner.h.
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.
double carrot_planner::CarrotPlanner::footprintCost | ( | double | x_i, |
double | y_i, | ||
double | theta_i | ||
) | [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 77 of file carrot_planner.cpp.
void carrot_planner::CarrotPlanner::initialize | ( | std::string | name, |
costmap_2d::Costmap2DROS * | costmap_ros | ||
) | [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.
bool carrot_planner::CarrotPlanner::makePlan | ( | const geometry_msgs::PoseStamped & | start, |
const geometry_msgs::PoseStamped & | goal, | ||
std::vector< geometry_msgs::PoseStamped > & | plan | ||
) | [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 107 of file carrot_planner.cpp.
double carrot_planner::CarrotPlanner::circumscribed_radius_ [private] |
Definition at line 95 of file carrot_planner.h.
Definition at line 93 of file carrot_planner.h.
Definition at line 91 of file carrot_planner.h.
std::vector<geometry_msgs::Point> carrot_planner::CarrotPlanner::footprint_spec_ [private] |
The footprint specification of the robot.
Definition at line 106 of file carrot_planner.h.
double carrot_planner::CarrotPlanner::inflation_radius_ [private] |
Definition at line 95 of file carrot_planner.h.
bool carrot_planner::CarrotPlanner::initialized_ [private] |
Definition at line 107 of file carrot_planner.h.
double carrot_planner::CarrotPlanner::inscribed_radius_ [private] |
Definition at line 95 of file carrot_planner.h.
double carrot_planner::CarrotPlanner::min_dist_from_robot_ [private] |
Definition at line 92 of file carrot_planner.h.
double carrot_planner::CarrotPlanner::step_size_ [private] |
Definition at line 92 of file carrot_planner.h.
The world model that the controller will use.
Definition at line 94 of file carrot_planner.h.