lib/uav_local_coverage.cpp
Go to the documentation of this file.
2 
3 uav_local_coverage::uav_local_coverage(double altitude) : altitude(altitude), pos(altitude)
4 {
5  // read parameters
6  NodeHandle nh;
7  nh.param(this_node::getName() + "/fov_hor", fov_hor, 1.236);
8  nh.param(this_node::getName() + "/fov_ver", fov_ver, 0.970);
9  nh.param(this_node::getName() + "/local_steps", max_steps, 20);
10 
11  // init number of search steps
12  steps = 0;
13 
14  // init local coordinate origin
15  // it is the center of the circle that defines the involute
16  double distance, direction;
17  compute_involute(distance, direction);
18  // invert direction to reach origin from current pose
19  // the current pose is the 0th step on the involute (x = radius a, y = 0)
20  direction += M_PI;
21  origin = pos.get_pose();
22 }
23 
25 {
26  // update position information
27  spinOnce();
28 
29  // next search step
30  if (pos.reached()) {
31  ++steps;
32 
33  // reached maximum number of steps, stop local coverage
34  if (steps >= max_steps) {
35  ROS_INFO("Reached maximum coverage steps!");
36  return STATE_ABORTED;
37  }
38  }
39 
40  // compute goal
41  geometry_msgs::Pose goal = select_goal();
42 
43  // move to new goal
44  if (pos.move(goal) == false)
45  return STATE_ABORTED;
46 
47  // return state to action server
48  return STATE_ACTIVE;
49 }
50 
51 void uav_local_coverage::compute_involute (double &distance, double &direction)
52 {
53  // parameters for circle involute
54  double a = altitude * tan(fov_hor / 2) / M_PI; // radius
55  double b = altitude * tan(fov_ver / 2) * 2; // step size
56 
57  // compute local coordinates using involute
58  double s = b * steps; // arc length
59  double t = sqrt(2 * s / a); // tangential angle
60  double x = a * (cos(t) + t * sin(t));
61  double y = a * (sin(t) - t * cos(t));
62 
63  // compute distance and heading from local origin
64  distance = hypot(x, y);
65  direction = atan2(y, x);
66 }
67 
68 geometry_msgs::Pose uav_local_coverage::select_goal ()
69 {
70  // compute heading and distance for current step
71  double distance, direction;
72  compute_involute(distance, direction);
73 
74  // compute gps coordinats of goal position
75  return pos.compute_goal(origin, distance, direction);
76 }
77 
79 {
80  pos.stop();
81 }
unsigned int steps
Number of steps performed in the local search.
bool move(geometry_msgs::Pose pose)
double fov_hor
Horizontal camera field of view in radian.
geometry_msgs::Pose select_goal()
Compute goal position.
bool reached()
double altitude
The altitude of the UAV above ground.
XmlRpcServer s
uav_local_coverage(double altitude)
Constructor that initializes the private member variables.
geometry_msgs::Pose get_pose() const
double fov_ver
Vertical camera field of view in radian.
behavior_state_t step()
Move the swarm member to a new position.
geometry_msgs::Pose origin
Center of the spiral movement search pattern.
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void compute_involute(double &distance, double &direction)
Compute local coordinates on circle involute for current step.
behavior_state_t
An enumeration for the state of the behavior algorithm.
geometry_msgs::Pose compute_goal(double distance, double direction) const
void stop()
Stop moving.
position pos
A helper object for position related tasks.
void stop()
ROSCPP_DECL void spinOnce()
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