Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Blimp/Blimp.cpp
9487 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "Blimp.h"
17
18
#define FORCE_VERSION_H_INCLUDE
19
#include "version.h"
20
#undef FORCE_VERSION_H_INCLUDE
21
22
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
23
24
#define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Blimp, &blimp, func, rate_hz, max_time_micros, priority)
25
#define FAST_TASK(func) FAST_TASK_CLASS(Blimp, &blimp, func)
26
27
/*
28
scheduler table - all tasks should be listed here.
29
30
All entries in this table must be ordered by priority.
31
32
This table is interleaved with the table in AP_Vehicle to determine
33
the order in which tasks are run. Convenience methods SCHED_TASK
34
and SCHED_TASK_CLASS are provided to build entries in this structure:
35
36
SCHED_TASK arguments:
37
- name of static function to call
38
- rate (in Hertz) at which the function should be called
39
- expected time (in MicroSeconds) that the function should take to run
40
- priority (0 through 255, lower number meaning higher priority)
41
42
SCHED_TASK_CLASS arguments:
43
- class name of method to be called
44
- instance on which to call the method
45
- method to call on that instance
46
- rate (in Hertz) at which the method should be called
47
- expected time (in MicroSeconds) that the method should take to run
48
- priority (0 through 255, lower number meaning higher priority)
49
50
*/
51
const AP_Scheduler::Task Blimp::scheduler_tasks[] = {
52
// update INS immediately to get current gyro data populated
53
FAST_TASK_CLASS(AP_InertialSensor, &blimp.ins, update),
54
// send outputs to the motors library immediately
55
FAST_TASK(motors_output),
56
// run EKF state estimator (expensive)
57
FAST_TASK(read_AHRS),
58
// Inertial Nav
59
FAST_TASK(read_inertia),
60
// check if ekf has reset target heading or position
61
FAST_TASK(check_ekf_reset),
62
// run the attitude controllers
63
FAST_TASK(update_flight_mode),
64
// update home from EKF if necessary
65
FAST_TASK(update_home_from_EKF),
66
67
SCHED_TASK(rc_loop, 100, 130, 3),
68
SCHED_TASK(throttle_loop, 50, 75, 6),
69
SCHED_TASK_CLASS(AP_GPS, &blimp.gps, update, 50, 200, 9),
70
SCHED_TASK(update_batt_compass, 10, 120, 12),
71
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&blimp.g2.rc_channels, read_aux_all, 10, 50, 15),
72
SCHED_TASK(update_altitude, 10, 100, 21),
73
SCHED_TASK(three_hz_loop, 3, 75, 24),
74
#if AP_SERVORELAYEVENTS_ENABLED
75
SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27),
76
#endif
77
#if HAL_LOGGING_ENABLED
78
SCHED_TASK(full_rate_logging, 50, 50, 33),
79
#endif
80
SCHED_TASK_CLASS(AP_Notify, &blimp.notify, update, 50, 90, 36),
81
SCHED_TASK(one_hz_loop, 1, 100, 39),
82
SCHED_TASK(ekf_check, 10, 75, 42),
83
SCHED_TASK(check_vibration, 10, 50, 45),
84
SCHED_TASK(gpsglitch_check, 10, 50, 48),
85
SCHED_TASK_CLASS(GCS, (GCS*)&blimp._gcs, update_receive, 400, 180, 51),
86
SCHED_TASK_CLASS(GCS, (GCS*)&blimp._gcs, update_send, 400, 550, 54),
87
#if HAL_LOGGING_ENABLED
88
SCHED_TASK(ten_hz_logging_loop, 10, 350, 57),
89
SCHED_TASK(twentyfive_hz_logging, 25, 110, 60),
90
SCHED_TASK_CLASS(AP_Logger, &blimp.logger, periodic_tasks, 400, 300, 63),
91
#endif
92
SCHED_TASK_CLASS(AP_InertialSensor, &blimp.ins, periodic, 400, 50, 66),
93
#if HAL_LOGGING_ENABLED
94
SCHED_TASK_CLASS(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75, 69),
95
#endif
96
};
97
98
void Blimp::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
99
uint8_t &task_count,
100
uint32_t &log_bit)
101
{
102
tasks = &scheduler_tasks[0];
103
task_count = ARRAY_SIZE(scheduler_tasks);
104
log_bit = MASK_LOG_PM;
105
}
106
107
constexpr int8_t Blimp::_failsafe_priorities[4];
108
109
// rc_loops - reads user input from transmitter/receiver
110
// called at 100hz
111
void Blimp::rc_loop()
112
{
113
// Read radio and 3-position switch on radio
114
// -----------------------------------------
115
read_radio();
116
rc().read_mode_switch();
117
}
118
119
// throttle_loop - should be run at 50 hz
120
// ---------------------------
121
void Blimp::throttle_loop()
122
{
123
// check auto_armed status
124
update_auto_armed();
125
}
126
127
// update_batt_compass - read battery and compass
128
// should be called at 10hz
129
void Blimp::update_batt_compass(void)
130
{
131
// read battery before compass because it may be used for motor interference compensation
132
battery.read();
133
134
if (AP::compass().available()) {
135
// update compass with throttle value - used for compassmot
136
compass.set_voltage(battery.voltage());
137
compass.read();
138
}
139
}
140
141
#if HAL_LOGGING_ENABLED
142
// Full rate logging of attitude, rate and pid loops
143
void Blimp::full_rate_logging()
144
{
145
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
146
Log_Write_Attitude();
147
}
148
if (should_log(MASK_LOG_PID)) {
149
Log_Write_PIDs();
150
}
151
}
152
153
// ten_hz_logging_loop
154
// should be run at 10hz
155
void Blimp::ten_hz_logging_loop()
156
{
157
// log attitude data if we're not already logging at the higher rate
158
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
159
Log_Write_Attitude();
160
}
161
// log EKF attitude data
162
if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) {
163
Log_Write_EKF_POS();
164
}
165
if (should_log(MASK_LOG_RCIN)) {
166
logger.Write_RCIN();
167
#if AP_RSSI_ENABLED
168
if (rssi.enabled()) {
169
logger.Write_RSSI();
170
}
171
#endif
172
}
173
if (should_log(MASK_LOG_RCOUT)) {
174
logger.Write_RCOUT();
175
}
176
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
177
AP::ins().Write_Vibration();
178
}
179
}
180
181
182
// twentyfive_hz_logging - should be run at 25hz
183
void Blimp::twentyfive_hz_logging()
184
{
185
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
186
Log_Write_EKF_POS();
187
}
188
189
if (should_log(MASK_LOG_IMU)) {
190
AP::ins().Write_IMU();
191
}
192
}
193
#endif // HAL_LOGGING_ENABLED
194
195
// three_hz_loop - 3.3hz loop
196
void Blimp::three_hz_loop()
197
{
198
// check if we've lost contact with the ground station
199
failsafe_gcs_check();
200
}
201
202
// one_hz_loop - runs at 1Hz
203
void Blimp::one_hz_loop()
204
{
205
#if HAL_LOGGING_ENABLED
206
if (should_log(MASK_LOG_ANY)) {
207
Log_Write_Data(LogDataID::AP_STATE, ap.value);
208
}
209
#endif
210
211
// update assigned functions and enable auxiliary servos
212
AP::srv().enable_aux_servos();
213
214
AP_Notify::flags.flying = !ap.land_complete;
215
216
blimp.pid_pos_yaw.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
217
}
218
219
void Blimp::read_AHRS(void)
220
{
221
// we tell AHRS to skip INS update as we have already done it in fast_loop()
222
ahrs.update(true);
223
224
IGNORE_RETURN(ahrs.get_velocity_NED(vel_ned));
225
IGNORE_RETURN(ahrs.get_relative_position_NED_origin_float(pos_ned));
226
227
vel_yaw = ahrs.get_yaw_rate_earth();
228
Vector2f vel_xy_filtd = vel_xy_filter.apply({vel_ned.x, vel_ned.y});
229
vel_ned_filtd = {vel_xy_filtd.x, vel_xy_filtd.y, vel_z_filter.apply(vel_ned.z)};
230
vel_yaw_filtd = vel_yaw_filter.apply(vel_yaw);
231
232
#if HAL_LOGGING_ENABLED
233
AP::logger().WriteStreaming("VNF", "TimeUS,X,XF,Y,YF,Z,ZF,Yaw,YawF,PX,PY,PZ,PYaw", "Qffffffffffff",
234
AP_HAL::micros64(),
235
vel_ned.x,
236
vel_ned_filtd.x,
237
vel_ned.y,
238
vel_ned_filtd.y,
239
vel_ned.z,
240
vel_ned_filtd.z,
241
vel_yaw,
242
vel_yaw_filtd,
243
pos_ned.x,
244
pos_ned.y,
245
pos_ned.z,
246
blimp.ahrs.get_yaw_rad());
247
#endif
248
}
249
250
// read baro and log control tuning
251
void Blimp::update_altitude()
252
{
253
// read in baro altitude
254
read_barometer();
255
256
#if HAL_LOGGING_ENABLED
257
if (should_log(MASK_LOG_CTUN)) {
258
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
259
AP::ins().write_notch_log_messages();
260
#endif
261
#if HAL_GYROFFT_ENABLED
262
gyro_fft.write_log_messages();
263
#endif
264
}
265
#endif
266
}
267
268
//Conversions are in 2D so that up remains up in world frame when the blimp is not exactly level.
269
void Blimp::rotate_BF_to_NE(Vector2f &vec)
270
{
271
float ne_x = vec.x*ahrs.cos_yaw() - vec.y*ahrs.sin_yaw();
272
float ne_y = vec.x*ahrs.sin_yaw() + vec.y*ahrs.cos_yaw();
273
vec.x = ne_x;
274
vec.y = ne_y;
275
}
276
277
void Blimp::rotate_NE_to_BF(Vector2f &vec)
278
{
279
float bf_x = vec.x*ahrs.cos_yaw() + vec.y*ahrs.sin_yaw();
280
float bf_y = -vec.x*ahrs.sin_yaw() + vec.y*ahrs.cos_yaw();
281
vec.x = bf_x;
282
vec.y = bf_y;
283
284
}
285
286
/*
287
constructor for main Blimp class
288
*/
289
Blimp::Blimp(void)
290
:
291
flight_modes(&g.flight_mode1),
292
control_mode(Mode::Number::MANUAL),
293
rc_throttle_control_in_filter(1.0f),
294
inertial_nav(ahrs),
295
param_loader(var_info),
296
flightmode(&mode_manual)
297
{
298
}
299
300
Blimp blimp;
301
AP_Vehicle& vehicle = blimp;
302
303
AP_HAL_MAIN_CALLBACKS(&blimp);
304
305