carrot_planner::CarrotPlanner Class Reference

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>

List of all members.

Public Member Functions

 CarrotPlanner (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Constructor for the CarrotPlanner.
 CarrotPlanner ()
 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.

Detailed Description

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 59 of file carrot_planner.h.


Constructor & Destructor Documentation

carrot_planner::CarrotPlanner::CarrotPlanner (  ) 

Constructor for the CarrotPlanner.

Definition at line 41 of file carrot_planner.cpp.

carrot_planner::CarrotPlanner::CarrotPlanner ( std::string  name,
costmap_2d::Costmap2DROS *  costmap_ros 
)

Constructor for the CarrotPlanner.

Parameters:
name The name of this planner
costmap_ros A pointer to the ROS wrapper of the costmap to use for planning

Definition at line 44 of file carrot_planner.cpp.


Member Function Documentation

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.

Parameters:
x_i The x position of the robot
y_i The y position of the robot
theta_i The orientation of the robot
Returns:

Definition at line 73 of file carrot_planner.cpp.

void carrot_planner::CarrotPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS *  costmap_ros 
)

Initialization function for the CarrotPlanner.

Parameters:
name The name of this planner
costmap_ros A pointer to the ROS wrapper of the costmap to use for planning

Definition at line 49 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 
)

Given a goal pose in the world, compute a plan.

Parameters:
start The start pose
goal The goal pose
plan The plan... filled by the planner
Returns:
True if a valid plan was found, false otherwise

Definition at line 103 of file carrot_planner.cpp.


Member Data Documentation

Definition at line 94 of file carrot_planner.h.

costmap_2d::Costmap2D carrot_planner::CarrotPlanner::costmap_ [private]

Definition at line 92 of file carrot_planner.h.

costmap_2d::Costmap2DROS* carrot_planner::CarrotPlanner::costmap_ros_ [private]

Definition at line 90 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 105 of file carrot_planner.h.

Definition at line 94 of file carrot_planner.h.

Definition at line 106 of file carrot_planner.h.

Definition at line 94 of file carrot_planner.h.

Definition at line 91 of file carrot_planner.h.

Definition at line 91 of file carrot_planner.h.

base_local_planner::WorldModel* carrot_planner::CarrotPlanner::world_model_ [private]

The world model that the controller will use.

Definition at line 93 of file carrot_planner.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables


carrot_planner
Author(s): Eitan Marder-Eppstein, Sachin Chitta
autogenerated on Fri Jan 11 09:42:57 2013