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

Combine pre-planning, planning and post-planning to customize the your path. More...

#include <gpp_plugin.hpp>

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

Public Types

using Map = costmap_2d::Costmap2DROS
 
using Path = std::vector< Pose >
 
using Pose = geometry_msgs::PoseStamped
 
- Public Types inherited from mbf_costmap_core::CostmapPlanner
typedef boost::shared_ptr< ::mbf_costmap_core::CostmapPlannerPtr
 
- Public Types inherited from mbf_abstract_core::AbstractPlanner
typedef boost::shared_ptr< ::mbf_abstract_core::AbstractPlannerPtr
 

Public Member Functions

bool cancel () override
 
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
 
uint32_t makePlan (const Pose &start, const Pose &goal, double tolerance, Path &plan, double &cost, std::string &message) 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 ()
 
- Public Member Functions inherited from mbf_costmap_core::CostmapPlanner
virtual uint32_t makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message)=0
 
virtual ~CostmapPlanner ()
 
- Public Member Functions inherited from mbf_abstract_core::AbstractPlanner
virtual ~AbstractPlanner ()
 

Private Member Functions

bool globalPlanning (const Pose &_start, const Pose &_goal, Path &_plan, double &_cost)
 
bool postPlanning (const Pose &_start, const Pose &_goal, Path &_path, double &_cost)
 
bool prePlanning (Pose &_start, Pose &_goal)
 

Private Attributes

std::atomic_bool cancel_
 
Mapcostmap_ = nullptr
 
CostmapPlannerManager global_planning_
 
std::string name_
 
PostPlanningManager post_planning_
 
PrePlanningManager pre_planning_
 

Additional Inherited Members

- Protected Member Functions inherited from nav_core::BaseGlobalPlanner
 BaseGlobalPlanner ()
 
- Protected Member Functions inherited from mbf_costmap_core::CostmapPlanner
 CostmapPlanner ()
 
- Protected Member Functions inherited from mbf_abstract_core::AbstractPlanner
 AbstractPlanner ()
 

Detailed Description

Combine pre-planning, planning and post-planning to customize the your path.

The planner implements BaseGlobalPlanner and CostmapPlanner interfaces.

Parameters

Define the pre_planning plugins under the tag pre_planning: those plugins must implement gpp_interface::PrePlanningInterface.

Define planning plugins under the tag planning: those plugins must implement either nav_core::BaseLocalPlanner or 'mbf_costmap_core::CostmapPlanner`.

Define post_planning plugins under tha tag post_planning: those plugins must implement gpp_interface::PostPlanningInterface.

The plugins under every tag (pre_planning, planning or post_planning) must be defined as an array. Every element withing the array must have the tags name and type - following the standard ros syntax for pluginlib-loaded plugins.

Below is a code example

# define the pre-planning plugins
pre_planning:
- {name: first_pre_planning_name, type: first_pre_planning_type}
- {name: second_pre_planning_name, type: second_pre_planning_type}
# define the planning plugins
planning:
- {name: first_planning_name, type: first_planning_type}
- {name: second_planning_name, type: second_planning_type}
# define the post-planning plugins
post_planning:
- {name: first_post_planning_name, type: first_post_planning_type}
- {name: second_post_planning_name, type: second_post_planning_type}
# define the default values for the groups
pre_planning_default_value: true
planning_default_value: false
post_planning_default_value: true

Definition at line 410 of file gpp_plugin.hpp.

Member Typedef Documentation

◆ Map

Definition at line 414 of file gpp_plugin.hpp.

◆ Path

using gpp_plugin::GppPlugin::Path = std::vector<Pose>

Definition at line 413 of file gpp_plugin.hpp.

◆ Pose

using gpp_plugin::GppPlugin::Pose = geometry_msgs::PoseStamped

Definition at line 412 of file gpp_plugin.hpp.

Member Function Documentation

◆ cancel()

bool gpp_plugin::GppPlugin::cancel ( )
overridevirtual

Implements mbf_costmap_core::CostmapPlanner.

Definition at line 292 of file gpp_plugin.cpp.

◆ globalPlanning()

bool gpp_plugin::GppPlugin::globalPlanning ( const Pose _start,
const Pose _goal,
Path _plan,
double &  _cost 
)
private

Definition at line 244 of file gpp_plugin.cpp.

◆ initialize()

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

Implements mbf_costmap_core::CostmapPlanner.

Definition at line 213 of file gpp_plugin.cpp.

◆ makePlan() [1/3]

bool gpp_plugin::GppPlugin::makePlan ( const Pose _start,
const Pose _goal,
Path _plan 
)
override

Definition at line 253 of file gpp_plugin.cpp.

◆ makePlan() [2/3]

bool gpp_plugin::GppPlugin::makePlan ( const Pose _start,
const Pose _goal,
Path _plan,
double &  _cost 
)
override

Definition at line 259 of file gpp_plugin.cpp.

◆ makePlan() [3/3]

uint32_t gpp_plugin::GppPlugin::makePlan ( const Pose start,
const Pose goal,
double  tolerance,
Path plan,
double &  cost,
std::string &  message 
)
override

Definition at line 266 of file gpp_plugin.cpp.

◆ postPlanning()

bool gpp_plugin::GppPlugin::postPlanning ( const Pose _start,
const Pose _goal,
Path _path,
double &  _cost 
)
private

Definition at line 235 of file gpp_plugin.cpp.

◆ prePlanning()

bool gpp_plugin::GppPlugin::prePlanning ( Pose _start,
Pose _goal 
)
private

Definition at line 227 of file gpp_plugin.cpp.

Member Data Documentation

◆ cancel_

std::atomic_bool gpp_plugin::GppPlugin::cancel_
private

Definition at line 444 of file gpp_plugin.hpp.

◆ costmap_

Map* gpp_plugin::GppPlugin::costmap_ = nullptr
private

Definition at line 448 of file gpp_plugin.hpp.

◆ global_planning_

CostmapPlannerManager gpp_plugin::GppPlugin::global_planning_
private

Definition at line 452 of file gpp_plugin.hpp.

◆ name_

std::string gpp_plugin::GppPlugin::name_
private

Definition at line 447 of file gpp_plugin.hpp.

◆ post_planning_

PostPlanningManager gpp_plugin::GppPlugin::post_planning_
private

Definition at line 451 of file gpp_plugin.hpp.

◆ pre_planning_

PrePlanningManager gpp_plugin::GppPlugin::pre_planning_
private

Definition at line 450 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