|
| 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 |
| |
| 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 () |
| |
| 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 () |
| |
| virtual | ~AbstractPlanner () |
| |
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.