8#include <nav_core/base_global_planner.h> 
    9#include <nav_msgs/GetPlan.h> 
   10#include <nav_msgs/Path.h> 
   15namespace backward_global_planner
 
   24    bool makePlan(
const geometry_msgs::PoseStamped &start,
 
   25                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);
 
   27    bool makePlan(
const geometry_msgs::PoseStamped &start,
 
   28                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,
 
   32                                           const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);
 
   47    void publishGoalMarker(
const geometry_msgs::Pose &pose, 
double r, 
double g, 
double b);
 
double skip_straight_motion_distance_
 
double puresSpinningRadStep_
 
virtual bool createDefaultBackwardPath(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 
virtual ~BackwardGlobalPlanner()
 
void publishGoalMarker(const geometry_msgs::Pose &pose, double r, double g, double b)
 
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 
void onForwardTrailMsg(const nav_msgs::Path::ConstPtr &trailMessage)
 
ros::Publisher markersPub_
 
costmap_2d::Costmap2DROS * costmap_ros_
 
virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_) override