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>
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::Ptr & | costmap_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< AbstractPlannerExecution > | Ptr |
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_ |
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.
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.
planner_name | Name of the planner to use. |
planner_ptr | Shared pointer to the plugin to use. |
tf_listener_ptr | Shared pointer to the tf-listener. |
costmap_ptr | Shared pointer to the global costmap. |
config | Current server configuration (dynamic). |
Definition at line 47 of file costmap_planner_execution.cpp.
|
virtual |
Destructor.
Definition at line 57 of file costmap_planner_execution.cpp.
|
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.
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 |
Reimplemented from mbf_abstract_nav::AbstractPlannerExecution.
Definition at line 71 of file costmap_planner_execution.cpp.
|
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.
|
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.
|
private |
Definition at line 61 of file costmap_planner_execution.cpp.
|
private |
Shared pointer to the global planner costmap.
Definition at line 122 of file costmap_planner_execution.h.
|
private |
Whether to lock costmap before calling the planner (see issue #4 for details)
Definition at line 125 of file costmap_planner_execution.h.
|
private |
Name of the planner assigned by the class loader.
Definition at line 128 of file costmap_planner_execution.h.