Dynamic window approach.
More...
#include <dynamic_window.hpp>
|
| tuple< bool, vec > | control (const GridMap &grid, const vec &x0, const vec &vb, const mat &xt_ref, double dt_ref) const |
| | Compose best control. More...
|
| |
| tuple< bool, vec > | control (const GridMap &grid, const vec &x0, const vec &vb, const vec &vref) const |
| | Compose best control. More...
|
| |
| | DynamicWindow (const Collision &collision, double dt, double horizon, double acc_dt, double acc_lim_x, double acc_lim_y, double acc_lim_th, double max_vel_x, double min_vel_x, double max_vel_y, double min_vel_y, double max_rot_vel, double min_rot_vel, unsigned int vx_samples, unsigned int vy_samples, unsigned int vth_samples) |
| | Constructor. More...
|
| |
| double | horizon () const |
| | return control horizon More...
|
| |
| unsigned int | steps () const |
| | return number of steps in horizon More...
|
| |
| double | timeStep () const |
| | return time step More...
|
| |
|
| double | objective (const GridMap &grid, const vec &x0, const vec &u, const mat &xt_ref, double tf) const |
| | Objective function for reference trajectory. More...
|
| |
| double | objective (const GridMap &grid, const vec &x0, const vec &vref, const vec &u) const |
| | Objective function for reference twist. More...
|
| |
| tuple< vec, vec > | window (const vec &vb) const |
| | Compose window size and discretization. More...
|
| |
Dynamic window approach.
Definition at line 52 of file dynamic_window.hpp.
◆ DynamicWindow()
| ergodic_exploration::DynamicWindow::DynamicWindow |
( |
const Collision & |
collision, |
|
|
double |
dt, |
|
|
double |
horizon, |
|
|
double |
acc_dt, |
|
|
double |
acc_lim_x, |
|
|
double |
acc_lim_y, |
|
|
double |
acc_lim_th, |
|
|
double |
max_vel_x, |
|
|
double |
min_vel_x, |
|
|
double |
max_vel_y, |
|
|
double |
min_vel_y, |
|
|
double |
max_rot_vel, |
|
|
double |
min_rot_vel, |
|
|
unsigned int |
vx_samples, |
|
|
unsigned int |
vy_samples, |
|
|
unsigned int |
vth_samples |
|
) |
| |
Constructor.
- Parameters
-
| collision | - collision detector |
| dt | - time step in integration |
| horizon | - control horizon |
| acc_dt | - time acceleration limit is applied for determining window limits |
| acc_lim_x | - x acceleration limit |
| acc_lim_y | - y acceleration limit |
| acc_lim_th | - rotational acceleration limit |
| max_vel_x | - max x velocity |
| min_vel_x | - min x velocity |
| max_vel_y | - max y velocity |
| min_vel_y | - min y velocity |
| max_rot_vel | - max rotational velocity |
| min_rot_vel | - min rotational velocity |
| vx_samples | - number of x velocity samples |
| vy_samples | - number of y velocity samples |
| vth_samples | - number of rotational velocity samples |
Given a reference control finds the closest collision free control
Definition at line 46 of file dynamic_window.cpp.
◆ control() [1/2]
| tuple< bool, vec > ergodic_exploration::DynamicWindow::control |
( |
const GridMap & |
grid, |
|
|
const vec & |
x0, |
|
|
const vec & |
vb, |
|
|
const mat & |
xt_ref, |
|
|
double |
dt_ref |
|
) |
| const |
Compose best control.
- Parameters
-
| grid | - grid map |
| x0 | - current state [x, y, theta] |
| vb | - current twist [vx, vy, w] |
| xt_ref | - reference trajectory |
| dt_ref | - reference trajectory time discretization |
- Returns
- true if at least one solution is found and optimal twist [vx, vy, w]
u_opt is set to zeros if no solution found
Definition at line 141 of file dynamic_window.cpp.
◆ control() [2/2]
| tuple< bool, vec > ergodic_exploration::DynamicWindow::control |
( |
const GridMap & |
grid, |
|
|
const vec & |
x0, |
|
|
const vec & |
vb, |
|
|
const vec & |
vref |
|
) |
| const |
Compose best control.
- Parameters
-
| grid | - grid map |
| x0 | - current state [x, y, theta] |
| vb | - current twist [vx, vy, w] |
| vref | - desired twist to follow [vx, vy, w] |
- Returns
- true if at least 1 solution found and optimal twist [vx, vy, w]
u_opt is set to zeros if no solution found
Definition at line 92 of file dynamic_window.cpp.
◆ horizon()
| double ergodic_exploration::DynamicWindow::horizon |
( |
| ) |
const |
|
inline |
◆ objective() [1/2]
| double ergodic_exploration::DynamicWindow::objective |
( |
const GridMap & |
grid, |
|
|
const vec & |
x0, |
|
|
const vec & |
u, |
|
|
const mat & |
xt_ref, |
|
|
double |
tf |
|
) |
| const |
|
private |
Objective function for reference trajectory.
- Parameters
-
| grid | - grid map |
| x0 | - current state [x, y, theta] |
| u | - twist from dynamic window |
| xt_ref | - reference trajectory |
| tf | - reference trajectory length in time |
- Returns
- cost of the current sampled twist
- Finds best twist that generates a path closest to the reference trajectory that is collision free. If there is a collision the cost is the max numerical value for a double.
Definition at line 258 of file dynamic_window.cpp.
◆ objective() [2/2]
| double ergodic_exploration::DynamicWindow::objective |
( |
const GridMap & |
grid, |
|
|
const vec & |
x0, |
|
|
const vec & |
vref, |
|
|
const vec & |
u |
|
) |
| const |
|
private |
Objective function for reference twist.
- Parameters
-
| grid | - grid map |
| x0 | - current state [x, y, theta] |
| vref | - desired twist to follow [vx, vy, w] |
| u | - twist from dynamic window |
- Returns
- cost of the current sampled twist
- Finds best twist to reference twist that is collision free. If there is a collision the cost is the max numerical value for a double.
Definition at line 237 of file dynamic_window.cpp.
◆ steps()
| unsigned int ergodic_exploration::DynamicWindow::steps |
( |
| ) |
const |
|
inline |
◆ timeStep()
| double ergodic_exploration::DynamicWindow::timeStep |
( |
| ) |
const |
|
inline |
◆ window()
| tuple< vec, vec > ergodic_exploration::DynamicWindow::window |
( |
const vec & |
vb | ) |
const |
|
private |
Compose window size and discretization.
- Parameters
-
| vb | - current twist [vx, vy, w] |
- Returns
- twist lower limits and twist discretization
Definition at line 193 of file dynamic_window.cpp.
◆ acc_dt_
| double ergodic_exploration::DynamicWindow::acc_dt_ |
|
private |
◆ acc_lim_th_
| double ergodic_exploration::DynamicWindow::acc_lim_th_ |
|
private |
◆ acc_lim_x_
| double ergodic_exploration::DynamicWindow::acc_lim_x_ |
|
private |
◆ acc_lim_y_
| double ergodic_exploration::DynamicWindow::acc_lim_y_ |
|
private |
◆ collision_
| Collision ergodic_exploration::DynamicWindow::collision_ |
|
private |
◆ dt_
| double ergodic_exploration::DynamicWindow::dt_ |
|
private |
◆ horizon_
| double ergodic_exploration::DynamicWindow::horizon_ |
|
private |
◆ max_rot_vel_
| double ergodic_exploration::DynamicWindow::max_rot_vel_ |
|
private |
◆ max_vel_x_
| double ergodic_exploration::DynamicWindow::max_vel_x_ |
|
private |
◆ max_vel_y_
| double ergodic_exploration::DynamicWindow::max_vel_y_ |
|
private |
◆ min_rot_vel_
| double ergodic_exploration::DynamicWindow::min_rot_vel_ |
|
private |
◆ min_vel_x_
| double ergodic_exploration::DynamicWindow::min_vel_x_ |
|
private |
◆ min_vel_y_
| double ergodic_exploration::DynamicWindow::min_vel_y_ |
|
private |
◆ steps_
| unsigned int ergodic_exploration::DynamicWindow::steps_ |
|
private |
◆ vth_samples_
| unsigned int ergodic_exploration::DynamicWindow::vth_samples_ |
|
private |
◆ vx_samples_
| unsigned int ergodic_exploration::DynamicWindow::vx_samples_ |
|
private |
◆ vy_samples_
| unsigned int ergodic_exploration::DynamicWindow::vy_samples_ |
|
private |
The documentation for this class was generated from the following files: