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< VelMeasurement > | buffer_ |
Circular buffer to store the last measurements. More... | |
bool | oscillating_ = false |
Current state: true if robot is oscillating. More... | |
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.
|
inline |
Default constructor.
Definition at line 65 of file recovery_behaviors.h.
|
inline |
destructor.
Definition at line 70 of file recovery_behaviors.h.
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.
|
protected |
Detect if the robot got stucked based on the current buffer content.
Afterwards the status might be checked using gotStucked();
v_eps | Threshold for the average normalized linear velocity in (0,1) that must not be exceded (e.g. 0.1) |
omega_eps | Threshold for the average normalized angular velocity in (0,1) that must not be exceded (e.g. 0.1) |
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.
Definition at line 80 of file recovery_behaviors.cpp.
|
inline |
Set buffer length (measurement history)
length | number 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.
twist | geometry_msgs::Twist velocity information |
v_max | maximum forward translational velocity |
v_backwards_max | maximum backward translational velocity |
omega_max | maximum angular velocity |
v_eps | Threshold for the average normalized linear velocity in (0,1) that must not be exceded (e.g. 0.1) |
omega_eps | Threshold 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.
|
private |
Circular buffer to store the last measurements.
Definition at line 126 of file recovery_behaviors.h.
|
private |
Current state: true if robot is oscillating.
Definition at line 127 of file recovery_behaviors.h.