Public Member Functions | Private Member Functions | Private Attributes | List of all members
mbf_costmap_nav::CostmapPlannerExecution Class Reference

The CostmapPlannerExecution binds a global costmap to the AbstractPlannerExecution and uses the nav_core/BaseCostmapPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base. More...

#include <costmap_planner_execution.h>

Inheritance diagram for mbf_costmap_nav::CostmapPlannerExecution:
Inheritance graph
[legend]

Public Member Functions

 CostmapPlannerExecution (const std::string &planner_name, const mbf_costmap_core::CostmapPlanner::Ptr &planner_ptr, const TFPtr &tf_listener_ptr, const CostmapWrapper::Ptr &costmap_ptr, const MoveBaseFlexConfig &config)
 Constructor. More...
 
virtual ~CostmapPlannerExecution ()
 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 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...
 
void postRun ()
 Implementation-specific cleanup function, called right after execution. This method overrides abstract execution empty implementation with underlying map-specific cleanup code. More...
 
void preRun ()
 Implementation-specific setup function, called right before execution. This method overrides abstract execution empty implementation with underlying map-specific setup code. More...
 
mbf_abstract_nav::MoveBaseFlexConfig toAbstract (const MoveBaseFlexConfig &config)
 

Private Attributes

const CostmapWrapper::Ptrcostmap_ptr_
 Shared pointer to the global planner costmap. More...
 
bool lock_costmap_
 Whether to lock costmap before calling the planner (see issue #4 for details) More...
 
std::string planner_name_
 Name of the planner assigned by the class loader. More...
 

Additional Inherited Members

- Public Types inherited from mbf_abstract_nav::AbstractPlannerExecution
enum  PlanningState
 
typedef boost::shared_ptr< AbstractPlannerExecutionPtr
 
- 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 CostmapPlannerExecution binds a global costmap to the AbstractPlannerExecution and uses the nav_core/BaseCostmapPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base.

Definition at line 60 of file costmap_planner_execution.h.

Constructor & Destructor Documentation

◆ CostmapPlannerExecution()

mbf_costmap_nav::CostmapPlannerExecution::CostmapPlannerExecution ( const std::string &  planner_name,
const mbf_costmap_core::CostmapPlanner::Ptr planner_ptr,
const TFPtr tf_listener_ptr,
const CostmapWrapper::Ptr costmap_ptr,
const MoveBaseFlexConfig &  config 
)

Constructor.

Parameters
planner_nameName of the planner to use.
planner_ptrShared pointer to the plugin to use.
tf_listener_ptrShared pointer to the tf-listener.
costmap_ptrShared pointer to the global costmap.
configCurrent server configuration (dynamic).

Definition at line 47 of file costmap_planner_execution.cpp.

◆ ~CostmapPlannerExecution()

mbf_costmap_nav::CostmapPlannerExecution::~CostmapPlannerExecution ( )
virtual

Destructor.

Definition at line 57 of file costmap_planner_execution.cpp.

Member Function Documentation

◆ makePlan()

uint32_t mbf_costmap_nav::CostmapPlannerExecution::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 71 of file costmap_planner_execution.cpp.

◆ postRun()

void mbf_costmap_nav::CostmapPlannerExecution::postRun ( )
inlineprivatevirtual

Implementation-specific cleanup function, called right after execution. This method overrides abstract execution empty implementation with underlying map-specific cleanup code.

Reimplemented from mbf_abstract_nav::AbstractExecutionBase.

Definition at line 95 of file costmap_planner_execution.h.

◆ preRun()

void mbf_costmap_nav::CostmapPlannerExecution::preRun ( )
inlineprivatevirtual

Implementation-specific setup function, called right before execution. This method overrides abstract execution empty implementation with underlying map-specific setup code.

Reimplemented from mbf_abstract_nav::AbstractExecutionBase.

Definition at line 86 of file costmap_planner_execution.h.

◆ toAbstract()

mbf_abstract_nav::MoveBaseFlexConfig mbf_costmap_nav::CostmapPlannerExecution::toAbstract ( const MoveBaseFlexConfig &  config)
private

Definition at line 61 of file costmap_planner_execution.cpp.

Member Data Documentation

◆ costmap_ptr_

const CostmapWrapper::Ptr& mbf_costmap_nav::CostmapPlannerExecution::costmap_ptr_
private

Shared pointer to the global planner costmap.

Definition at line 122 of file costmap_planner_execution.h.

◆ lock_costmap_

bool mbf_costmap_nav::CostmapPlannerExecution::lock_costmap_
private

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

Definition at line 125 of file costmap_planner_execution.h.

◆ planner_name_

std::string mbf_costmap_nav::CostmapPlannerExecution::planner_name_
private

Name of the planner assigned by the class loader.

Definition at line 128 of file costmap_planner_execution.h.


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


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Mon Feb 28 2022 22:49:55