Public Member Functions | Private Member Functions | Private Attributes | List of all members
uav_random_direction Class Reference

A class that allows to cover a given area with the random direction algorithm. The random direction is a mathematical movement model, where an agent moves straight forward until it reaches an obstacle. There, it changes its direction randomly. More...

#include <uav_random_direction.h>

Public Member Functions

behavior_state_t step ()
 Move the swarm member to a new position. More...
 
void stop ()
 Stop moving. More...
 
 uav_random_direction (double altitude)
 Constructor that initializes the private member variables. More...
 
 ~uav_random_direction ()
 Destructor that deletes the private member objects. More...
 

Private Member Functions

bool new_direction ()
 Compute new direction using rng. More...
 
bool select_goal ()
 Compute goal position from direction. More...
 

Private Attributes

ServiceClient area_client
 Service client to get the area polygon. More...
 
ServiceClient clear_sector_client
 Service client for determining the sector clear of obstacles. More...
 
double direction
 The direction in which the drone is travling. It is measured in radian, clockwise starting from north. More...
 
geometry_msgs::Pose goal
 The current goal. More...
 
double margin
 The distance in meter to keep to the environment boundary. More...
 
position pos
 A helper object for position related tasks. More...
 
random_numbers::RandomNumberGeneratorrng
 The random number generator used for selecting a random direction. More...
 

Detailed Description

A class that allows to cover a given area with the random direction algorithm. The random direction is a mathematical movement model, where an agent moves straight forward until it reaches an obstacle. There, it changes its direction randomly.

Definition at line 24 of file uav_random_direction.h.

Constructor & Destructor Documentation

uav_random_direction::uav_random_direction ( double  altitude)

Constructor that initializes the private member variables.

Parameters
altitudeThe altitude at which the CPS operates.

Definition at line 3 of file lib/uav_random_direction.cpp.

uav_random_direction::~uav_random_direction ( )

Destructor that deletes the private member objects.

Definition at line 36 of file lib/uav_random_direction.cpp.

Member Function Documentation

bool uav_random_direction::new_direction ( )
private

Compute new direction using rng.

Returns
Whether a a new direction could be set successfully.

Definition at line 120 of file lib/uav_random_direction.cpp.

bool uav_random_direction::select_goal ( )
private

Compute goal position from direction.

Returns
Whether the goal could be computed successfully.

Definition at line 75 of file lib/uav_random_direction.cpp.

behavior_state_t uav_random_direction::step ( )

Move the swarm member to a new position.

Returns
Return the state of the coverage algorithm.

Definition at line 41 of file lib/uav_random_direction.cpp.

void uav_random_direction::stop ( )

Stop moving.

Definition at line 70 of file lib/uav_random_direction.cpp.

Member Data Documentation

ServiceClient uav_random_direction::area_client
private

Service client to get the area polygon.

Definition at line 65 of file uav_random_direction.h.

ServiceClient uav_random_direction::clear_sector_client
private

Service client for determining the sector clear of obstacles.

Definition at line 70 of file uav_random_direction.h.

double uav_random_direction::direction
private

The direction in which the drone is travling. It is measured in radian, clockwise starting from north.

Definition at line 80 of file uav_random_direction.h.

geometry_msgs::Pose uav_random_direction::goal
private

The current goal.

Definition at line 85 of file uav_random_direction.h.

double uav_random_direction::margin
private

The distance in meter to keep to the environment boundary.

Definition at line 95 of file uav_random_direction.h.

position uav_random_direction::pos
private

A helper object for position related tasks.

Definition at line 75 of file uav_random_direction.h.

random_numbers::RandomNumberGenerator* uav_random_direction::rng
private

The random number generator used for selecting a random direction.

Definition at line 90 of file uav_random_direction.h.


The documentation for this class was generated from the following files:


uav_random_direction
Author(s): Micha Sende
autogenerated on Sat Feb 6 2021 03:11:41