Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
mbf_abstract_nav::AbstractPlannerExecution Class Reference

The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread running the plugin in a cycle to plan and re-plan. An internal state is saved and will be pulled by the server, which controls the global planner execution. Due to a state change it wakes up all threads connected to the condition variable. More...

#include <abstract_planner_execution.h>

Inheritance diagram for mbf_abstract_nav::AbstractPlannerExecution:
Inheritance graph
[legend]

Public Types

enum  PlanningState {
  INITIALIZED, STARTED, PLANNING, FOUND_PLAN,
  MAX_RETRIES, PAT_EXCEEDED, NO_PLAN_FOUND, CANCELED,
  STOPPED, INTERNAL_ERROR
}
 Internal states. More...
 
typedef boost::shared_ptr< AbstractPlannerExecutionPtr
 shared pointer type to the planner execution. More...
 

Public Member Functions

 AbstractPlannerExecution (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const MoveBaseFlexConfig &config)
 Constructor. More...
 
 AbstractPlannerExecution (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const TFPtr &tf_listener_ptr, const MoveBaseFlexConfig &config)
 Constructor. More...
 
virtual bool cancel ()
 Cancel the planner execution. This calls the cancel method of the planner plugin. This could be useful if the computation takes too much time, or if we are aborting the navigation. More...
 
double getCost () const
 Gets computed costs. More...
 
double getFrequency () const
 Gets planning frequency. More...
 
ros::Time getLastValidPlanTime () const
 Returns the last time a valid plan was available. More...
 
std::vector< geometry_msgs::PoseStamped > getPlan () const
 Returns a new plan, if one is available. More...
 
PlanningState getState () const
 Returns the current internal state. More...
 
bool isPatienceExceeded () const
 Checks whether the patience was exceeded. More...
 
void reconfigure (const MoveBaseFlexConfig &config)
 Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconfigure to reconfigure the current state. More...
 
void setNewGoal (const geometry_msgs::PoseStamped &goal, double tolerance)
 Sets a new goal pose for the planner execution. More...
 
void setNewStart (const geometry_msgs::PoseStamped &start)
 Sets a new start pose for the planner execution. More...
 
void setNewStartAndGoal (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance)
 Sets a new star and goal pose for the planner execution. More...
 
bool start (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance)
 Starts the planner execution thread with the given parameters. More...
 
virtual ~AbstractPlannerExecution ()
 Destructor. More...
 
- Public Member Functions inherited from mbf_abstract_nav::AbstractExecutionBase
 AbstractExecutionBase (const std::string &name)
 
const std::string & getMessage () const
 Gets the current plugin execution message. More...
 
const std::string & getName () const
 Returns the name of the corresponding plugin. More...
 
uint32_t getOutcome () const
 Gets the current plugin execution outcome. More...
 
void join ()
 
virtual void postRun ()
 Optional implementation-specific cleanup function, called right after execution. More...
 
virtual void preRun ()
 Optional implementation-specific setup function, called right before execution. More...
 
virtual void reconfigure (MoveBaseFlexConfig &_cfg)
 Optional implementaiton-specific configuration function. More...
 
virtual bool start ()
 
virtual void stop ()
 
boost::cv_status waitForStateUpdate (boost::chrono::microseconds const &duration)
 
virtual ~AbstractExecutionBase ()
 

Protected Member Functions

virtual void run ()
 The main run method, a thread will execute this method. It contains the main planner execution loop. More...
 

Protected Attributes

mbf_abstract_core::AbstractPlanner::Ptr planner_
 the local planer to calculate the robot trajectory More...
 
std::string plugin_name_
 the name of the loaded planner plugin More...
 
const TFPtr tf_listener_ptr_
 shared pointer to a common TransformListener More...
 
- Protected Attributes inherited from mbf_abstract_nav::AbstractExecutionBase
bool cancel_
 flag for canceling controlling More...
 
boost::condition_variable condition_
 condition variable to wake up control thread More...
 
std::string message_
 the last received plugin execution message More...
 
std::string name_
 the plugin name; not the plugin type! More...
 
uint32_t outcome_
 the last received plugin execution outcome More...
 
boost::thread thread_
 the controlling thread object More...
 

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 setState (PlanningState state, bool signalling)
 Sets the internal state, thread communication safe. More...
 

Private Attributes

boost::mutex configuration_mutex_
 dynamic reconfigure mutex for a thread safe communication More...
 
double cost_
 current global plan cost More...
 
double frequency_
 planning cycle frequency (used only when running full navigation; we store here for grouping parameters nicely) More...
 
std::string global_frame_
 the global frame in which the planner needs to plan More...
 
geometry_msgs::PoseStamped goal_
 the current goal pose used for planning More...
 
boost::mutex goal_start_mtx_
 mutex to handle safe thread communication for the goal and start pose. More...
 
bool has_new_goal_
 true, if a new goal pose has been set, until it is used. More...
 
bool has_new_start_
 true, if a new start pose has been set, until it is used. More...
 
ros::Time last_call_start_time_
 the last call start time, updated each cycle. More...
 
ros::Time last_valid_plan_time_
 the last time a valid plan has been computed. More...
 
int max_retries_
 planning max retries More...
 
ros::Duration patience_
 planning patience duration time More...
 
std::vector< geometry_msgs::PoseStamped > plan_
 current global plan More...
 
boost::mutex plan_mtx_
 mutex to handle safe thread communication for the plan and plan-costs More...
 
bool planning_
 main cycle variable of the execution loop More...
 
boost::mutex planning_mtx_
 mutex to handle safe thread communication for the planning_ flag. More...
 
std::string robot_frame_
 robot frame used for computing the current robot pose More...
 
geometry_msgs::PoseStamped start_
 the current start pose used for planning More...
 
PlanningState state_
 current internal state More...
 
boost::mutex state_mtx_
 mutex to handle safe thread communication for the current state More...
 
double tolerance_
 optional goal tolerance, in meters More...
 

Detailed Description

The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread running the plugin in a cycle to plan and re-plan. An internal state is saved and will be pulled by the server, which controls the global planner execution. Due to a state change it wakes up all threads connected to the condition variable.

Definition at line 74 of file abstract_planner_execution.h.

Member Typedef Documentation

◆ Ptr

shared pointer type to the planner execution.

Definition at line 79 of file abstract_planner_execution.h.

Member Enumeration Documentation

◆ PlanningState

Internal states.

Enumerator
INITIALIZED 

Planner initialized.

STARTED 

Planner started.

PLANNING 

Executing the plugin.

FOUND_PLAN 

Found a valid plan.

MAX_RETRIES 

Exceeded the maximum number of retries without a valid command.

PAT_EXCEEDED 

Exceeded the patience time without a valid command.

NO_PLAN_FOUND 

No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).

CANCELED 

The planner has been canceled.

STOPPED 

The planner has been stopped.

INTERNAL_ERROR 

An internal error occurred.

Definition at line 125 of file abstract_planner_execution.h.

Constructor & Destructor Documentation

◆ AbstractPlannerExecution() [1/2]

mbf_abstract_nav::AbstractPlannerExecution::AbstractPlannerExecution ( const std::string &  name,
const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr,
const MoveBaseFlexConfig &  config 
)

Constructor.

Parameters
nameName of this execution
planner_ptrPointer to the planner
configInitial configuration for this execution

Definition at line 45 of file src/abstract_planner_execution.cpp.

◆ AbstractPlannerExecution() [2/2]

mbf_abstract_nav::AbstractPlannerExecution::AbstractPlannerExecution ( const std::string &  name,
const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr,
const TFPtr tf_listener_ptr,
const MoveBaseFlexConfig &  config 
)

Constructor.

Parameters
nameName of this execution
planner_ptrPointer to the planner
tf_listener_ptrShared Pointer to a tf-listener.
configInitial configuration for this execution

Definition at line 66 of file src/abstract_planner_execution.cpp.

◆ ~AbstractPlannerExecution()

mbf_abstract_nav::AbstractPlannerExecution::~AbstractPlannerExecution ( )
virtual

Destructor.

Definition at line 88 of file src/abstract_planner_execution.cpp.

Member Function Documentation

◆ cancel()

bool mbf_abstract_nav::AbstractPlannerExecution::cancel ( )
virtual

Cancel the planner execution. This calls the cancel method of the planner plugin. This could be useful if the computation takes too much time, or if we are aborting the navigation.

Returns
true, if the planner plugin tries / tried to cancel the planning step.

Reimplemented from mbf_abstract_nav::AbstractExecutionBase.

Definition at line 231 of file src/abstract_planner_execution.cpp.

◆ getCost()

double mbf_abstract_nav::AbstractPlannerExecution::getCost ( ) const

Gets computed costs.

Returns
The costs of the computed path

Definition at line 110 of file src/abstract_planner_execution.cpp.

◆ getFrequency()

double mbf_abstract_nav::AbstractPlannerExecution::getFrequency ( ) const
inline

Gets planning frequency.

Definition at line 148 of file abstract_planner_execution.h.

◆ getLastValidPlanTime()

ros::Time mbf_abstract_nav::AbstractPlannerExecution::getLastValidPlanTime ( ) const

Returns the last time a valid plan was available.

Returns
time, the last valid plan was available.

Definition at line 156 of file src/abstract_planner_execution.cpp.

◆ getPlan()

std::vector< geometry_msgs::PoseStamped > mbf_abstract_nav::AbstractPlannerExecution::getPlan ( ) const

Returns a new plan, if one is available.

Definition at line 169 of file src/abstract_planner_execution.cpp.

◆ getState()

AbstractPlannerExecution::PlanningState mbf_abstract_nav::AbstractPlannerExecution::getState ( ) const

Returns the current internal state.

Returns
the current internal state

Definition at line 136 of file src/abstract_planner_execution.cpp.

◆ isPatienceExceeded()

bool mbf_abstract_nav::AbstractPlannerExecution::isPatienceExceeded ( ) const

Checks whether the patience was exceeded.

Returns
true, if the patience duration was exceeded.

Definition at line 163 of file src/abstract_planner_execution.cpp.

◆ makePlan()

uint32_t mbf_abstract_nav::AbstractPlannerExecution::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

Definition at line 246 of file src/abstract_planner_execution.cpp.

◆ reconfigure()

void mbf_abstract_nav::AbstractPlannerExecution::reconfigure ( const MoveBaseFlexConfig &  config)

Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconfigure to reconfigure the current state.

Parameters
configMoveBaseFlexConfig object

Definition at line 115 of file src/abstract_planner_execution.cpp.

◆ run()

void mbf_abstract_nav::AbstractPlannerExecution::run ( )
protectedvirtual

The main run method, a thread will execute this method. It contains the main planner execution loop.

Reimplemented from mbf_abstract_nav::AbstractExecutionBase.

Definition at line 256 of file src/abstract_planner_execution.cpp.

◆ setNewGoal()

void mbf_abstract_nav::AbstractPlannerExecution::setNewGoal ( const geometry_msgs::PoseStamped &  goal,
double  tolerance 
)

Sets a new goal pose for the planner execution.

Parameters
goalthe new goal pose
tolerancetolerance to the goal for the planning

Definition at line 177 of file src/abstract_planner_execution.cpp.

◆ setNewStart()

void mbf_abstract_nav::AbstractPlannerExecution::setNewStart ( const geometry_msgs::PoseStamped &  start)

Sets a new start pose for the planner execution.

Parameters
startnew start pose

Definition at line 186 of file src/abstract_planner_execution.cpp.

◆ setNewStartAndGoal()

void mbf_abstract_nav::AbstractPlannerExecution::setNewStartAndGoal ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance 
)

Sets a new star and goal pose for the planner execution.

Parameters
startnew start pose
goalnew goal pose
tolerancetolerance to the new goal for the planning

Definition at line 194 of file src/abstract_planner_execution.cpp.

◆ setState()

void mbf_abstract_nav::AbstractPlannerExecution::setState ( PlanningState  state,
bool  signalling 
)
private

Sets the internal state, thread communication safe.

Parameters
statethe current state
signallingset true to trigger the condition-variable for state-update

Definition at line 142 of file src/abstract_planner_execution.cpp.

◆ start()

bool mbf_abstract_nav::AbstractPlannerExecution::start ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance 
)

Starts the planner execution thread with the given parameters.

Parameters
startstart pose for the planning
goalgoal pose for the planning
tolerancetolerance to the goal pose for the planning
Returns
true, if the planner thread has been started, false if the thread is already running.

Definition at line 207 of file src/abstract_planner_execution.cpp.

Member Data Documentation

◆ configuration_mutex_

boost::mutex mbf_abstract_nav::AbstractPlannerExecution::configuration_mutex_
mutableprivate

dynamic reconfigure mutex for a thread safe communication

Definition at line 259 of file abstract_planner_execution.h.

◆ cost_

double mbf_abstract_nav::AbstractPlannerExecution::cost_
private

current global plan cost

Definition at line 277 of file abstract_planner_execution.h.

◆ frequency_

double mbf_abstract_nav::AbstractPlannerExecution::frequency_
private

planning cycle frequency (used only when running full navigation; we store here for grouping parameters nicely)

Definition at line 289 of file abstract_planner_execution.h.

◆ global_frame_

std::string mbf_abstract_nav::AbstractPlannerExecution::global_frame_
private

the global frame in which the planner needs to plan

Definition at line 304 of file abstract_planner_execution.h.

◆ goal_

geometry_msgs::PoseStamped mbf_abstract_nav::AbstractPlannerExecution::goal_
private

the current goal pose used for planning

Definition at line 283 of file abstract_planner_execution.h.

◆ goal_start_mtx_

boost::mutex mbf_abstract_nav::AbstractPlannerExecution::goal_start_mtx_
mutableprivate

mutex to handle safe thread communication for the goal and start pose.

Definition at line 253 of file abstract_planner_execution.h.

◆ has_new_goal_

bool mbf_abstract_nav::AbstractPlannerExecution::has_new_goal_
private

true, if a new goal pose has been set, until it is used.

Definition at line 262 of file abstract_planner_execution.h.

◆ has_new_start_

bool mbf_abstract_nav::AbstractPlannerExecution::has_new_start_
private

true, if a new start pose has been set, until it is used.

Definition at line 265 of file abstract_planner_execution.h.

◆ last_call_start_time_

ros::Time mbf_abstract_nav::AbstractPlannerExecution::last_call_start_time_
private

the last call start time, updated each cycle.

Definition at line 268 of file abstract_planner_execution.h.

◆ last_valid_plan_time_

ros::Time mbf_abstract_nav::AbstractPlannerExecution::last_valid_plan_time_
private

the last time a valid plan has been computed.

Definition at line 271 of file abstract_planner_execution.h.

◆ max_retries_

int mbf_abstract_nav::AbstractPlannerExecution::max_retries_
private

planning max retries

Definition at line 295 of file abstract_planner_execution.h.

◆ patience_

ros::Duration mbf_abstract_nav::AbstractPlannerExecution::patience_
private

planning patience duration time

Definition at line 292 of file abstract_planner_execution.h.

◆ plan_

std::vector<geometry_msgs::PoseStamped> mbf_abstract_nav::AbstractPlannerExecution::plan_
private

current global plan

Definition at line 274 of file abstract_planner_execution.h.

◆ plan_mtx_

boost::mutex mbf_abstract_nav::AbstractPlannerExecution::plan_mtx_
mutableprivate

mutex to handle safe thread communication for the plan and plan-costs

Definition at line 250 of file abstract_planner_execution.h.

◆ planner_

mbf_abstract_core::AbstractPlanner::Ptr mbf_abstract_nav::AbstractPlannerExecution::planner_
protected

the local planer to calculate the robot trajectory

Definition at line 205 of file abstract_planner_execution.h.

◆ planning_

bool mbf_abstract_nav::AbstractPlannerExecution::planning_
private

main cycle variable of the execution loop

Definition at line 298 of file abstract_planner_execution.h.

◆ planning_mtx_

boost::mutex mbf_abstract_nav::AbstractPlannerExecution::planning_mtx_
mutableprivate

mutex to handle safe thread communication for the planning_ flag.

Definition at line 256 of file abstract_planner_execution.h.

◆ plugin_name_

std::string mbf_abstract_nav::AbstractPlannerExecution::plugin_name_
protected

the name of the loaded planner plugin

Definition at line 208 of file abstract_planner_execution.h.

◆ robot_frame_

std::string mbf_abstract_nav::AbstractPlannerExecution::robot_frame_
private

robot frame used for computing the current robot pose

Definition at line 301 of file abstract_planner_execution.h.

◆ start_

geometry_msgs::PoseStamped mbf_abstract_nav::AbstractPlannerExecution::start_
private

the current start pose used for planning

Definition at line 280 of file abstract_planner_execution.h.

◆ state_

PlanningState mbf_abstract_nav::AbstractPlannerExecution::state_
private

current internal state

Definition at line 307 of file abstract_planner_execution.h.

◆ state_mtx_

boost::mutex mbf_abstract_nav::AbstractPlannerExecution::state_mtx_
mutableprivate

mutex to handle safe thread communication for the current state

Definition at line 247 of file abstract_planner_execution.h.

◆ tf_listener_ptr_

const TFPtr mbf_abstract_nav::AbstractPlannerExecution::tf_listener_ptr_
protected

shared pointer to a common TransformListener

Definition at line 211 of file abstract_planner_execution.h.

◆ tolerance_

double mbf_abstract_nav::AbstractPlannerExecution::tolerance_
private

optional goal tolerance, in meters

Definition at line 286 of file abstract_planner_execution.h.


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


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:48