38 #ifndef ABSTRACT_LOCAL_PLANNER_ODOM_H_ 39 #define ABSTRACT_LOCAL_PLANNER_ODOM_H_ 43 #include <boost/thread.hpp> 92 std::string global_frame);
96 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
std::string getGlobalFrame()
tf::TransformListener * tf_
bool getGoal(tf::Stamped< tf::Pose > &goal_pose)
void reconfigureCB(LocalPlannerLimits &config, bool restore_defaults)
Callback to update the local planner's parameters.
costmap_2d::Costmap2D * getCostmap()
bool getLocalPlan(tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
boost::mutex limits_configuration_mutex_
LocalPlannerLimits default_limits_
void initialize(tf::TransformListener *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
LocalPlannerLimits getCurrentLimits()
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
std::vector< geometry_msgs::PoseStamped > global_plan_
std::string global_frame_
LocalPlannerLimits limits_
Helper class implementing infrastructure code many local planner implementations may need...
costmap_2d::Costmap2D * costmap_