Public Member Functions | Private Member Functions | Private Attributes | List of all members
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]

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...
 
 ~CarrotPlanner ()
 Destructor. 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::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. More...
 

Additional Inherited Members

- Protected Member Functions inherited from nav_core::BaseGlobalPlanner
 BaseGlobalPlanner ()
 

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

Constructor & Destructor Documentation

◆ CarrotPlanner() [1/2]

carrot_planner::CarrotPlanner::CarrotPlanner ( )

Constructor for the CarrotPlanner.

Definition at line 84 of file carrot_planner.cpp.

◆ CarrotPlanner() [2/2]

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

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 87 of file carrot_planner.cpp.

◆ ~CarrotPlanner()

carrot_planner::CarrotPlanner::~CarrotPlanner ( )

Destructor.

Definition at line 92 of file carrot_planner.cpp.

Member Function Documentation

◆ footprintCost()

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 114 of file carrot_planner.cpp.

◆ initialize()

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 97 of file carrot_planner.cpp.

◆ makePlan()

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 131 of file carrot_planner.cpp.

Member Data Documentation

◆ costmap_

costmap_2d::Costmap2D* carrot_planner::CarrotPlanner::costmap_
private

Definition at line 127 of file carrot_planner.h.

◆ costmap_ros_

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

Definition at line 125 of file carrot_planner.h.

◆ initialized_

bool carrot_planner::CarrotPlanner::initialized_
private

Definition at line 139 of file carrot_planner.h.

◆ min_dist_from_robot_

double carrot_planner::CarrotPlanner::min_dist_from_robot_
private

Definition at line 126 of file carrot_planner.h.

◆ step_size_

double carrot_planner::CarrotPlanner::step_size_
private

Definition at line 126 of file carrot_planner.h.

◆ world_model_

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

The world model that the controller will use.

Definition at line 128 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 Mon Mar 6 2023 03:50:28