47 std::string global_frame) {
55 ROS_WARN(
"Planner utils have already been initialized, doing nothing.");
61 if(
setup_ && restore_defaults) {
93 ROS_ERROR(
"Planner utils have not been initialized, please call initialize() first");
114 ROS_WARN(
"Could not transform the global plan to the frame of the controller");
tf::TransformListener * tf_
bool getGoal(tf::Stamped< tf::Pose > &goal_pose)
bool getGoalPose(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, tf::Stamped< tf::Pose > &goal_pose)
Returns last pose in plan.
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_
void prunePlan(const tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
Trim off parts of the global plan that are far enough behind the robot.
LocalPlannerLimits default_limits_
void initialize(tf::TransformListener *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &global_robot_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
Transforms the global plan of the robot from the planner frame to the frame of the costmap...
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_
costmap_2d::Costmap2D * costmap_