37 #ifndef CARROT_PLANNER_H_ 38 #define CARROT_PLANNER_H_ 44 #include <geometry_msgs/PoseStamped.h> 85 bool makePlan(
const geometry_msgs::PoseStamped& start,
86 const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
101 double footprintCost(
double x_i,
double y_i,
double theta_i);
double min_dist_from_robot_
costmap_2d::Costmap2DROS * costmap_ros_
base_local_planner::WorldModel * world_model_
The world model that the controller will use.
costmap_2d::Costmap2D * costmap_
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.
Provides a simple global planner that will compute a valid goal point for the local planner by walkin...
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the CarrotPlanner.
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...
CarrotPlanner()
Constructor for the CarrotPlanner.