Helper class implementing infrastructure code many local planner implementations may need. More...
#include <local_planner_util.h>
Public Member Functions | |
costmap_2d::Costmap2D * | getCostmap () |
LocalPlannerLimits | getCurrentLimits () |
bool | getGoal (tf::Stamped< tf::Pose > &goal_pose) |
bool | getLocalPlan (tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan) |
void | initialize (tf::TransformListener *tf, costmap_2d::Costmap2D *costmap, std::string global_frame) |
LocalPlannerUtil () | |
void | reconfigureCB (LocalPlannerLimits &config, bool restore_defaults) |
Callback to update the local planner's parameters. | |
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
~LocalPlannerUtil () | |
Private Attributes | |
costmap_2d::Costmap2D * | costmap_ |
LocalPlannerLimits | default_limits_ |
std::string | global_frame_ |
std::vector < geometry_msgs::PoseStamped > | global_plan_ |
bool | initialized_ |
LocalPlannerLimits | limits_ |
boost::mutex | limits_configuration_mutex_ |
std::string | name_ |
bool | setup_ |
tf::TransformListener * | tf_ |
Helper class implementing infrastructure code many local planner implementations may need.
Definition at line 58 of file local_planner_util.h.
Definition at line 85 of file local_planner_util.h.
Definition at line 87 of file local_planner_util.h.
Definition at line 73 of file local_planner_util.cpp.
Definition at line 77 of file local_planner_util.cpp.
bool base_local_planner::LocalPlannerUtil::getGoal | ( | tf::Stamped< tf::Pose > & | goal_pose | ) |
Definition at line 83 of file local_planner_util.cpp.
bool base_local_planner::LocalPlannerUtil::getLocalPlan | ( | tf::Stamped< tf::Pose > & | global_pose, |
std::vector< geometry_msgs::PoseStamped > & | transformed_plan | ||
) |
Definition at line 105 of file local_planner_util.cpp.
void base_local_planner::LocalPlannerUtil::initialize | ( | tf::TransformListener * | tf, |
costmap_2d::Costmap2D * | costmap, | ||
std::string | global_frame | ||
) |
Definition at line 44 of file local_planner_util.cpp.
void base_local_planner::LocalPlannerUtil::reconfigureCB | ( | LocalPlannerLimits & | config, |
bool | restore_defaults | ||
) |
Callback to update the local planner's parameters.
Definition at line 59 of file local_planner_util.cpp.
bool base_local_planner::LocalPlannerUtil::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | orig_global_plan | ) |
Definition at line 91 of file local_planner_util.cpp.
Definition at line 65 of file local_planner_util.h.
Definition at line 74 of file local_planner_util.h.
std::string base_local_planner::LocalPlannerUtil::global_frame_ [private] |
Definition at line 63 of file local_planner_util.h.
std::vector<geometry_msgs::PoseStamped> base_local_planner::LocalPlannerUtil::global_plan_ [private] |
Definition at line 69 of file local_planner_util.h.
bool base_local_planner::LocalPlannerUtil::initialized_ [private] |
Definition at line 76 of file local_planner_util.h.
Definition at line 75 of file local_planner_util.h.
boost::mutex base_local_planner::LocalPlannerUtil::limits_configuration_mutex_ [private] |
Definition at line 72 of file local_planner_util.h.
std::string base_local_planner::LocalPlannerUtil::name_ [private] |
Definition at line 62 of file local_planner_util.h.
bool base_local_planner::LocalPlannerUtil::setup_ [private] |
Definition at line 73 of file local_planner_util.h.
Definition at line 66 of file local_planner_util.h.