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

The AbstractRecoveryExecution class loads and binds the recovery behavior plugin. It contains a thread running the plugin, executing the recovery behavior. An internal state is saved and will be pulled by the server, which controls the recovery behavior execution. Due to a state change it wakes up all threads connected to the condition variable. More...

#include <abstract_recovery_execution.h>

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

Public Types

typedef boost::shared_ptr< AbstractRecoveryExecutionPtr
 
enum  RecoveryState {
  INITIALIZED, STARTED, RECOVERING, WRONG_NAME,
  RECOVERY_DONE, CANCELED, STOPPED, INTERNAL_ERROR
}
 internal state. More...
 

Public Member Functions

 AbstractRecoveryExecution (const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &recovery_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...
 
AbstractRecoveryExecution::RecoveryState getState ()
 Returns the current state, thread-safe communication. More...
 
bool isPatienceExceeded ()
 Checks whether the patience was exceeded. More...
 
void reconfigure (const MoveBaseFlexConfig &config)
 Reconfigures the current configuration and reloads all parameters. This method is called from a dynamic reconfigure tool. More...
 
virtual ~AbstractRecoveryExecution ()
 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 ()
 Main execution method which will be executed by the recovery execution thread_. More...
 

Protected Attributes

mbf_abstract_core::AbstractRecovery::Ptr behavior_
 the current loaded recovery behavior More...
 
const TFPtr tf_listener_ptr_
 shared pointer to 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

void setState (RecoveryState state)
 Sets the current internal state. This method is thread communication safe. More...
 

Private Attributes

boost::mutex conf_mtx_
 dynamic reconfigure and start time mutexes to mutually exclude read/write configuration More...
 
ros::Duration patience_
 recovery behavior allowed time More...
 
ros::Time start_time_
 recovery behavior start time More...
 
RecoveryState state_
 current internal state More...
 
boost::mutex state_mtx_
 mutex to handle safe thread communication for the current state More...
 
boost::mutex time_mtx_
 

Detailed Description

The AbstractRecoveryExecution class loads and binds the recovery behavior plugin. It contains a thread running the plugin, executing the recovery behavior. An internal state is saved and will be pulled by the server, which controls the recovery behavior execution. Due to a state change it wakes up all threads connected to the condition variable.

Definition at line 74 of file abstract_recovery_execution.h.

Member Typedef Documentation

◆ Ptr

Definition at line 78 of file abstract_recovery_execution.h.

Member Enumeration Documentation

◆ RecoveryState

internal state.

Enumerator
INITIALIZED 

The recovery execution has been initialized.

STARTED 

The recovery execution thread has been started.

RECOVERING 

The recovery behavior plugin is running.

WRONG_NAME 

The given name could not be associated with a load behavior.

RECOVERY_DONE 

The recovery behavior execution is done.

CANCELED 

The recovery execution was canceled.

STOPPED 

The recovery execution has been stopped.

INTERNAL_ERROR 

An internal error occurred.

Definition at line 111 of file abstract_recovery_execution.h.

Constructor & Destructor Documentation

◆ AbstractRecoveryExecution()

mbf_abstract_nav::AbstractRecoveryExecution::AbstractRecoveryExecution ( const std::string &  name,
const mbf_abstract_core::AbstractRecovery::Ptr recovery_ptr,
const TFPtr tf_listener_ptr,
const MoveBaseFlexConfig &  config 
)

Constructor.

Parameters
conditionThread sleep condition variable, to wake up connected threads
tf_listener_ptrShared pointer to a common tf listener

Definition at line 48 of file abstract_recovery_execution.cpp.

◆ ~AbstractRecoveryExecution()

mbf_abstract_nav::AbstractRecoveryExecution::~AbstractRecoveryExecution ( )
virtual

Destructor.

Definition at line 60 of file abstract_recovery_execution.cpp.

Member Function Documentation

◆ cancel()

bool mbf_abstract_nav::AbstractRecoveryExecution::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 90 of file abstract_recovery_execution.cpp.

◆ getState()

AbstractRecoveryExecution::RecoveryState mbf_abstract_nav::AbstractRecoveryExecution::getState ( )

Returns the current state, thread-safe communication.

Returns
current internal state

Definition at line 84 of file abstract_recovery_execution.cpp.

◆ isPatienceExceeded()

bool mbf_abstract_nav::AbstractRecoveryExecution::isPatienceExceeded ( )

Checks whether the patience was exceeded.

Returns
true, if the patience duration was exceeded.

Definition at line 103 of file abstract_recovery_execution.cpp.

◆ reconfigure()

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

Reconfigures the current configuration and reloads all parameters. This method is called from a dynamic reconfigure tool.

Parameters
configCurrent MoveBaseFlexConfig object. See the MoveBaseFlex.cfg definition.

Definition at line 65 of file abstract_recovery_execution.cpp.

◆ run()

void mbf_abstract_nav::AbstractRecoveryExecution::run ( )
protectedvirtual

Main execution method which will be executed by the recovery execution thread_.

Reimplemented from mbf_abstract_nav::AbstractExecutionBase.

Definition at line 111 of file abstract_recovery_execution.cpp.

◆ setState()

void mbf_abstract_nav::AbstractRecoveryExecution::setState ( RecoveryState  state)
private

Sets the current internal state. This method is thread communication safe.

Parameters
stateThe state to set.

Definition at line 77 of file abstract_recovery_execution.cpp.

Member Data Documentation

◆ behavior_

mbf_abstract_core::AbstractRecovery::Ptr mbf_abstract_nav::AbstractRecoveryExecution::behavior_
protected

the current loaded recovery behavior

Definition at line 144 of file abstract_recovery_execution.h.

◆ conf_mtx_

boost::mutex mbf_abstract_nav::AbstractRecoveryExecution::conf_mtx_
private

dynamic reconfigure and start time mutexes to mutually exclude read/write configuration

Definition at line 161 of file abstract_recovery_execution.h.

◆ patience_

ros::Duration mbf_abstract_nav::AbstractRecoveryExecution::patience_
private

recovery behavior allowed time

Definition at line 165 of file abstract_recovery_execution.h.

◆ start_time_

ros::Time mbf_abstract_nav::AbstractRecoveryExecution::start_time_
private

recovery behavior start time

Definition at line 168 of file abstract_recovery_execution.h.

◆ state_

RecoveryState mbf_abstract_nav::AbstractRecoveryExecution::state_
private

current internal state

Definition at line 171 of file abstract_recovery_execution.h.

◆ state_mtx_

boost::mutex mbf_abstract_nav::AbstractRecoveryExecution::state_mtx_
private

mutex to handle safe thread communication for the current state

Definition at line 158 of file abstract_recovery_execution.h.

◆ tf_listener_ptr_

const TFPtr mbf_abstract_nav::AbstractRecoveryExecution::tf_listener_ptr_
protected

shared pointer to common TransformListener

Definition at line 147 of file abstract_recovery_execution.h.

◆ time_mtx_

boost::mutex mbf_abstract_nav::AbstractRecoveryExecution::time_mtx_
private

Definition at line 162 of file abstract_recovery_execution.h.


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


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