Classes | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
teb_local_planner::FailureDetector Class Reference

This class implements methods in order to detect if the robot got stucked or is oscillating. More...

#include <recovery_behaviors.h>

Classes

struct  VelMeasurement
 

Public Member Functions

void clear ()
 Clear the current internal state. More...
 
 FailureDetector ()
 Default constructor. More...
 
bool isOscillating () const
 Check if the robot got stucked. More...
 
void setBufferLength (int length)
 Set buffer length (measurement history) More...
 
void update (const geometry_msgs::Twist &twist, double v_max, double v_backwards_max, double omega_max, double v_eps, double omega_eps)
 Add a new twist measurement to the internal buffer and compute a new decision. More...
 
 ~FailureDetector ()
 destructor. More...
 

Protected Member Functions

bool detect (double v_eps, double omega_eps)
 Detect if the robot got stucked based on the current buffer content. More...
 

Private Attributes

boost::circular_buffer< VelMeasurementbuffer_
 Circular buffer to store the last measurements. More...
 
bool oscillating_ = false
 Current state: true if robot is oscillating. More...
 

Detailed Description

This class implements methods in order to detect if the robot got stucked or is oscillating.

The StuckDetector analyzes the last N commanded velocities in order to detect whether the robot might got stucked or oscillates between left/right/forward/backwards motions.

Definition at line 58 of file recovery_behaviors.h.

Constructor & Destructor Documentation

teb_local_planner::FailureDetector::FailureDetector ( )
inline

Default constructor.

Definition at line 65 of file recovery_behaviors.h.

teb_local_planner::FailureDetector::~FailureDetector ( )
inline

destructor.

Definition at line 70 of file recovery_behaviors.h.

Member Function Documentation

void teb_local_planner::FailureDetector::clear ( )

Clear the current internal state.

This call also resets the internal buffer

Definition at line 74 of file recovery_behaviors.cpp.

bool teb_local_planner::FailureDetector::detect ( double  v_eps,
double  omega_eps 
)
protected

Detect if the robot got stucked based on the current buffer content.

Afterwards the status might be checked using gotStucked();

Parameters
v_epsThreshold for the average normalized linear velocity in (0,1) that must not be exceded (e.g. 0.1)
omega_epsThreshold for the average normalized angular velocity in (0,1) that must not be exceded (e.g. 0.1)
Returns
true if the robot got stucked, false otherwise

Definition at line 85 of file recovery_behaviors.cpp.

bool teb_local_planner::FailureDetector::isOscillating ( ) const

Check if the robot got stucked.

This call does not compute the actual decision, since it is computed within each update() invocation.

Returns
true if the robot got stucked, false otherwise.

Definition at line 80 of file recovery_behaviors.cpp.

void teb_local_planner::FailureDetector::setBufferLength ( int  length)
inline

Set buffer length (measurement history)

Parameters
lengthnumber of measurements to be kept

Definition at line 76 of file recovery_behaviors.h.

void teb_local_planner::FailureDetector::update ( const geometry_msgs::Twist &  twist,
double  v_max,
double  v_backwards_max,
double  omega_max,
double  v_eps,
double  omega_eps 
)

Add a new twist measurement to the internal buffer and compute a new decision.

Parameters
twistgeometry_msgs::Twist velocity information
v_maxmaximum forward translational velocity
v_backwards_maxmaximum backward translational velocity
omega_maxmaximum angular velocity
v_epsThreshold for the average normalized linear velocity in (0,1) that must not be exceded (e.g. 0.1)
omega_epsThreshold for the average normalized angular velocity in (0,1) that must not be exceded (e.g. 0.1)

Definition at line 51 of file recovery_behaviors.cpp.

Member Data Documentation

boost::circular_buffer<VelMeasurement> teb_local_planner::FailureDetector::buffer_
private

Circular buffer to store the last measurements.

See also
setBufferLength

Definition at line 126 of file recovery_behaviors.h.

bool teb_local_planner::FailureDetector::oscillating_ = false
private

Current state: true if robot is oscillating.

Definition at line 127 of file recovery_behaviors.h.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08