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

A Pre-Planning class will be run before the planner. More...

#include <pre_planning_interface.hpp>

Public Types

using Map = costmap_2d::Costmap2DROS
 
using Pose = geometry_msgs::PoseStamped
 

Public Member Functions

virtual void initialize (const std::string &_name, Map *_map)=0
 
virtual bool preProcess (Pose &_start, Pose &_goal)=0
 
virtual ~PrePlanningInterface ()=default
 

Detailed Description

A Pre-Planning class will be run before the planner.

Use this class to alter the input for your planner. You can implement

The class offers two methods. Following the standard-approach of ros-navigation plugins, call first initialize to initialize the instance. Then you can use the instance by calling preProcess

// dummy implementation
struct MyPrePlanning : public PrePlanningInterface{
bool
preProcess(Pose& _start, Pose& _goal) override
{}
void
initialize(const std::string& _name, Map* _map) override {}
};
// now create an instance
MyPrePlanning pre_planning;
// init your instance
pre_planning.initialize("my_pre_planning");
// use it
if(pre_planning.preProcess(...)) {
std::cout << "pre_planning worked" << std::endl;
}
else {
std::cerr << "pre_planning failed" << std::endl;
}

Definition at line 78 of file pre_planning_interface.hpp.

Member Typedef Documentation

◆ Map

Definition at line 81 of file pre_planning_interface.hpp.

◆ Pose

using gpp_interface::PrePlanningInterface::Pose = geometry_msgs::PoseStamped

Definition at line 80 of file pre_planning_interface.hpp.

Constructor & Destructor Documentation

◆ ~PrePlanningInterface()

virtual gpp_interface::PrePlanningInterface::~PrePlanningInterface ( )
virtualdefault

Member Function Documentation

◆ initialize()

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

◆ preProcess()

virtual bool gpp_interface::PrePlanningInterface::preProcess ( Pose _start,
Pose _goal 
)
pure virtual
Parameters
_startStart pose for the planning problem
_goalGoal pose for the planning problem
Returns
true, if successful

The documentation for this struct was generated from the following file:
gpp_interface::PrePlanningInterface::initialize
virtual void initialize(const std::string &_name, Map *_map)=0
tf::Transform
gpp_interface::PrePlanningInterface::preProcess
virtual bool preProcess(Pose &_start, Pose &_goal)=0
gpp_interface::PrePlanningInterface::Map
costmap_2d::Costmap2DROS Map
Definition: pre_planning_interface.hpp:81


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