Public Types | 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 Types

typedef boost::shared_ptr< costmap_2d::Costmap2DROSCostmapPtr
 
- Public Types inherited from mbf_abstract_nav::AbstractPlannerExecution
enum  PlanningState
 
typedef boost::shared_ptr< AbstractPlannerExecutionPtr
 

Public Member Functions

 CostmapPlannerExecution (const std::string name, const mbf_costmap_core::CostmapPlanner::Ptr &planner_ptr, CostmapPtr &costmap, const MoveBaseFlexConfig &config, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
 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, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
 
virtual bool cancel ()
 
double getCost ()
 
double getFrequency ()
 
ros::Time getLastValidPlanTime ()
 
std::vector< geometry_msgs::PoseStamped > getPlan ()
 
PlanningState getState ()
 
bool isPatienceExceeded ()
 
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 (std::string name, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
 
std::string getMessage ()
 
std::string getName ()
 
uint32_t getOutcome ()
 
void join ()
 
virtual bool start ()
 
virtual void stop ()
 
void waitForStateUpdate (boost::chrono::microseconds const &duration)
 

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

CostmapPtrcostmap_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 Attributes inherited from mbf_abstract_nav::AbstractPlannerExecution
 CANCELED
 
 FOUND_PLAN
 
 INITIALIZED
 
 INTERNAL_ERROR
 
 MAX_RETRIES
 
 NO_PLAN_FOUND
 
 PAT_EXCEEDED
 
 PLANNING
 
 STARTED
 
 STOPPED
 
- Public Attributes inherited from mbf_abstract_nav::AbstractExecutionBase
boost::function< void()> cleanup_fn_
 
boost::function< void()> setup_fn_
 
- 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_
 
- 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 57 of file costmap_planner_execution.h.

Member Typedef Documentation

Definition at line 60 of file costmap_planner_execution.h.

Constructor & Destructor Documentation

mbf_costmap_nav::CostmapPlannerExecution::CostmapPlannerExecution ( const std::string  name,
const mbf_costmap_core::CostmapPlanner::Ptr planner_ptr,
CostmapPtr costmap,
const MoveBaseFlexConfig &  config,
boost::function< void()>  setup_fn,
boost::function< void()>  cleanup_fn 
)

Constructor.

Parameters
conditionThread sleep condition variable, to wake up connected threads
costmapShared pointer to the costmap.

Definition at line 47 of file costmap_planner_execution.cpp.

mbf_costmap_nav::CostmapPlannerExecution::~CostmapPlannerExecution ( )
virtual

Destructor.

Definition at line 61 of file costmap_planner_execution.cpp.

Member Function Documentation

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 75 of file costmap_planner_execution.cpp.

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

Definition at line 65 of file costmap_planner_execution.cpp.

Member Data Documentation

CostmapPtr& mbf_costmap_nav::CostmapPlannerExecution::costmap_ptr_
private

Shared pointer to the global planner costmap.

Definition at line 104 of file costmap_planner_execution.h.

bool mbf_costmap_nav::CostmapPlannerExecution::lock_costmap_
private

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

Definition at line 107 of file costmap_planner_execution.h.

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

Name of the planner assigned by the class loader.

Definition at line 110 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 Tue Jun 18 2019 19:34:40