Namespaces | |
| models | |
Classes | |
| class | Basis |
| Fourier cosine basis. More... | |
| class | Collision |
| 2D collision detection More... | |
| struct | CollisionConfig |
| Collision detection parameters. More... | |
| class | DynamicWindow |
| Dynamic window approach. More... | |
| class | ErgodicControl |
| Receding horizon ergodic trajectory optimization. More... | |
| class | Exploration |
| Exploration template. More... | |
| struct | Gaussian |
| 2D gaussian More... | |
| class | GridMap |
| Constructs an 2D grid. More... | |
| class | OccupancyMapper |
| Occupancy grid mapping. More... | |
| class | ReplayBuffer |
| Store and smaple past states. More... | |
| class | RungeKutta |
| 4th order Runge-Kutta integration More... | |
| class | RungeKutta45 |
| class | Target |
| Target distribution. More... | |
Typedefs | |
| typedef std::function< vec(const vec &, const vec &, const vec &, const mat &)> | CoStateFunc |
| Function representing the time derivatve of the co-state variable. More... | |
| typedef std::vector< Gaussian > | GaussianList |
| typedef std::vector< int8_t > | GridData |
| Occupancy grid data. More... | |
Enumerations | |
| enum | CollisionMsg { CollisionMsg::crash, CollisionMsg::obstacle, CollisionMsg::none } |
| State of the collision detector. More... | |
Functions | |
| bool | almost_equal (double d1, double d2, double epsilon=1.0e-12) |
| approximately compare two floating-point numbers More... | |
| unsigned int | axis_length (double lower, double upper, double resolution) |
| Length of a grid axis. More... | |
| double | axis_upper (double lower, double resolution, unsigned int size) |
| Upper axis limit. More... | |
| nav_msgs::Path | constTwistPath (const std::string &map_frame_id, const vec &x0, const vec &u, double dt, double horizon) |
| Visualize path from following a constant twist. More... | |
| double | distance (double x0, double y0, double x1, double y1) |
| Euclidean distance between two points. More... | |
| double | entropy (double p) |
| Entropy of a single grid cell. More... | |
| double | getYaw (double qx, double qy, double qz, double qw) |
| Get yaw from quaternion. More... | |
| vec | integrate_twist (const vec &x, const vec &u, double dt) |
| Integrate a constant twist. More... | |
| double | logOdds2Prob (double l) |
| Convert log odds to a probability. More... | |
| double | normalize_angle_2PI (double rad) |
| Wraps angle between 0 and 2pi or 0 to -2pi. More... | |
| double | normalize_angle_PI (double rad) |
| Wraps angle between -pi and pi. More... | |
| vec | polar2Cartesian (double angle, double range) |
| Convert polar to cartesian coordinates. More... | |
| vec | polar2CartesianHomo (double angle, double range) |
| Convert polar to cartesian homogenous coordinates. More... | |
| double | prob2LogOdds (double p) |
| Convert probability to log odds. More... | |
| vec | rhodot (const vec &rho, const vec &gdx, const vec &dbar, const mat &fdx) |
| Time derivatve of the co-state variable. More... | |
| mat | transform2d (double angle) |
| Construct 2D transformation. More... | |
| mat | transform2d (double x, double y) |
| Construct 2D transformation matrix. More... | |
| mat | transform2d (double x, double y, double angle) |
| Construct 2D transformation matrix. More... | |
| mat | transform2dInv (const mat &trans2d) |
| Construct 2D transformation inverse. More... | |
| bool | validate_control (const Collision &collision, const GridMap &grid, const vec &x0, const vec &u, double dt, double horizon) |
| Determine if control will cause a collision. More... | |
Variables | |
| constexpr char | LOGNAME [] = "ergodic exploration" |
| constexpr double | PI = 3.14159265358979323846 |
| typedef std::function<vec(const vec&, const vec&, const vec&, const mat&)> ergodic_exploration::CoStateFunc |
Function representing the time derivatve of the co-state variable.
inputs are co-state, ergodic measure derivatve, barrier derivatve, and the jacobian of the dynamics w.r.t state
Definition at line 60 of file integrator.hpp.
| typedef std::vector<Gaussian> ergodic_exploration::GaussianList |
Definition at line 52 of file target.hpp.
| typedef std::vector<int8_t> ergodic_exploration::GridData |
|
strong |
State of the collision detector.
| Enumerator | |
|---|---|
| crash | |
| obstacle | |
| none | |
Definition at line 55 of file collision.hpp.
|
inline |
approximately compare two floating-point numbers
| d1 | - a number to compare |
| d2 | - a second number to compare |
| epsilon | - absolute threshold required for equality |
Definition at line 67 of file numerics.hpp.
|
inline |
|
inline |
|
inline |
Visualize path from following a constant twist.
| x0 | - current state |
| u | - twist [vx, vy, w] |
| dt | - time step |
| horizon | - control horizon |
Definition at line 340 of file numerics.hpp.
|
inline |
Euclidean distance between two points.
| x0 | - x-position point 0 |
| y0 | - y-position point 0 |
| x1 | - x-position point 1 |
| y1 | - y-position point 1 |
Definition at line 152 of file numerics.hpp.
|
inline |
Entropy of a single grid cell.
| p | - probability grid cell is occupied represented as a decimal |
Definition at line 164 of file numerics.hpp.
|
inline |
Get yaw from quaternion.
| qx | - x-axis rotation component |
| qy | - y-axis rotation component |
| qz | - z-axis rotation component |
| qw | - rotation magnitude |
Definition at line 118 of file numerics.hpp.
|
inline |
Integrate a constant twist.
| x | - current state [x, y, theta] |
| vb | - current twist [vx, vy, w] |
| dt | - time step |
Definition at line 273 of file numerics.hpp.
| double ergodic_exploration::logOdds2Prob | ( | double | l | ) |
Convert log odds to a probability.
| l | - log odds |
Definition at line 51 of file mapping.cpp.
|
inline |
Wraps angle between 0 and 2pi or 0 to -2pi.
| rad | - angle in radians |
Definition at line 96 of file numerics.hpp.
|
inline |
Wraps angle between -pi and pi.
| rad | - angle in radians |
Definition at line 77 of file numerics.hpp.
|
inline |
Convert polar to cartesian coordinates.
| angle | - angle in radians |
| range | - range measurement |
Definition at line 186 of file numerics.hpp.
|
inline |
Convert polar to cartesian homogenous coordinates.
| angle | - angle in radians |
| range | - range measurement |
Definition at line 198 of file numerics.hpp.
| double ergodic_exploration::prob2LogOdds | ( | double | p | ) |
Convert probability to log odds.
| p | - probability |
Definition at line 61 of file mapping.cpp.
|
inline |
Time derivatve of the co-state variable.
| rho | - co-state variable |
| gdx | - gradient of the ergodic metric |
| dbar | - derivatve of barrier function |
| fdx | - jacobian of the dynamics w.r.t state A = D1(f(x,u)) |
Definition at line 65 of file ergodic_control.hpp.
|
inline |
Construct 2D transformation.
| angle | - yaw in radians |
2D transformation
Definition at line 239 of file numerics.hpp.
|
inline |
Construct 2D transformation matrix.
| x | - x position |
| y | - y position |
2D transformation
Definition at line 227 of file numerics.hpp.
|
inline |
Construct 2D transformation matrix.
| x | - x position |
| y | - y position |
| angle | - yaw in radians |
2D transformation
Definition at line 212 of file numerics.hpp.
|
inline |
Construct 2D transformation inverse.
| trans2d | - 2D transformation |
2D transformation inverse
Definition at line 252 of file numerics.hpp.
|
inline |
Determine if control will cause a collision.
| collision | - collision detector |
| grid | - grid map |
| x0 | - initial state |
| u | - twist [vx, vy, w] |
| dt | - time step in integration |
| horizon | - length of integration |
The control is assumed to be constant and a twist is integrated for a fixed amout of time
Definition at line 312 of file numerics.hpp.
|
constexpr |
Definition at line 57 of file exploration.hpp.
|
constexpr |
Definition at line 58 of file numerics.hpp.