19 void FarmNodelet::init_anchors(
AlgaeLine &line,
unsigned int i)
21 line.
anchor1[0] = i * offset_lines_;
23 line.
anchor1[2] = -depth_water_;
25 line.
anchor2[0] = i * offset_lines_;
26 line.
anchor2[1] = length_lines_;
27 line.
anchor2[2] = -depth_water_;
36 float l = depth_water_;
37 float h = l - depth_lines_;
38 float L = length_lines_;
42 float phi = phi_lines_;
43 float theta = theta_lines_;
45 if (randomise_lines_) {
46 phi += rand_uniform(-bnd_phi_lines_, bnd_phi_lines_);
47 theta += rand_uniform(-bnd_theta_lines_, bnd_theta_lines_);
50 float x1 = l * sin(theta) * cos(phi);
51 float y1 = l * sin(theta) * sin(phi);
52 float z1 = l * cos(theta);
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)));
61 gamma = copysign(gamma, y1);
63 gamma += rand_uniform(-bnd_gamma_lines_, bnd_gamma_lines_);
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);
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));
79 x1 = h * sin(theta) * cos(phi);
80 y1 = h * sin(theta) * sin(phi);
82 x2 = -h * ( sa*(expr) - ca*sgcd);
83 y2 = -h * (-ca*(expr) - sa*sgcd);
84 z2 = h * (cos(beta)*cgcd - sin(beta)*sin(delta));
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;
98 perlin_.configure(height_disease_heatmap_, width_disease_heatmap_,
99 height_grid_heatmap_, width_grid_heatmap_, random_seed_);
100 perlin_.randomise_gradients();
103 for (
unsigned int k = 1; k <= nbr_algae_; k++) {
104 if (!rand_bernoulli(alga_miss_rate_)) {
108 alga.
position = X1 + float(k)/(n+1) * (X2 - X1);
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_));
116 alga.
length = length_algae_;
117 alga.
width = width_algae_;
122 height_disease_heatmap_,
123 vector<float>(width_disease_heatmap_, 0)
126 perlin_.generate(random_seed_);
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);
136 line.
algae.emplace_back(alga);
tf2::Vector3 position
Position of the alga on the line.
Declaration of 2D perlin noise generator.
Rope floating_rope
Rope on wich the buoys are.
float thickness_ropes
Thickness of each rope.
Declaration of common structures and functions for farm simulator.
float anchors_diameter
Anchors diameter.
tf2::Vector3 anchor1
First anchor.
tf2::Vector3 anchor2
Second anchor.
std::vector< Alga > algae
List of algae hanging on the line.
std::vector< std::vector< float > > disease_heatmap
Heatmap representing disease across the alga.
float width
Width of the alga.
Declaration of nodelet for managing the farm simulation.
tf2::Vector3 p1
Position of the first extremity of the rope.
tf2::Vector3 p2
Position of the second extremity of the rope.
Rope line
Rope on wich the algae grow.
float length
Length of the alga.
float anchors_height
Anchors height.
Line on which algae grow.
float orientation
Orientation of the alga.