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>
|
| 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...
|
|
| 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 () |
|
| 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) |
|
|
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 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.
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
-
condition | Thread sleep condition variable, to wake up connected threads |
costmap | Shared pointer to the costmap. |
Definition at line 47 of file costmap_planner_execution.cpp.
mbf_costmap_nav::CostmapPlannerExecution::~CostmapPlannerExecution |
( |
| ) |
|
|
virtual |
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
-
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 75 of file costmap_planner_execution.cpp.
mbf_abstract_nav::MoveBaseFlexConfig mbf_costmap_nav::CostmapPlannerExecution::toAbstract |
( |
const MoveBaseFlexConfig & |
config | ) |
|
|
private |
CostmapPtr& mbf_costmap_nav::CostmapPlannerExecution::costmap_ptr_ |
|
private |
bool mbf_costmap_nav::CostmapPlannerExecution::lock_costmap_ |
|
private |
std::string mbf_costmap_nav::CostmapPlannerExecution::planner_name_ |
|
private |
The documentation for this class was generated from the following files: