Public Types | Public Member Functions | Private Attributes | List of all members
gpp_plugin::BaseGlobalPlannerWrapper Struct Reference

Wrappes the CostmapPlaner API into the traditional BaseGlobalPlanner API. More...

#include <gpp_plugin.hpp>

Inheritance diagram for gpp_plugin::BaseGlobalPlannerWrapper:
Inheritance graph
[legend]

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 ()
 

Detailed Description

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.

Member Typedef Documentation

◆ ImplPlanner

Definition at line 321 of file gpp_plugin.hpp.

◆ Map

Definition at line 320 of file gpp_plugin.hpp.

◆ Path

Definition at line 319 of file gpp_plugin.hpp.

◆ Pose

using gpp_plugin::BaseGlobalPlannerWrapper::Pose = geometry_msgs::PoseStamped

Definition at line 318 of file gpp_plugin.hpp.

Constructor & Destructor Documentation

◆ BaseGlobalPlannerWrapper()

gpp_plugin::BaseGlobalPlannerWrapper::BaseGlobalPlannerWrapper ( ImplPlanner &&  _impl)
explicit

our c'tor

Parameters
_impla valid instance of the CostmapPlanner, which we will own
Exceptions
std::invalid_argument,if_impl is nullptr

Definition at line 151 of file gpp_plugin.cpp.

Member Function Documentation

◆ initialize()

void gpp_plugin::BaseGlobalPlannerWrapper::initialize ( std::string  name,
Map costmap_ros 
)
overridevirtual

Implements nav_core::BaseGlobalPlanner.

Definition at line 173 of file gpp_plugin.cpp.

◆ makePlan() [1/2]

bool gpp_plugin::BaseGlobalPlannerWrapper::makePlan ( const Pose start,
const Pose goal,
Path plan 
)
override

Definition at line 159 of file gpp_plugin.cpp.

◆ makePlan() [2/2]

bool gpp_plugin::BaseGlobalPlannerWrapper::makePlan ( const Pose start,
const Pose goal,
Path plan,
double &  cost 
)
override

Definition at line 166 of file gpp_plugin.cpp.

Member Data Documentation

◆ impl_

ImplPlanner gpp_plugin::BaseGlobalPlannerWrapper::impl_
private

Definition at line 339 of file gpp_plugin.hpp.


The documentation for this struct was generated from the following files:


gpp_plugin
Author(s):
autogenerated on Wed Mar 2 2022 00:21:23