Public Types | Public Member Functions | List of all members
gpp_interface::PostPlanningInterface Struct Referenceabstract

#include <post_planning_interface.hpp>

Public Types

using Map = costmap_2d::Costmap2DROS
 
using Path = std::vector< Pose >
 
using Pose = geometry_msgs::PoseStamped
 

Public Member Functions

virtual void initialize (const std::string &_name, Map *_map)=0
 
virtual bool postProcess (const Pose &_start, const Pose &_goal, Path &_path, double &_cost)=0
 
virtual ~PostPlanningInterface ()=default
 

Detailed Description

Post-Planning class will be run after the global planner

Use this class to alter the output of your planner. You can implement

Definition at line 44 of file post_planning_interface.hpp.

Member Typedef Documentation

◆ Map

Definition at line 48 of file post_planning_interface.hpp.

◆ Path

Definition at line 47 of file post_planning_interface.hpp.

◆ Pose

using gpp_interface::PostPlanningInterface::Pose = geometry_msgs::PoseStamped

Definition at line 46 of file post_planning_interface.hpp.

Constructor & Destructor Documentation

◆ ~PostPlanningInterface()

virtual gpp_interface::PostPlanningInterface::~PostPlanningInterface ( )
virtualdefault

Member Function Documentation

◆ initialize()

virtual void gpp_interface::PostPlanningInterface::initialize ( const std::string &  _name,
Map _map 
)
pure virtual
Parameters
_nameName of the resource
_mapMap on which the planning problem will be preformed

◆ postProcess()

virtual bool gpp_interface::PostPlanningInterface::postProcess ( const Pose _start,
const Pose _goal,
Path _path,
double &  _cost 
)
pure virtual
Parameters
[in]_startstart pose for the planning
[in]_goalgoal pose for the planning
[out]_pathpath as output from a global planner
[out]_costcost as output from a global planner
Returns
true, if successful

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


gpp_interface
Author(s):
autogenerated on Wed Mar 2 2022 00:21:20