|
base_local_planner
|
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 () |
| std::string | getGlobalFrame () |
| bool | getGoal (geometry_msgs::PoseStamped &goal_pose) |
| bool | getLocalPlan (const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan) |
| void | initialize (tf2_ros::Buffer *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. More... | |
| 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_ |
| tf2_ros::Buffer * | tf_ |
Helper class implementing infrastructure code many local planner implementations may need.
Definition at line 92 of file local_planner_util.h.
|
inline |
Definition at line 119 of file local_planner_util.h.
|
inline |
Definition at line 121 of file local_planner_util.h.
| costmap_2d::Costmap2D * base_local_planner::LocalPlannerUtil::getCostmap | ( | ) |
Definition at line 108 of file local_planner_util.cpp.
| LocalPlannerLimits base_local_planner::LocalPlannerUtil::getCurrentLimits | ( | ) |
Definition at line 112 of file local_planner_util.cpp.
|
inline |
Definition at line 138 of file local_planner_util.h.
| bool base_local_planner::LocalPlannerUtil::getGoal | ( | geometry_msgs::PoseStamped & | goal_pose | ) |
Definition at line 118 of file local_planner_util.cpp.
| bool base_local_planner::LocalPlannerUtil::getLocalPlan | ( | const geometry_msgs::PoseStamped & | global_pose, |
| std::vector< geometry_msgs::PoseStamped > & | transformed_plan | ||
| ) |
Definition at line 140 of file local_planner_util.cpp.
| void base_local_planner::LocalPlannerUtil::initialize | ( | tf2_ros::Buffer * | tf, |
| costmap_2d::Costmap2D * | costmap, | ||
| std::string | global_frame | ||
| ) |
Definition at line 79 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 94 of file local_planner_util.cpp.
| bool base_local_planner::LocalPlannerUtil::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | orig_global_plan | ) |
Definition at line 126 of file local_planner_util.cpp.
|
private |
Definition at line 99 of file local_planner_util.h.
|
private |
Definition at line 108 of file local_planner_util.h.
|
private |
Definition at line 97 of file local_planner_util.h.
|
private |
Definition at line 103 of file local_planner_util.h.
|
private |
Definition at line 110 of file local_planner_util.h.
|
private |
Definition at line 109 of file local_planner_util.h.
|
private |
Definition at line 106 of file local_planner_util.h.
|
private |
Definition at line 96 of file local_planner_util.h.
|
private |
Definition at line 107 of file local_planner_util.h.
|
private |
Definition at line 100 of file local_planner_util.h.
1.8.17