include
teb_local_planner
recovery_behaviors.h
Go to the documentation of this file.
1
/*********************************************************************
2
*
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2016,
6
* TU Dortmund - Institute of Control Theory and Systems Engineering.
7
* All rights reserved.
8
*
9
* Redistribution and use in source and binary forms, with or without
10
* modification, are permitted provided that the following conditions
11
* are met:
12
*
13
* * Redistributions of source code must retain the above copyright
14
* notice, this list of conditions and the following disclaimer.
15
* * Redistributions in binary form must reproduce the above
16
* copyright notice, this list of conditions and the following
17
* disclaimer in the documentation and/or other materials provided
18
* with the distribution.
19
* * Neither the name of the institute nor the names of its
20
* contributors may be used to endorse or promote products derived
21
* from this software without specific prior written permission.
22
*
23
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34
* POSSIBILITY OF SUCH DAMAGE.
35
*
36
* Author: Christoph Rösmann
37
*********************************************************************/
38
39
#ifndef RECOVERY_BEHAVIORS_H__
40
#define RECOVERY_BEHAVIORS_H__
41
42
43
#include <boost/circular_buffer.hpp>
44
#include <geometry_msgs/Twist.h>
45
#include <
ros/ros.h
>
46
47
namespace
teb_local_planner
48
{
49
50
58
class
FailureDetector
59
{
60
public
:
61
65
FailureDetector
() {}
66
70
~FailureDetector
() {}
71
76
void
setBufferLength
(
int
length) {
buffer_
.set_capacity(length);}
77
87
void
update
(
const
geometry_msgs::Twist
& twist,
double
v_max,
double
v_backwards_max,
double
omega_max,
double
v_eps,
double
omega_eps);
88
96
bool
isOscillating
()
const
;
97
103
void
clear
();
104
105
protected
:
106
108
struct
VelMeasurement
109
{
110
double
v
= 0;
111
double
omega
= 0;
112
};
113
122
bool
detect
(
double
v_eps,
double
omega_eps);
123
124
private
:
125
126
boost::circular_buffer<VelMeasurement>
buffer_
;
127
bool
oscillating_
=
false
;
128
129
};
130
131
132
}
// namespace teb_local_planner
133
134
#endif
/* RECOVERY_BEHAVIORS_H__ */
teb_local_planner::FailureDetector::buffer_
boost::circular_buffer< VelMeasurement > buffer_
Circular buffer to store the last measurements.
Definition:
recovery_behaviors.h:162
cmd_vel_to_ackermann_drive.Twist
Twist
Definition:
cmd_vel_to_ackermann_drive.py:56
teb_local_planner::FailureDetector::update
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.
Definition:
recovery_behaviors.cpp:87
ros.h
teb_local_planner::FailureDetector::setBufferLength
void setBufferLength(int length)
Set buffer length (measurement history)
Definition:
recovery_behaviors.h:112
teb_local_planner::FailureDetector::clear
void clear()
Clear the current internal state.
Definition:
recovery_behaviors.cpp:110
teb_local_planner::FailureDetector::isOscillating
bool isOscillating() const
Check if the robot got stucked.
Definition:
recovery_behaviors.cpp:116
teb_local_planner::FailureDetector::VelMeasurement::omega
double omega
Definition:
recovery_behaviors.h:147
teb_local_planner::FailureDetector::~FailureDetector
~FailureDetector()
destructor.
Definition:
recovery_behaviors.h:106
teb_local_planner::FailureDetector::VelMeasurement::v
double v
Definition:
recovery_behaviors.h:146
teb_local_planner::FailureDetector::VelMeasurement
Definition:
recovery_behaviors.h:144
teb_local_planner::FailureDetector::oscillating_
bool oscillating_
Current state: true if robot is oscillating.
Definition:
recovery_behaviors.h:163
teb_local_planner
Definition:
distance_calculations.h:46
teb_local_planner::FailureDetector::detect
bool detect(double v_eps, double omega_eps)
Detect if the robot got stucked based on the current buffer content.
Definition:
recovery_behaviors.cpp:121
teb_local_planner::FailureDetector::FailureDetector
FailureDetector()
Default constructor.
Definition:
recovery_behaviors.h:101
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15