Go to the documentation of this file.
38 #ifndef ABSTRACT_LOCAL_PLANNER_ODOM_H_
39 #define ABSTRACT_LOCAL_PLANNER_ODOM_H_
43 #include <boost/thread.hpp>
57 class LocalPlannerUtil {
82 void reconfigureCB(LocalPlannerLimits &config,
bool restore_defaults);
91 std::string global_frame);
93 bool getGoal(geometry_msgs::PoseStamped& goal_pose);
95 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
97 bool getLocalPlan(
const geometry_msgs::PoseStamped& global_pose, std::vector<geometry_msgs::PoseStamped>& transformed_plan);
boost::mutex limits_configuration_mutex_
bool getLocalPlan(const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
LocalPlannerLimits limits_
void reconfigureCB(LocalPlannerLimits &config, bool restore_defaults)
Callback to update the local planner's parameters.
std::string getGlobalFrame()
costmap_2d::Costmap2D * getCostmap()
costmap_2d::Costmap2D * costmap_
void initialize(tf2_ros::Buffer *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
LocalPlannerLimits default_limits_
std::string global_frame_
std::vector< geometry_msgs::PoseStamped > global_plan_
LocalPlannerLimits getCurrentLimits()
bool getGoal(geometry_msgs::PoseStamped &goal_pose)
base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24