Wrappes the CostmapPlaner API into the traditional BaseGlobalPlanner API. More...
#include <gpp_plugin.hpp>

Public Types | |
| using | ImplPlanner = pluginlib::UniquePtr< CostmapPlanner > |
| using | Map = costmap_2d::Costmap2DROS |
| using | Path = std::vector< Pose > |
| using | Pose = geometry_msgs::PoseStamped |
Public Member Functions | |
| BaseGlobalPlannerWrapper (ImplPlanner &&_impl) | |
| our c'tor More... | |
| void | initialize (std::string name, Map *costmap_ros) override |
| bool | makePlan (const Pose &start, const Pose &goal, Path &plan) override |
| bool | makePlan (const Pose &start, const Pose &goal, Path &plan, double &cost) override |
Public Member Functions inherited from nav_core::BaseGlobalPlanner | |
| virtual bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)=0 |
| virtual bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost) |
| virtual | ~BaseGlobalPlanner () |
Private Attributes | |
| ImplPlanner | impl_ |
Additional Inherited Members | |
Protected Member Functions inherited from nav_core::BaseGlobalPlanner | |
| BaseGlobalPlanner () | |
Wrappes the CostmapPlaner API into the traditional BaseGlobalPlanner API.
Implementation is very simpliar to move-base-flex wrapper class. However, all publicly available planners stick to the BaseGlobalPlanner API, so we treat it as default.
Definition at line 316 of file gpp_plugin.hpp.
| using gpp_plugin::BaseGlobalPlannerWrapper::ImplPlanner = pluginlib::UniquePtr<CostmapPlanner> |
Definition at line 321 of file gpp_plugin.hpp.
Definition at line 320 of file gpp_plugin.hpp.
| using gpp_plugin::BaseGlobalPlannerWrapper::Path = std::vector<Pose> |
Definition at line 319 of file gpp_plugin.hpp.
| using gpp_plugin::BaseGlobalPlannerWrapper::Pose = geometry_msgs::PoseStamped |
Definition at line 318 of file gpp_plugin.hpp.
|
explicit |
our c'tor
| _impl | a valid instance of the CostmapPlanner, which we will own |
| std::invalid_argument,if | _impl is nullptr |
Definition at line 151 of file gpp_plugin.cpp.
|
overridevirtual |
Implements nav_core::BaseGlobalPlanner.
Definition at line 173 of file gpp_plugin.cpp.
|
override |
Definition at line 159 of file gpp_plugin.cpp.
|
override |
Definition at line 166 of file gpp_plugin.cpp.
|
private |
Definition at line 339 of file gpp_plugin.hpp.