Public Member Functions | Private Member Functions | Private Attributes
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>

Inheritance diagram for carrot_planner::CarrotPlanner:
Inheritance graph
[legend]

List of all members.

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

costmap_2d::Costmap2Dcostmap_
costmap_2d::Costmap2DROScostmap_ros_
bool initialized_
double min_dist_from_robot_
double step_size_
base_local_planner::WorldModelworld_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 58 of file carrot_planner.h.


Constructor & Destructor Documentation

Constructor for the CarrotPlanner.

Definition at line 45 of file carrot_planner.cpp.

Constructor for the CarrotPlanner.

Parameters:
nameThe name of this planner
costmap_rosA pointer to the ROS wrapper of the costmap to use for planning

Definition at line 48 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_iThe x position of the robot
y_iThe y position of the robot
theta_iThe orientation of the robot
Returns:

Definition at line 70 of file carrot_planner.cpp.

void carrot_planner::CarrotPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
) [virtual]

Initialization function for the CarrotPlanner.

Parameters:
nameThe name of this planner
costmap_rosA 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.

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

Implements nav_core::BaseGlobalPlanner.

Definition at line 87 of file carrot_planner.cpp.


Member Data Documentation

Definition at line 91 of file carrot_planner.h.

Definition at line 89 of file carrot_planner.h.

Definition at line 103 of file carrot_planner.h.

Definition at line 90 of file carrot_planner.h.

Definition at line 90 of file carrot_planner.h.

The world model that the controller will use.

Definition at line 92 of file carrot_planner.h.


The documentation for this class was generated from the following files:


carrot_planner
Author(s): Eitan Marder-Eppstein, Sachin Chitta, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:51