An implementation of the coverage class that allows to cover a given area with the random walk algorithm. The random walk is a mathematical movement model, where an agent moves straight for a specific distance and then changes its direction randomly. More...
#include <ugv_random_walk.h>
Public Member Functions | |
| behavior_state_t | step () |
| Move the swarm member to a new position. More... | |
| void | stop () |
| Stop moving. More... | |
| ugv_random_walk () | |
| Constructor that initializes the private member variables. More... | |
| ~ugv_random_walk () | |
| Destructor that deletes the private member objects. More... | |
Private Member Functions | |
| bool | new_direction () |
| Compute new direction using rng. More... | |
| bool | reflect () |
| Compute new direction as reflection from wall. More... | |
| geometry_msgs::Pose | select_goal () |
| Compute goal position from direction. More... | |
Private Attributes | |
| ServiceClient | bound_client |
| Service client for determining closest mission area boundary to the current UGV position. More... | |
| ServiceClient | clear_sector_client |
| Service client for determining the sector clear of obstacles. More... | |
| double | direction |
| The direction in which the UGV is traveling. It is measured in radian, clockwise starting from north. More... | |
| position | pos |
| A helper object for position related tasks. More... | |
| random_numbers::RandomNumberGenerator * | rng |
| The random number generator used for selecting a random direction. More... | |
| double | step_size |
| The distance that the UGV travels in one step. More... | |
An implementation of the coverage class that allows to cover a given area with the random walk algorithm. The random walk is a mathematical movement model, where an agent moves straight for a specific distance and then changes its direction randomly.
Definition at line 24 of file ugv_random_walk.h.
| ugv_random_walk::ugv_random_walk | ( | ) |
Constructor that initializes the private member variables.
Definition at line 3 of file lib/ugv_random_walk.cpp.
| ugv_random_walk::~ugv_random_walk | ( | ) |
Destructor that deletes the private member objects.
Definition at line 34 of file lib/ugv_random_walk.cpp.
|
private |
Compute new direction using rng.
Definition at line 71 of file lib/ugv_random_walk.cpp.
|
private |
Compute new direction as reflection from wall.
Definition at line 95 of file lib/ugv_random_walk.cpp.
|
private |
Compute goal position from direction.
Definition at line 119 of file lib/ugv_random_walk.cpp.
| behavior_state_t ugv_random_walk::step | ( | ) |
Move the swarm member to a new position.
Definition at line 39 of file lib/ugv_random_walk.cpp.
| void ugv_random_walk::stop | ( | ) |
Stop moving.
Definition at line 66 of file lib/ugv_random_walk.cpp.
|
private |
Service client for determining closest mission area boundary to the current UGV position.
Definition at line 70 of file ugv_random_walk.h.
|
private |
Service client for determining the sector clear of obstacles.
Definition at line 75 of file ugv_random_walk.h.
|
private |
The direction in which the UGV is traveling. It is measured in radian, clockwise starting from north.
Definition at line 90 of file ugv_random_walk.h.
|
private |
A helper object for position related tasks.
Definition at line 80 of file ugv_random_walk.h.
|
private |
The random number generator used for selecting a random direction.
Definition at line 95 of file ugv_random_walk.h.
|
private |
The distance that the UGV travels in one step.
Definition at line 85 of file ugv_random_walk.h.