A class that allows to cover a given area using a local search algorithm. The local search performs a spiral movement pattern according to the circle involute (http://mathworld.wolfram.com/CircleInvolute.html). More...
#include <uav_local_coverage.h>
Public Member Functions | |
| behavior_state_t | step () |
| Move the swarm member to a new position. More... | |
| void | stop () |
| Stop moving. More... | |
| uav_local_coverage (double altitude) | |
| Constructor that initializes the private member variables. More... | |
Private Member Functions | |
| void | compute_involute (double &distance, double &direction) |
| Compute local coordinates on circle involute for current step. More... | |
| geometry_msgs::Pose | select_goal () |
| Compute goal position. More... | |
Private Attributes | |
| double | altitude |
| The altitude of the UAV above ground. More... | |
| double | fov_hor |
| Horizontal camera field of view in radian. More... | |
| double | fov_ver |
| Vertical camera field of view in radian. More... | |
| int | max_steps |
| Maximum number of steps to do in the local search. More... | |
| geometry_msgs::Pose | origin |
| Center of the spiral movement search pattern. More... | |
| position | pos |
| A helper object for position related tasks. More... | |
| unsigned int | steps |
| Number of steps performed in the local search. More... | |
A class that allows to cover a given area using a local search algorithm. The local search performs a spiral movement pattern according to the circle involute (http://mathworld.wolfram.com/CircleInvolute.html).
Definition at line 21 of file uav_local_coverage.h.
| uav_local_coverage::uav_local_coverage | ( | double | altitude | ) |
Constructor that initializes the private member variables.
| altitude | The altitude at which the CPS operates. |
Definition at line 3 of file lib/uav_local_coverage.cpp.
|
private |
Compute local coordinates on circle involute for current step.
| distance | Returns distance from local origin. |
| direction | Returns direction from local origin. |
Definition at line 51 of file lib/uav_local_coverage.cpp.
|
private |
Compute goal position.
Definition at line 68 of file lib/uav_local_coverage.cpp.
| behavior_state_t uav_local_coverage::step | ( | ) |
Move the swarm member to a new position.
Definition at line 24 of file lib/uav_local_coverage.cpp.
| void uav_local_coverage::stop | ( | ) |
Stop moving.
Definition at line 78 of file lib/uav_local_coverage.cpp.
|
private |
The altitude of the UAV above ground.
Definition at line 63 of file uav_local_coverage.h.
|
private |
Horizontal camera field of view in radian.
Definition at line 68 of file uav_local_coverage.h.
|
private |
Vertical camera field of view in radian.
Definition at line 73 of file uav_local_coverage.h.
|
private |
Maximum number of steps to do in the local search.
Definition at line 88 of file uav_local_coverage.h.
|
private |
Center of the spiral movement search pattern.
Definition at line 78 of file uav_local_coverage.h.
|
private |
A helper object for position related tasks.
Definition at line 58 of file uav_local_coverage.h.
|
private |
Number of steps performed in the local search.
Definition at line 83 of file uav_local_coverage.h.