CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Blimp/Fins.cpp
Views: 1798
1
#include "Blimp.h"
2
3
#include <SRV_Channel/SRV_Channel.h>
4
5
// This is the scale used for RC inputs so that they can be scaled to the float point values used in the sine wave code.
6
#define FIN_SCALE_MAX 1000
7
8
/*
9
2nd group of parameters
10
*/
11
const AP_Param::GroupInfo Fins::var_info[] = {
12
13
// @Param: FREQ_HZ
14
// @DisplayName: Fins frequency
15
// @Description: This is the oscillation frequency of the fins
16
// @Range: 1 10
17
// @User: Standard
18
AP_GROUPINFO("FREQ_HZ", 1, Fins, freq_hz, 3),
19
20
// @Param: TURBO_MODE
21
// @DisplayName: Enable turbo mode
22
// @Description: Enables double speed on high offset.
23
// @Range: 0 1
24
// @User: Standard
25
AP_GROUPINFO("TURBO_MODE", 2, Fins, turbo_mode, 0),
26
27
AP_GROUPEND
28
};
29
30
//constructor
31
Fins::Fins(uint16_t loop_rate) :
32
_loop_rate(loop_rate)
33
{
34
AP_Param::setup_object_defaults(this, var_info);
35
}
36
37
void Fins::setup_fins()
38
{
39
//fin # r f d y, r f d y right, front, down, yaw for amplitude then for offset
40
add_fin(0, 0, 1, 0.5, 0, 0, 0, 0.5, 0); //Back
41
add_fin(1, 0, -1, 0.5, 0, 0, 0, 0.5, 0); //Front
42
add_fin(2, -1, 0, 0, 0.5, 0, 0, 0, 0.5); //Right
43
add_fin(3, 1, 0, 0, 0.5, 0, 0, 0, -0.5); //Left
44
45
SRV_Channels::set_angle(SRV_Channel::k_motor1, FIN_SCALE_MAX);
46
SRV_Channels::set_angle(SRV_Channel::k_motor2, FIN_SCALE_MAX);
47
SRV_Channels::set_angle(SRV_Channel::k_motor3, FIN_SCALE_MAX);
48
SRV_Channels::set_angle(SRV_Channel::k_motor4, FIN_SCALE_MAX);
49
}
50
51
void Fins::add_fin(int8_t fin_num, float right_amp_fac, float front_amp_fac, float down_amp_fac, float yaw_amp_fac,
52
float right_off_fac, float front_off_fac, float down_off_fac, float yaw_off_fac)
53
{
54
55
// ensure valid fin number is provided
56
if (fin_num >= 0 && fin_num < NUM_FINS) {
57
58
// set amplitude factors
59
_right_amp_factor[fin_num] = right_amp_fac;
60
_front_amp_factor[fin_num] = front_amp_fac;
61
_down_amp_factor[fin_num] = down_amp_fac;
62
_yaw_amp_factor[fin_num] = yaw_amp_fac;
63
64
// set offset factors
65
_right_off_factor[fin_num] = right_off_fac;
66
_front_off_factor[fin_num] = front_off_fac;
67
_down_off_factor[fin_num] = down_off_fac;
68
_yaw_off_factor[fin_num] = yaw_off_fac;
69
}
70
}
71
72
//B,F,R,L = 0,1,2,3
73
void Fins::output()
74
{
75
if (!_armed) {
76
// set everything to zero so fins stop moving
77
right_out = 0;
78
front_out = 0;
79
down_out = 0;
80
yaw_out = 0;
81
}
82
83
#if HAL_LOGGING_ENABLED
84
blimp.Write_FINI(right_out, front_out, down_out, yaw_out);
85
#endif
86
87
//Constrain after logging so as to still show when sub-optimal tuning is causing massive overshoots.
88
right_out = constrain_float(right_out, -1, 1);
89
front_out = constrain_float(front_out, -1, 1);
90
down_out = constrain_float(down_out, -1, 1);
91
yaw_out = constrain_float(yaw_out, -1, 1);
92
93
_time = AP_HAL::micros() * 1.0e-6;
94
95
for (int8_t i=0; i<NUM_FINS; i++) {
96
_amp[i] = fmaxf(0,_right_amp_factor[i]*right_out) + fmaxf(0,_front_amp_factor[i]*front_out) +
97
fabsf(_down_amp_factor[i]*down_out) + fabsf(_yaw_amp_factor[i]*yaw_out);
98
_off[i] = _right_off_factor[i]*right_out + _front_off_factor[i]*front_out +
99
_down_off_factor[i]*down_out + _yaw_off_factor[i]*yaw_out;
100
_freq[i] = 1;
101
102
_num_added = 0;
103
if (fmaxf(0,_right_amp_factor[i]*right_out) > 0.0f) {
104
_num_added++;
105
}
106
if (fmaxf(0,_front_amp_factor[i]*front_out) > 0.0f) {
107
_num_added++;
108
}
109
if (fabsf(_down_amp_factor[i]*down_out) > 0.0f) {
110
_num_added++;
111
}
112
if (fabsf(_yaw_amp_factor[i]*yaw_out) > 0.0f) {
113
_num_added++;
114
}
115
116
if (_num_added > 0) {
117
_off[i] = _off[i]/_num_added; //average the offsets
118
}
119
120
if ((_amp[i]+fabsf(_off[i])) > 1) {
121
_amp[i] = 1 - fabsf(_off[i]);
122
}
123
124
if (turbo_mode) {
125
//double speed fins if offset at max...
126
if (_amp[i] <= 0.6 && fabsf(_off[i]) >= 0.4) {
127
_freq[i] = 2;
128
}
129
}
130
// finding and outputting current position for each servo from sine wave
131
_pos[i]= _amp[i]*cosf(freq_hz * _freq[i] * _time * 2 * M_PI) + _off[i];
132
SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), _pos[i] * FIN_SCALE_MAX);
133
}
134
135
#if HAL_LOGGING_ENABLED
136
blimp.Write_FINO(_amp, _off);
137
#endif
138
}
139
140
void Fins::output_min()
141
{
142
right_out = 0;
143
front_out = 0;
144
down_out = 0;
145
yaw_out = 0;
146
Fins::output();
147
}
148
149