Corentin Chauvin-Hameau – 2019-2020
Coverage Path Planning for an underwater robot surveying a marine farm
farm_initialisation.cpp
Go to the documentation of this file.
1 /**
2  * @file
3  *
4  * \brief Implementation of functions for initialising a farm
5  * \author Corentin Chauvin-Hameau
6  * \date 2019
7  */
8 
9 #include "farm_nodelet.hpp"
10 #include "farm_common.hpp"
12 #include <vector>
13 
14 using namespace std;
15 
16 
17 namespace mfcpp {
18 
19 void FarmNodelet::init_anchors(AlgaeLine &line, unsigned int i)
20 {
21  line.anchor1[0] = i * offset_lines_;
22  line.anchor1[1] = 0;
23  line.anchor1[2] = -depth_water_;
24 
25  line.anchor2[0] = i * offset_lines_;
26  line.anchor2[1] = length_lines_;
27  line.anchor2[2] = -depth_water_;
28 
29  line.anchors_diameter = anchors_diameter_;
30  line.anchors_height = anchors_height_;
31 }
32 
33 
34 void FarmNodelet::init_ropes(AlgaeLine &line)
35 {
36  float l = depth_water_; // distance seafloor - floating line
37  float h = l - depth_lines_; // distance seafloor - algae line
38  float L = length_lines_;
39 
40  // Initialise floating rope
41  line.thickness_ropes = thickness_ropes_;
42  float phi = phi_lines_;
43  float theta = theta_lines_;
44 
45  if (randomise_lines_) {
46  phi += rand_uniform(-bnd_phi_lines_, bnd_phi_lines_);
47  theta += rand_uniform(-bnd_theta_lines_, bnd_theta_lines_);
48  }
49 
50  float x1 = l * sin(theta) * cos(phi);
51  float y1 = l * sin(theta) * sin(phi);
52  float z1 = l * cos(theta);
53 
54  float D2 = pow(x1, 2) + pow(L-y1, 2);
55  float d = sqrt(D2 + pow(z1, 2));
56  float alpha = atan2(x1, L - y1);
57  float beta = atan2(z1, sqrt(D2));
58  float delta = -asin((pow(d, 2) + pow(l, 2) - pow(L, 2)) / (2*d*l));
59  float gamma = -acos(1/(cos(beta)*cos(delta)) * (z1/l + sin(beta)*sin(delta)));
60 
61  gamma = copysign(gamma, y1);
62  if (randomise_lines_)
63  gamma += rand_uniform(-bnd_gamma_lines_, bnd_gamma_lines_);
64 
65  float ca = cos(alpha);
66  float sa = sin(alpha);
67  float cgcd = cos(gamma)*cos(delta);
68  float expr = sin(beta)*cgcd + cos(beta)*sin(delta);
69  float sgcd = sin(gamma)*cos(delta);
70 
71  float x2 = -l * ( sa*(expr) - ca*sgcd);
72  float y2 = -l * (-ca*(expr) - sa*sgcd);
73  float z2 = l * (cos(beta)*cgcd - sin(beta)*sin(delta));
74 
75  line.floating_rope.p1 = line.anchor1 + tf2::Vector3(x1, y1, z1);
76  line.floating_rope.p2 = line.anchor2 + tf2::Vector3(x2, y2, z2);
77 
78  // Initialise algae rope
79  x1 = h * sin(theta) * cos(phi);
80  y1 = h * sin(theta) * sin(phi);
81  z1 = h * cos(theta);
82  x2 = -h * ( sa*(expr) - ca*sgcd);
83  y2 = -h * (-ca*(expr) - sa*sgcd);
84  z2 = h * (cos(beta)*cgcd - sin(beta)*sin(delta));
85 
86  line.line.p1 = line.anchor1 + tf2::Vector3(x1, y1, z1);
87  line.line.p2 = line.anchor2 + tf2::Vector3(x2, y2, z2);
88 }
89 
90 
91 void FarmNodelet::init_algae(AlgaeLine &line)
92 {
93  line.algae.reserve(nbr_algae_);
94  unsigned int n = nbr_algae_;
95  tf2::Vector3 X1 = line.line.p1;
96  tf2::Vector3 X2 = line.line.p2;
97 
98  perlin_.configure(height_disease_heatmap_, width_disease_heatmap_,
99  height_grid_heatmap_, width_grid_heatmap_, random_seed_);
100  perlin_.randomise_gradients();
101 
102 
103  for (unsigned int k = 1; k <= nbr_algae_; k++) {
104  if (!rand_bernoulli(alga_miss_rate_)) {
105  Alga alga;
106 
107  // Initialise pose and dimensions of alga
108  alga.position = X1 + float(k)/(n+1) * (X2 - X1);
109 
110  if (randomise_algae_) {
111  alga.orientation = rand_gaussian(psi_algae_, std_psi_algae_);
112  alga.length = abs(rand_gaussian(length_algae_, std_length_algae_));
113  alga.width = abs(rand_gaussian(width_algae_, std_width_algae_));
114  } else {
115  alga.orientation = psi_algae_;
116  alga.length = length_algae_;
117  alga.width = width_algae_;
118  }
119 
120  // Initialise disease heatmap of alga
121  alga.disease_heatmap.resize(
122  height_disease_heatmap_,
123  vector<float>(width_disease_heatmap_, 0)
124  );
125 
126  perlin_.generate(random_seed_);
127 
128  for (int i = 0; i < height_disease_heatmap_; i++) {
129  for (int j = 0; j < width_disease_heatmap_; j++) {
130  float value = perlin_.evaluate(i, j);
131  alga.disease_heatmap[i][j] = disease_ratio_*value;
132  }
133  }
134 
135  // Add the alga
136  line.algae.emplace_back(alga);
137  }
138  }
139 }
140 
141 
142 
143 
144 } // namespace mfcpp
tf2::Vector3 position
Position of the alga on the line.
Definition: farm_common.hpp:40
Definition: common.hpp:23
Declaration of 2D perlin noise generator.
Rope floating_rope
Rope on wich the buoys are.
Definition: farm_common.hpp:61
float thickness_ropes
Thickness of each rope.
Definition: farm_common.hpp:64
Declaration of common structures and functions for farm simulator.
float anchors_diameter
Anchors diameter.
Definition: farm_common.hpp:65
tf2::Vector3 anchor1
First anchor.
Definition: farm_common.hpp:62
tf2::Vector3 anchor2
Second anchor.
Definition: farm_common.hpp:63
std::vector< Alga > algae
List of algae hanging on the line.
Definition: farm_common.hpp:69
std::vector< std::vector< float > > disease_heatmap
Heatmap representing disease across the alga.
Definition: farm_common.hpp:52
float width
Width of the alga.
Definition: farm_common.hpp:44
Declaration of nodelet for managing the farm simulation.
tf2::Vector3 p1
Position of the first extremity of the rope.
Definition: farm_common.hpp:25
tf2::Vector3 p2
Position of the second extremity of the rope.
Definition: farm_common.hpp:26
Rope line
Rope on wich the algae grow.
Definition: farm_common.hpp:60
float length
Length of the alga.
Definition: farm_common.hpp:43
float anchors_height
Anchors height.
Definition: farm_common.hpp:66
Line on which algae grow.
Definition: farm_common.hpp:58
Alga hanging on a line.
Definition: farm_common.hpp:32
float orientation
Orientation of the alga.
Definition: farm_common.hpp:42