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/Blimp.cpp
Views: 1798
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(arm_motors_check, 10, 50, 18),
73
SCHED_TASK(update_altitude, 10, 100, 21),
74
SCHED_TASK(three_hz_loop, 3, 75, 24),
75
#if AP_SERVORELAYEVENTS_ENABLED
76
SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27),
77
#endif
78
#if HAL_LOGGING_ENABLED
79
SCHED_TASK(full_rate_logging, 50, 50, 33),
80
#endif
81
SCHED_TASK_CLASS(AP_Notify, &blimp.notify, update, 50, 90, 36),
82
SCHED_TASK(one_hz_loop, 1, 100, 39),
83
SCHED_TASK(ekf_check, 10, 75, 42),
84
SCHED_TASK(check_vibration, 10, 50, 45),
85
SCHED_TASK(gpsglitch_check, 10, 50, 48),
86
SCHED_TASK_CLASS(GCS, (GCS*)&blimp._gcs, update_receive, 400, 180, 51),
87
SCHED_TASK_CLASS(GCS, (GCS*)&blimp._gcs, update_send, 400, 550, 54),
88
#if HAL_LOGGING_ENABLED
89
SCHED_TASK(ten_hz_logging_loop, 10, 350, 57),
90
SCHED_TASK(twentyfive_hz_logging, 25, 110, 60),
91
SCHED_TASK_CLASS(AP_Logger, &blimp.logger, periodic_tasks, 400, 300, 63),
92
#endif
93
SCHED_TASK_CLASS(AP_InertialSensor, &blimp.ins, periodic, 400, 50, 66),
94
#if HAL_LOGGING_ENABLED
95
SCHED_TASK_CLASS(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75, 69),
96
#endif
97
};
98
99
void Blimp::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
100
uint8_t &task_count,
101
uint32_t &log_bit)
102
{
103
tasks = &scheduler_tasks[0];
104
task_count = ARRAY_SIZE(scheduler_tasks);
105
log_bit = MASK_LOG_PM;
106
}
107
108
constexpr int8_t Blimp::_failsafe_priorities[4];
109
110
// rc_loops - reads user input from transmitter/receiver
111
// called at 100hz
112
void Blimp::rc_loop()
113
{
114
// Read radio and 3-position switch on radio
115
// -----------------------------------------
116
read_radio();
117
rc().read_mode_switch();
118
}
119
120
// throttle_loop - should be run at 50 hz
121
// ---------------------------
122
void Blimp::throttle_loop()
123
{
124
// check auto_armed status
125
update_auto_armed();
126
}
127
128
// update_batt_compass - read battery and compass
129
// should be called at 10hz
130
void Blimp::update_batt_compass(void)
131
{
132
// read battery before compass because it may be used for motor interference compensation
133
battery.read();
134
135
if (AP::compass().available()) {
136
// update compass with throttle value - used for compassmot
137
compass.set_voltage(battery.voltage());
138
compass.read();
139
}
140
}
141
142
#if HAL_LOGGING_ENABLED
143
// Full rate logging of attitude, rate and pid loops
144
void Blimp::full_rate_logging()
145
{
146
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
147
Log_Write_Attitude();
148
}
149
if (should_log(MASK_LOG_PID)) {
150
Log_Write_PIDs();
151
}
152
}
153
154
// ten_hz_logging_loop
155
// should be run at 10hz
156
void Blimp::ten_hz_logging_loop()
157
{
158
// log attitude data if we're not already logging at the higher rate
159
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
160
Log_Write_Attitude();
161
}
162
// log EKF attitude data
163
if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) {
164
Log_Write_EKF_POS();
165
}
166
if (should_log(MASK_LOG_RCIN)) {
167
logger.Write_RCIN();
168
#if AP_RSSI_ENABLED
169
if (rssi.enabled()) {
170
logger.Write_RSSI();
171
}
172
#endif
173
}
174
if (should_log(MASK_LOG_RCOUT)) {
175
logger.Write_RCOUT();
176
}
177
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
178
AP::ins().Write_Vibration();
179
}
180
}
181
182
183
// twentyfive_hz_logging - should be run at 25hz
184
void Blimp::twentyfive_hz_logging()
185
{
186
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
187
Log_Write_EKF_POS();
188
}
189
190
if (should_log(MASK_LOG_IMU)) {
191
AP::ins().Write_IMU();
192
}
193
}
194
#endif // HAL_LOGGING_ENABLED
195
196
// three_hz_loop - 3.3hz loop
197
void Blimp::three_hz_loop()
198
{
199
// check if we've lost contact with the ground station
200
failsafe_gcs_check();
201
}
202
203
// one_hz_loop - runs at 1Hz
204
void Blimp::one_hz_loop()
205
{
206
#if HAL_LOGGING_ENABLED
207
if (should_log(MASK_LOG_ANY)) {
208
Log_Write_Data(LogDataID::AP_STATE, ap.value);
209
}
210
#endif
211
212
// update assigned functions and enable auxiliary servos
213
AP::srv().enable_aux_servos();
214
215
AP_Notify::flags.flying = !ap.land_complete;
216
217
blimp.pid_pos_yaw.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
218
}
219
220
void Blimp::read_AHRS(void)
221
{
222
// we tell AHRS to skip INS update as we have already done it in fast_loop()
223
ahrs.update(true);
224
225
IGNORE_RETURN(ahrs.get_velocity_NED(vel_ned));
226
IGNORE_RETURN(ahrs.get_relative_position_NED_origin(pos_ned));
227
228
vel_yaw = ahrs.get_yaw_rate_earth();
229
Vector2f vel_xy_filtd = vel_xy_filter.apply({vel_ned.x, vel_ned.y});
230
vel_ned_filtd = {vel_xy_filtd.x, vel_xy_filtd.y, vel_z_filter.apply(vel_ned.z)};
231
vel_yaw_filtd = vel_yaw_filter.apply(vel_yaw);
232
233
#if HAL_LOGGING_ENABLED
234
AP::logger().WriteStreaming("VNF", "TimeUS,X,XF,Y,YF,Z,ZF,Yaw,YawF,PX,PY,PZ,PYaw", "Qffffffffffff",
235
AP_HAL::micros64(),
236
vel_ned.x,
237
vel_ned_filtd.x,
238
vel_ned.y,
239
vel_ned_filtd.y,
240
vel_ned.z,
241
vel_ned_filtd.z,
242
vel_yaw,
243
vel_yaw_filtd,
244
pos_ned.x,
245
pos_ned.y,
246
pos_ned.z,
247
blimp.ahrs.get_yaw());
248
#endif
249
}
250
251
// read baro and log control tuning
252
void Blimp::update_altitude()
253
{
254
// read in baro altitude
255
read_barometer();
256
257
#if HAL_LOGGING_ENABLED
258
if (should_log(MASK_LOG_CTUN)) {
259
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
260
AP::ins().write_notch_log_messages();
261
#endif
262
#if HAL_GYROFFT_ENABLED
263
gyro_fft.write_log_messages();
264
#endif
265
}
266
#endif
267
}
268
269
//Conversions are in 2D so that up remains up in world frame when the blimp is not exactly level.
270
void Blimp::rotate_BF_to_NE(Vector2f &vec)
271
{
272
float ne_x = vec.x*ahrs.cos_yaw() - vec.y*ahrs.sin_yaw();
273
float ne_y = vec.x*ahrs.sin_yaw() + vec.y*ahrs.cos_yaw();
274
vec.x = ne_x;
275
vec.y = ne_y;
276
}
277
278
void Blimp::rotate_NE_to_BF(Vector2f &vec)
279
{
280
float bf_x = vec.x*ahrs.cos_yaw() + vec.y*ahrs.sin_yaw();
281
float bf_y = -vec.x*ahrs.sin_yaw() + vec.y*ahrs.cos_yaw();
282
vec.x = bf_x;
283
vec.y = bf_y;
284
285
}
286
287
/*
288
constructor for main Blimp class
289
*/
290
Blimp::Blimp(void)
291
:
292
flight_modes(&g.flight_mode1),
293
control_mode(Mode::Number::MANUAL),
294
rc_throttle_control_in_filter(1.0f),
295
inertial_nav(ahrs),
296
param_loader(var_info),
297
flightmode(&mode_manual)
298
{
299
}
300
301
Blimp blimp;
302
AP_Vehicle& vehicle = blimp;
303
304
AP_HAL_MAIN_CALLBACKS(&blimp);
305
306