2D collision detection
More...
#include <collision.hpp>
2D collision detection
Definition at line 85 of file collision.hpp.
◆ Collision()
ergodic_exploration::Collision::Collision |
( |
double |
boundary_radius, |
|
|
double |
search_radius, |
|
|
double |
obstacle_threshold, |
|
|
double |
occupied_threshold |
|
) |
| |
Constructor.
- Parameters
-
boundary_radius | - collision boundary around robot represented as a circle |
search_radius | - radius outside of collision boundary to search for obstacles |
obstacle_threshold | - distance from boundary radius to obstacle to be considered a collision |
occupied_threshold | - min probaility [0 1] for a cell to be considered an obstacle |
Definition at line 46 of file collision.cpp.
◆ bresenhamCircle()
bool ergodic_exploration::Collision::bresenhamCircle |
( |
CollisionConfig & |
cfg, |
|
|
const GridMap & |
grid, |
|
|
int |
r |
|
) |
| const |
|
private |
Bresenham's circle algorithm.
- Parameters
-
cfg[out] | - collision configuration |
grid | - grid map |
r | - radius of circle |
- Returns
- true if there is a collision
Perfroms Bresenham's circle algorithm to detect obstacle cells
Definition at line 166 of file collision.cpp.
◆ checkCell()
bool ergodic_exploration::Collision::checkCell |
( |
CollisionConfig & |
cfg, |
|
|
const GridMap & |
grid, |
|
|
unsigned int |
cj, |
|
|
unsigned int |
ci |
|
) |
| const |
|
private |
Check if cell is an obstacle.
- Parameters
-
cfg[out] | - collision configuration |
grid | - grid map |
cj | - x-coordinate (jth column) of cell on perimeter of circle |
ci | - y-coordinate (ith row) of cell on perimeter of circle |
- Returns
- true if there is a collision
Definition at line 216 of file collision.cpp.
◆ collisionCheck()
bool ergodic_exploration::Collision::collisionCheck |
( |
const GridMap & |
grid, |
|
|
const vec & |
pose |
|
) |
| const |
Check if the given state is a collision.
- Parameters
-
grid | - grid map |
pose | - robot state [x, y, theta] |
- Returns
- true if collision
Definition at line 126 of file collision.cpp.
◆ minDirection()
tuple< CollisionMsg, vec > ergodic_exploration::Collision::minDirection |
( |
const GridMap & |
grid, |
|
|
const vec & |
pose |
|
) |
| const |
Compose displacement vector from closest obstacle to robot.
- Parameters
-
grid | - grid map |
pose | - robot state [x, y, theta] |
- Returns
- state of collision detector and vector from closest obstacle
if collision distance to vector is all zeros and if there are no obstacles the vector contains the max numerical value for a double
Definition at line 95 of file collision.cpp.
◆ minDistance()
tuple< CollisionMsg, double > ergodic_exploration::Collision::minDistance |
( |
const GridMap & |
grid, |
|
|
const vec & |
pose |
|
) |
| const |
Compose distance to closest obstacle.
- Parameters
-
grid | - grid map |
pose | - robot state [x, y, theta] |
- Returns
- state of collision detector and distance to closest obstacle
if collision distance to obstacle is zero and if there are no obstacles distance is max numerical value for a double
Definition at line 65 of file collision.cpp.
◆ search()
Find occupied cells between collision boundary and max search radius.
- Parameters
-
cfg[out] | - collision configuration |
grid | - grid map |
- Returns
- true if there is a collision
Definition at line 148 of file collision.cpp.
◆ totalPadding()
double ergodic_exploration::Collision::totalPadding |
( |
| ) |
const |
Return the distance from robot center to collision boundary.
Definition at line 143 of file collision.cpp.
◆ boundary_radius_
double ergodic_exploration::Collision::boundary_radius_ |
|
private |
◆ obstacle_threshold_
double ergodic_exploration::Collision::obstacle_threshold_ |
|
private |
◆ occupied_threshold_
double ergodic_exploration::Collision::occupied_threshold_ |
|
private |
◆ search_radius_
double ergodic_exploration::Collision::search_radius_ |
|
private |
The documentation for this class was generated from the following files: