Go to the documentation of this file.
37 #ifndef SBPL_RECOVERY_SBPL_RECOVERY_H_
38 #define SBPL_RECOVERY_SBPL_RECOVERY_H_
45 #include <geometry_msgs/PoseStamped.h>
46 #include <nav_msgs/Path.h>
47 #include <boost/thread.hpp>
67 void planCB(
const nav_msgs::Path::ConstPtr& plan);
68 double sqDistance(
const geometry_msgs::PoseStamped& p1,
69 const geometry_msgs::PoseStamped& p2);
70 std::vector<geometry_msgs::PoseStamped>
makePlan();
std::vector< geometry_msgs::PoseStamped > makePlan()
double sq_planning_distance_
void planCB(const nav_msgs::Path::ConstPtr &plan)
costmap_2d::Costmap2DROS * global_costmap_
double control_frequency_
ros::Subscriber plan_sub_
sbpl_lattice_planner::SBPLLatticePlanner global_planner_
void initialize(std::string n, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
pose_follower::PoseFollower local_planner_
double sqDistance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
double controller_patience_
costmap_2d::Costmap2DROS * local_costmap_
sbpl_recovery
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Aug 26 2022 02:17:55