A class that allows to cover a given area optimally with a swarm of cyber physical systems (CPSs). The area is divided among the CPSs and each CPS covers its part by simple back and forth (boustrophedon) motion. More...
#include <uav_optimal_coverage.h>
Public Member Functions | |
behavior_state_t | step () |
Move the swarm member to a new position. More... | |
void | stop () |
Stop moving. More... | |
uav_optimal_coverage (double altitude) | |
Constructor that initializes the private member variables. More... | |
~uav_optimal_coverage () | |
Destructor that deletes the private member objects. More... | |
Private Attributes | |
cpswarm_msgs::GetWaypoint | get_wp |
Service message to get the current waypoint. More... | |
position | pos |
A helper object for position related tasks. More... | |
geometry_msgs::Point | waypoint |
Current waypoint to navigate to. More... | |
ServiceClient | wp_getter |
Service client to get the current waypoint to navigate to. More... | |
A class that allows to cover a given area optimally with a swarm of cyber physical systems (CPSs). The area is divided among the CPSs and each CPS covers its part by simple back and forth (boustrophedon) motion.
Definition at line 23 of file uav_optimal_coverage.h.
uav_optimal_coverage::uav_optimal_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_optimal_coverage.cpp.
uav_optimal_coverage::~uav_optimal_coverage | ( | ) |
Destructor that deletes the private member objects.
Definition at line 19 of file lib/uav_optimal_coverage.cpp.
behavior_state_t uav_optimal_coverage::step | ( | ) |
Move the swarm member to a new position.
Definition at line 23 of file lib/uav_optimal_coverage.cpp.
void uav_optimal_coverage::stop | ( | ) |
Stop moving.
Definition at line 60 of file lib/uav_optimal_coverage.cpp.
|
private |
Service message to get the current waypoint.
Definition at line 62 of file uav_optimal_coverage.h.
|
private |
A helper object for position related tasks.
Definition at line 67 of file uav_optimal_coverage.h.
|
private |
Current waypoint to navigate to.
Definition at line 57 of file uav_optimal_coverage.h.
|
private |
Service client to get the current waypoint to navigate to.
Definition at line 52 of file uav_optimal_coverage.h.