7#include <nav_core/base_global_planner.h>
8#include <nav_msgs/GetPlan.h>
9#include <nav_msgs/Path.h>
14namespace forward_global_planner
21 bool makePlan(
const geometry_msgs::PoseStamped &start,
22 const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);
24 bool makePlan(
const geometry_msgs::PoseStamped &start,
25 const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_)
double puresSpinningRadStep_
costmap_2d::Costmap2DROS * costmap_ros_
stored but almost not used
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
double skip_straight_motion_distance_