The MeshPlannerExecution binds a global mesh to the AbstractPlannerExecution and uses the nav_core/BaseMeshPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base.
More...
#include <mesh_planner_execution.h>
|
| | MeshPlannerExecution (const std::string name, const mbf_mesh_core::MeshPlanner::Ptr &planner_ptr, const MeshPtr &mesh, const MoveBaseFlexConfig &config) |
| | Constructor. More...
|
| |
| virtual | ~MeshPlannerExecution () |
| | Destructor. More...
|
| |
| | AbstractPlannerExecution (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const MoveBaseFlexConfig &config) |
| |
| | AbstractPlannerExecution (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const TFPtr &tf_listener_ptr, const MoveBaseFlexConfig &config) |
| |
| virtual bool | cancel () |
| |
| double | getCost () const |
| |
| double | getFrequency () const |
| |
| ros::Time | getLastValidPlanTime () const |
| |
| std::vector< geometry_msgs::PoseStamped > | getPlan () const |
| |
| PlanningState | getState () const |
| |
| bool | isPatienceExceeded () const |
| |
| void | reconfigure (const MoveBaseFlexConfig &config) |
| |
| void | setNewGoal (const geometry_msgs::PoseStamped &goal, double tolerance) |
| |
| void | setNewStart (const geometry_msgs::PoseStamped &start) |
| |
| void | setNewStartAndGoal (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance) |
| |
| bool | start (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance) |
| |
| virtual | ~AbstractPlannerExecution () |
| |
| | AbstractExecutionBase (const std::string &name) |
| |
| const std::string & | getMessage () const |
| |
| const std::string & | getName () const |
| |
| uint32_t | getOutcome () const |
| |
| void | join () |
| |
| virtual void | postRun () |
| |
| virtual void | preRun () |
| |
| virtual void | reconfigure (MoveBaseFlexConfig &_cfg) |
| |
| virtual bool | start () |
| |
| virtual void | stop () |
| |
| boost::cv_status | waitForStateUpdate (boost::chrono::microseconds const &duration) |
| |
| virtual | ~AbstractExecutionBase () |
| |
|
| 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) |
| | Calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance, if a goal tolerance is enabled in the planner plugin. More...
|
| |
| mbf_abstract_nav::MoveBaseFlexConfig | toAbstract (const MoveBaseFlexConfig &config) |
| |
The MeshPlannerExecution binds a global mesh to the AbstractPlannerExecution and uses the nav_core/BaseMeshPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base.
Definition at line 56 of file mesh_planner_execution.h.
◆ MeshPtr
◆ MeshPlannerExecution()
| mbf_mesh_nav::MeshPlannerExecution::MeshPlannerExecution |
( |
const std::string |
name, |
|
|
const mbf_mesh_core::MeshPlanner::Ptr & |
planner_ptr, |
|
|
const MeshPtr & |
mesh, |
|
|
const MoveBaseFlexConfig & |
config |
|
) |
| |
Constructor.
- Parameters
-
| condition | Thread sleep condition variable, to wake up connected threads |
| mesh | Shared pointer to the mesh. |
Definition at line 41 of file mesh_planner_execution.cpp.
◆ ~MeshPlannerExecution()
| mbf_mesh_nav::MeshPlannerExecution::~MeshPlannerExecution |
( |
| ) |
|
|
virtual |
◆ makePlan()
| uint32_t mbf_mesh_nav::MeshPlannerExecution::makePlan |
( |
const geometry_msgs::PoseStamped & |
start, |
|
|
const geometry_msgs::PoseStamped & |
goal, |
|
|
double |
tolerance, |
|
|
std::vector< geometry_msgs::PoseStamped > & |
plan, |
|
|
double & |
cost, |
|
|
std::string & |
message |
|
) |
| |
|
privatevirtual |
Calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance, if a goal tolerance is enabled in the planner plugin.
- Parameters
-
| start | The start pose for planning |
| goal | The goal pose for planning |
| tolerance | The goal tolerance |
| plan | The computed plan by the plugin |
| cost | The computed costs for the corresponding plan |
| message | An optional message which should correspond with the returned outcome |
- Returns
- An outcome number, see also the action definition in the GetPath.action file
Reimplemented from mbf_abstract_nav::AbstractPlannerExecution.
Definition at line 64 of file mesh_planner_execution.cpp.
◆ toAbstract()
| mbf_abstract_nav::MoveBaseFlexConfig mbf_mesh_nav::MeshPlannerExecution::toAbstract |
( |
const MoveBaseFlexConfig & |
config | ) |
|
|
private |
◆ lock_mesh_
| bool mbf_mesh_nav::MeshPlannerExecution::lock_mesh_ |
|
private |
◆ mesh_ptr_
| const MeshPtr& mbf_mesh_nav::MeshPlannerExecution::mesh_ptr_ |
|
private |
◆ planner_name_
| std::string mbf_mesh_nav::MeshPlannerExecution::planner_name_ |
|
private |
The documentation for this class was generated from the following files: