uav_local_coverage.h
Go to the documentation of this file.
1 #ifndef UAV_LOCAL_COVERAGE_H
2 #define UAV_LOCAL_COVERAGE_H
3 
4 #include <position.h>
5 
6 using namespace std;
7 using namespace ros;
8 
12 typedef enum {
17 
22 {
23 public:
28  uav_local_coverage(double altitude);
29 
35 
39  void stop ();
40 
41 private:
47  void compute_involute (double &distance, double &direction);
48 
53  geometry_msgs::Pose select_goal ();
54 
59 
63  double altitude;
64 
68  double fov_hor;
69 
73  double fov_ver;
74 
78  geometry_msgs::Pose origin;
79 
83  unsigned int steps;
84 
88  int max_steps;
89 
90 
91 };
92 
93 #endif // UAV_LOCAL_COVERAGE_H
unsigned int steps
Number of steps performed in the local search.
double fov_hor
Horizontal camera field of view in radian.
double altitude
The altitude of the UAV above ground.
A class that allows to cover a given area using a local search algorithm. The local search performs a...
double fov_ver
Vertical camera field of view in radian.
geometry_msgs::Pose origin
Center of the spiral movement search pattern.
behavior_state_t
An enumeration for the state of the behavior algorithm.
position pos
A helper object for position related tasks.
unsigned int step
int max_steps
Maximum number of steps to do in the local search.


uav_local_coverage
Author(s): Micha Sende
autogenerated on Sat Feb 6 2021 03:11:37