#include <gpp_interface/post_planning_interface.hpp>
#include <gpp_interface/pre_planning_interface.hpp>
#include <costmap_2d/costmap_2d_ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <mbf_costmap_core/costmap_planner.h>
#include <nav_core/base_global_planner.h>
#include <pluginlib/class_loader.h>
#include <ros/ros.h>
#include <memory>
#include <string>
#include <utility>
#include <vector>
Go to the source code of this file.
Classes | |
struct | gpp_plugin::ArrayPluginManager< _Plugin > |
Loads an array of plugins. More... | |
struct | gpp_plugin::BaseGlobalPlannerWrapper |
Wrappes the CostmapPlaner API into the traditional BaseGlobalPlanner API. More... | |
struct | gpp_plugin::CostmapPlannerManager |
Loads either CostmapPlanner or BaseGlobalPlanner plugins under a uniform interface. More... | |
struct | gpp_plugin::GppPlugin |
Combine pre-planning, planning and post-planning to customize the your path. More... | |
struct | gpp_plugin::PluginDefinition< _Plugin > |
POD defining the meta information required to load a plugin. More... | |
struct | gpp_plugin::PluginGroup< _Plugin > |
Common interface to a plugin group. More... | |
struct | gpp_plugin::PluginManager< _Plugin > |
Base class for loading a plugin with a valid PluginDefinition. More... | |
struct | gpp_plugin::PluginParameter |
Parameters defining how to execute a plugin. More... | |
Namespaces | |
gpp_plugin | |
Typedefs | |
using | gpp_plugin::GlobalPlannerManager = ArrayPluginManager< BaseGlobalPlanner > |
using | gpp_plugin::PostPlanningManager = ArrayPluginManager< PostPlanningInterface > |
using | gpp_plugin::PrePlanningManager = ArrayPluginManager< PrePlanningInterface > |
Functions | |
template<typename _Plugin , typename _Functor > | |
bool | gpp_plugin::_runPlugins (const PluginGroup< _Plugin > &_grp, const _Functor &_func, const std::atomic_bool &_cancel) |
Execution logic to run all plugins within one group. More... | |
template<typename _Plugin , typename _Functor > | |
bool | gpp_plugin::runPlugins (const PluginGroup< _Plugin > &_grp, const _Functor &_func, const std::atomic_bool &_cancel) |
as _runPlugins but with a warning on failure More... | |