Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
mbf_mesh_nav::MeshPlannerExecution Class Reference

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>

Inheritance diagram for mbf_mesh_nav::MeshPlannerExecution:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< mesh_map::MeshMapMeshPtr
 
- Public Types inherited from mbf_abstract_nav::AbstractPlannerExecution
enum  PlanningState
 
typedef boost::shared_ptr< AbstractPlannerExecutionPtr
 

Public Member Functions

 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...
 
- Public Member Functions inherited from mbf_abstract_nav::AbstractPlannerExecution
 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 ()
 
- Public Member Functions inherited from mbf_abstract_nav::AbstractExecutionBase
 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 ()
 

Private Member Functions

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)
 

Private Attributes

bool lock_mesh_
 Whether to lock mesh before calling the planner (see issue #4 for details) More...
 
const MeshPtrmesh_ptr_
 Shared pointer to the mesh for 3d navigation planning. More...
 
std::string planner_name_
 Name of the planner assigned by the class loader. More...
 

Additional Inherited Members

- Public Attributes inherited from mbf_abstract_nav::AbstractPlannerExecution
 CANCELED
 
 FOUND_PLAN
 
 INITIALIZED
 
 INTERNAL_ERROR
 
 MAX_RETRIES
 
 NO_PLAN_FOUND
 
 PAT_EXCEEDED
 
 PLANNING
 
 STARTED
 
 STOPPED
 
- Protected Member Functions inherited from mbf_abstract_nav::AbstractPlannerExecution
virtual void run ()
 
- Protected Attributes inherited from mbf_abstract_nav::AbstractPlannerExecution
mbf_abstract_core::AbstractPlanner::Ptr planner_
 
std::string plugin_name_
 
const TFPtr tf_listener_ptr_
 
- Protected Attributes inherited from mbf_abstract_nav::AbstractExecutionBase
bool cancel_
 
boost::condition_variable condition_
 
std::string message_
 
std::string name_
 
uint32_t outcome_
 
boost::thread thread_
 

Detailed Description

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.

Member Typedef Documentation

◆ MeshPtr

Definition at line 59 of file mesh_planner_execution.h.

Constructor & Destructor Documentation

◆ 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
conditionThread sleep condition variable, to wake up connected threads
meshShared pointer to the mesh.

Definition at line 41 of file mesh_planner_execution.cpp.

◆ ~MeshPlannerExecution()

mbf_mesh_nav::MeshPlannerExecution::~MeshPlannerExecution ( )
virtual

Destructor.

Definition at line 49 of file mesh_planner_execution.cpp.

Member Function Documentation

◆ 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
startThe start pose for planning
goalThe goal pose for planning
toleranceThe goal tolerance
planThe computed plan by the plugin
costThe computed costs for the corresponding plan
messageAn 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

Definition at line 53 of file mesh_planner_execution.cpp.

Member Data Documentation

◆ lock_mesh_

bool mbf_mesh_nav::MeshPlannerExecution::lock_mesh_
private

Whether to lock mesh before calling the planner (see issue #4 for details)

Definition at line 104 of file mesh_planner_execution.h.

◆ mesh_ptr_

const MeshPtr& mbf_mesh_nav::MeshPlannerExecution::mesh_ptr_
private

Shared pointer to the mesh for 3d navigation planning.

Definition at line 101 of file mesh_planner_execution.h.

◆ planner_name_

std::string mbf_mesh_nav::MeshPlannerExecution::planner_name_
private

Name of the planner assigned by the class loader.

Definition at line 107 of file mesh_planner_execution.h.


The documentation for this class was generated from the following files:


mbf_mesh_nav
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:57