|
| bool | ergodic_exploration::almost_equal (double d1, double d2, double epsilon=1.0e-12) |
| | approximately compare two floating-point numbers More...
|
| |
| nav_msgs::Path | ergodic_exploration::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 | ergodic_exploration::distance (double x0, double y0, double x1, double y1) |
| | Euclidean distance between two points. More...
|
| |
| double | ergodic_exploration::entropy (double p) |
| | Entropy of a single grid cell. More...
|
| |
| double | ergodic_exploration::getYaw (double qx, double qy, double qz, double qw) |
| | Get yaw from quaternion. More...
|
| |
| vec | ergodic_exploration::integrate_twist (const vec &x, const vec &u, double dt) |
| | Integrate a constant twist. More...
|
| |
| double | ergodic_exploration::normalize_angle_2PI (double rad) |
| | Wraps angle between 0 and 2pi or 0 to -2pi. More...
|
| |
| double | ergodic_exploration::normalize_angle_PI (double rad) |
| | Wraps angle between -pi and pi. More...
|
| |
| vec | ergodic_exploration::polar2Cartesian (double angle, double range) |
| | Convert polar to cartesian coordinates. More...
|
| |
| vec | ergodic_exploration::polar2CartesianHomo (double angle, double range) |
| | Convert polar to cartesian homogenous coordinates. More...
|
| |
| mat | ergodic_exploration::transform2d (double angle) |
| | Construct 2D transformation. More...
|
| |
| mat | ergodic_exploration::transform2d (double x, double y) |
| | Construct 2D transformation matrix. More...
|
| |
| mat | ergodic_exploration::transform2d (double x, double y, double angle) |
| | Construct 2D transformation matrix. More...
|
| |
| mat | ergodic_exploration::transform2dInv (const mat &trans2d) |
| | Construct 2D transformation inverse. More...
|
| |
| bool | ergodic_exploration::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...
|
| |
Useful numerical utilities.
- Author
- Boston Cleek
- Date
- 30 Oct 2020
Definition in file numerics.hpp.