APM:Copter
ArduCopter.cpp
Go to the documentation of this file.
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  * ArduCopter (also known as APM, APM:Copter or just Copter)
17  * Wiki: copter.ardupilot.org
18  * Creator: Jason Short
19  * Lead Developer: Randy Mackay
20  * Lead Tester: Marco Robustini
21  * Based on code and ideas from the Arducopter team: Leonard Hall, Andrew Tridgell, Robert Lefebvre, Pat Hickey, Michael Oborne, Jani Hirvinen,
22  Olivier Adler, Kevin Hester, Arthur Benemann, Jonathan Challinger, John Arne Birkeland,
23  Jean-Louis Naudin, Mike Smith, and more
24  * Thanks to: Chris Anderson, Jordi Munoz, Jason Short, Doug Weibel, Jose Julio
25  *
26  * Special Thanks to contributors (in alphabetical order by first name):
27  *
28  * Adam M Rivera :Auto Compass Declination
29  * Amilcar Lucas :Camera mount library
30  * Andrew Tridgell :General development, Mavlink Support
31  * Angel Fernandez :Alpha testing
32  * AndreasAntonopoulous:GeoFence
33  * Arthur Benemann :DroidPlanner GCS
34  * Benjamin Pelletier :Libraries
35  * Bill King :Single Copter
36  * Christof Schmid :Alpha testing
37  * Craig Elder :Release Management, Support
38  * Dani Saez :V Octo Support
39  * Doug Weibel :DCM, Libraries, Control law advice
40  * Emile Castelnuovo :VRBrain port, bug fixes
41  * Gregory Fletcher :Camera mount orientation math
42  * Guntars :Arming safety suggestion
43  * HappyKillmore :Mavlink GCS
44  * Hein Hollander :Octo Support, Heli Testing
45  * Igor van Airde :Control Law optimization
46  * Jack Dunkle :Alpha testing
47  * James Goppert :Mavlink Support
48  * Jani Hiriven :Testing feedback
49  * Jean-Louis Naudin :Auto Landing
50  * John Arne Birkeland :PPM Encoder
51  * Jose Julio :Stabilization Control laws, MPU6k driver
52  * Julien Dubois :PosHold flight mode
53  * Julian Oes :Pixhawk
54  * Jonathan Challinger :Inertial Navigation, CompassMot, Spin-When-Armed
55  * Kevin Hester :Andropilot GCS
56  * Max Levine :Tri Support, Graphics
57  * Leonard Hall :Flight Dynamics, Throttle, Loiter and Navigation Controllers
58  * Marco Robustini :Lead tester
59  * Michael Oborne :Mission Planner GCS
60  * Mike Smith :Pixhawk driver, coding support
61  * Olivier Adler :PPM Encoder, piezo buzzer
62  * Pat Hickey :Hardware Abstraction Layer (HAL)
63  * Robert Lefebvre :Heli Support, Copter LEDs
64  * Roberto Navoni :Library testing, Porting to VRBrain
65  * Sandro Benigno :Camera support, MinimOSD
66  * Sandro Tognana :PosHold flight mode
67  * Sebastian Quilter :SmartRTL
68  * ..and many more.
69  *
70  * Code commit statistics can be found here: https://github.com/ArduPilot/ardupilot/graphs/contributors
71  * Wiki: http://copter.ardupilot.org/
72  * Requires modified version of Arduino, which can be found here: http://ardupilot.com/downloads/?category=6
73  *
74  */
75 
76 #include "Copter.h"
77 
78 #define SCHED_TASK(func, rate_hz, max_time_micros) SCHED_TASK_CLASS(Copter, &copter, func, rate_hz, max_time_micros)
79 
80 /*
81  scheduler table for fast CPUs - all regular tasks apart from the fast_loop()
82  should be listed here, along with how often they should be called (in hz)
83  and the maximum time they are expected to take (in microseconds)
84  */
86  SCHED_TASK(rc_loop, 100, 130),
87  SCHED_TASK(throttle_loop, 50, 75),
88  SCHED_TASK(update_GPS, 50, 200),
89 #if OPTFLOW == ENABLED
90  SCHED_TASK(update_optical_flow, 200, 160),
91 #endif
92  SCHED_TASK(update_batt_compass, 10, 120),
93  SCHED_TASK(read_aux_switches, 10, 50),
94  SCHED_TASK(arm_motors_check, 10, 50),
95 #if TOY_MODE_ENABLED == ENABLED
96  SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50),
97 #endif
98  SCHED_TASK(auto_disarm_check, 10, 50),
99  SCHED_TASK(auto_trim, 10, 75),
100 #if RANGEFINDER_ENABLED == ENABLED
101  SCHED_TASK(read_rangefinder, 20, 100),
102 #endif
103 #if PROXIMITY_ENABLED == ENABLED
104  SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 100, 50),
105 #endif
106 #if BEACON_ENABLED == ENABLED
107  SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50),
108 #endif
109 #if VISUAL_ODOMETRY_ENABLED == ENABLED
110  SCHED_TASK(update_visual_odom, 400, 50),
111 #endif
112  SCHED_TASK(update_altitude, 10, 100),
113  SCHED_TASK(run_nav_updates, 50, 100),
114  SCHED_TASK(update_throttle_hover,100, 90),
115 #if MODE_SMARTRTL_ENABLED == ENABLED
116  SCHED_TASK_CLASS(Copter::ModeSmartRTL, &copter.mode_smartrtl, save_position, 3, 100),
117 #endif
118  SCHED_TASK(three_hz_loop, 3, 75),
119  SCHED_TASK(compass_accumulate, 100, 100),
120  SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90),
121 #if PRECISION_LANDING == ENABLED
122  SCHED_TASK(update_precland, 400, 50),
123 #endif
124 #if FRAME_CONFIG == HELI_FRAME
125  SCHED_TASK(check_dynamic_flight, 50, 75),
126 #endif
127 #if LOGGING_ENABLED == ENABLED
128  SCHED_TASK(fourhundred_hz_logging,400, 50),
129 #endif
130  SCHED_TASK_CLASS(AP_Notify, &copter.notify, update, 50, 90),
131  SCHED_TASK(one_hz_loop, 1, 100),
132  SCHED_TASK(ekf_check, 10, 75),
133  SCHED_TASK(gpsglitch_check, 10, 50),
134  SCHED_TASK(landinggear_update, 10, 75),
135  SCHED_TASK(lost_vehicle_check, 10, 50),
136  SCHED_TASK(gcs_check_input, 400, 180),
137  SCHED_TASK(gcs_send_heartbeat, 1, 110),
138  SCHED_TASK(gcs_send_deferred, 50, 550),
139  SCHED_TASK(gcs_data_stream_send, 50, 550),
140 #if MOUNT == ENABLED
141  SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75),
142 #endif
143 #if CAMERA == ENABLED
144  SCHED_TASK_CLASS(AP_Camera, &copter.camera, update_trigger, 50, 75),
145 #endif
146 #if LOGGING_ENABLED == ENABLED
147  SCHED_TASK(ten_hz_logging_loop, 10, 350),
148  SCHED_TASK(twentyfive_hz_logging, 25, 110),
149  SCHED_TASK_CLASS(DataFlash_Class, &copter.DataFlash, periodic_tasks, 400, 300),
150 #endif
151  SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50),
152  SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75),
153 #if RPM_ENABLED == ENABLED
154  SCHED_TASK(rpm_update, 10, 200),
155 #endif
156  SCHED_TASK(compass_cal_update, 100, 100),
157  SCHED_TASK(accel_cal_update, 10, 100),
158  SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100),
159 #if ADSB_ENABLED == ENABLED
160  SCHED_TASK(avoidance_adsb_update, 10, 100),
161 #endif
162 #if ADVANCED_FAILSAFE == ENABLED
163  SCHED_TASK(afs_fs_check, 10, 100),
164 #endif
165 #if AC_TERRAIN == ENABLED
166  SCHED_TASK(terrain_update, 10, 100),
167 #endif
168 #if GRIPPER_ENABLED == ENABLED
169  SCHED_TASK_CLASS(AP_Gripper, &copter.g2.gripper, update, 10, 75),
170 #endif
171 #if WINCH_ENABLED == ENABLED
172  SCHED_TASK(winch_update, 10, 50),
173 #endif
174 #ifdef USERHOOK_FASTLOOP
175  SCHED_TASK(userhook_FastLoop, 100, 75),
176 #endif
177 #ifdef USERHOOK_50HZLOOP
178  SCHED_TASK(userhook_50Hz, 50, 75),
179 #endif
180 #ifdef USERHOOK_MEDIUMLOOP
181  SCHED_TASK(userhook_MediumLoop, 10, 75),
182 #endif
183 #ifdef USERHOOK_SLOWLOOP
184  SCHED_TASK(userhook_SlowLoop, 3.3, 75),
185 #endif
186 #ifdef USERHOOK_SUPERSLOWLOOP
187  SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
188 #endif
189  SCHED_TASK_CLASS(AP_Button, &copter.g2.button, update, 5, 100),
190 #if STATS_ENABLED == ENABLED
191  SCHED_TASK_CLASS(AP_Stats, &copter.g2.stats, update, 1, 100),
192 #endif
193 };
194 
196 
198 {
199  // Load the default values of variables listed in var_info[]s
201 
202  // setup storage layout for copter
204 
205  init_ardupilot();
206 
207  // initialise the main loop scheduler
209 }
210 
212 {
213  scheduler.loop();
215 }
216 
217 
218 // Main loop - 400hz
220 {
221  // update INS immediately to get current gyro data populated
222  ins.update();
223 
224  // run low level rate controllers that only require IMU data
225  attitude_control->rate_controller_run();
226 
227  // send outputs to the motors library immediately
228  motors_output();
229 
230  // run EKF state estimator (expensive)
231  // --------------------
232  read_AHRS();
233 
234 #if FRAME_CONFIG == HELI_FRAME
236 #endif //HELI_FRAME
237 
238  // Inertial Nav
239  // --------------------
240  read_inertia();
241 
242  // check if ekf has reset target heading or position
243  check_ekf_reset();
244 
245  // run the attitude controllers
247 
248  // update home from EKF if necessary
250 
251  // check if we've landed or crashed
253 
254 #if MOUNT == ENABLED
255  // camera mount's fast update
257 #endif
258 
259  // log sensor health
260  if (should_log(MASK_LOG_ANY)) {
262  }
263 }
264 
265 // rc_loops - reads user input from transmitter/receiver
266 // called at 100hz
268 {
269  // Read radio and 3-position switch on radio
270  // -----------------------------------------
271  read_radio();
273 }
274 
275 // throttle_loop - should be run at 50 hz
276 // ---------------------------
278 {
279  // update throttle_low_comp value (controls priority of throttle vs attitude control)
281 
282  // check auto_armed status
284 
285 #if FRAME_CONFIG == HELI_FRAME
286  // update rotor speed
288 
289  // update trad heli swash plate movement
291 #endif
292 
293  // compensate for ground effect (if enabled)
295 }
296 
297 // update_batt_compass - read battery and compass
298 // should be called at 10hz
300 {
301  // read battery before compass because it may be used for motor interference compensation
302  battery.read();
303 
304  if(g.compass_enabled) {
305  // update compass with throttle value - used for compassmot
306  compass.set_throttle(motors->get_throttle());
308  compass.read();
309  // log compass information
312  }
313  }
314 }
315 
316 // Full rate logging of attitude, rate and pid loops
317 // should be run at 400hz
319 {
322  }
323 }
324 
325 // ten_hz_logging_loop
326 // should be run at 10hz
328 {
329  // log attitude data if we're not already logging at the higher rate
333  }
336  }
337  if (should_log(MASK_LOG_RCIN)) {
339  if (rssi.enabled()) {
341  }
342  }
343  if (should_log(MASK_LOG_RCOUT)) {
345  }
348  }
351  }
352  if (should_log(MASK_LOG_CTUN)) {
353  attitude_control->control_monitor_log();
354 #if PROXIMITY_ENABLED == ENABLED
355  DataFlash.Log_Write_Proximity(g2.proximity); // Write proximity sensor distances
356 #endif
357 #if BEACON_ENABLED == ENABLED
359 #endif
360  }
361 #if FRAME_CONFIG == HELI_FRAME
362  Log_Write_Heli();
363 #endif
364 }
365 
366 // twentyfive_hz_logging - should be run at 25hz
368 {
369 #if HIL_MODE != HIL_MODE_DISABLED
370  // HIL for a copter needs very fast update of the servo values
372 #endif
373 
374 #if HIL_MODE == HIL_MODE_DISABLED
377  }
378 
379  // log IMU data if we're not already logging at the higher rate
382  }
383 #endif
384 
385 #if PRECISION_LANDING == ENABLED
386  // log output
388 #endif
389 }
390 
391 // three_hz_loop - 3.3hz loop
393 {
394  // check if we've lost contact with the ground station
396 
397  // check if we've lost terrain data
399 
400 #if AC_FENCE == ENABLED
401  // check if we have breached a fence
402  fence_check();
403 #endif // AC_FENCE_ENABLED
404 
405 #if SPRAYER == ENABLED
406  sprayer.update();
407 #endif
408 
409  update_events();
410 
411  // update ch6 in flight tuning
412  tuning();
413 }
414 
415 // one_hz_loop - runs at 1Hz
417 {
418  if (should_log(MASK_LOG_ANY)) {
420  }
421 
422  arming.update();
423 
424  if (!motors->armed()) {
425  // make it possible to change ahrs orientation at runtime during initial config
427 
429 
430  // check the user hasn't updated the frame class or type
432 
433 #if FRAME_CONFIG != HELI_FRAME
434  // set all throttle channel settings
436 #endif
437  }
438 
439  // update assigned functions and enable auxiliary servos
441 
442  check_usb_mux();
443 
444  // log terrain data
445  terrain_logging();
446 
447 #if ADSB_ENABLED == ENABLED
448  adsb.set_is_flying(!ap.land_complete);
449 #endif
450 
451  // update error mask of sensors and subsystems. The mask uses the
452  // MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
453  // indicates that the sensor or subsystem is present but not
454  // functioning correctly
456 }
457 
458 // called at 50hz
460 {
461  static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; // time of last gps message
462  bool gps_updated = false;
463 
464  gps.update();
465 
466  // log after every gps message
467  for (uint8_t i=0; i<gps.num_sensors(); i++) {
468  if (gps.last_message_time_ms(i) != last_gps_reading[i]) {
469  last_gps_reading[i] = gps.last_message_time_ms(i);
470  gps_updated = true;
471  break;
472  }
473  }
474 
475  if (gps_updated) {
476  // set system time if necessary
478 
479 #if CAMERA == ENABLED
480  camera.update();
481 #endif
482  }
483 }
484 
486 {
487  // capture current cos_yaw and sin_yaw values
490 
491  // initialise super simple heading (i.e. heading towards home) to be 180 deg from simple mode heading
495 
496  // log the simple bearing to dataflash
497  if (should_log(MASK_LOG_ANY)) {
499  }
500 }
501 
502 // update_simple_mode - rotates pilot input if we are in simple mode
504 {
505  float rollx, pitchx;
506 
507  // exit immediately if no new radio frame or not in simple mode
508  if (ap.simple_mode == 0 || !ap.new_radio_frame) {
509  return;
510  }
511 
512  // mark radio frame as consumed
513  ap.new_radio_frame = false;
514 
515  if (ap.simple_mode == 1) {
516  // rotate roll, pitch input by -initial simple heading (i.e. north facing)
519  }else{
520  // rotate roll, pitch input by -super simple heading (reverse of heading to home)
523  }
524 
525  // rotate roll, pitch input from north facing to vehicle's perspective
526  channel_roll->set_control_in(rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw());
527  channel_pitch->set_control_in(-rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw());
528 }
529 
530 // update_super_simple_bearing - adjusts simple bearing based on location
531 // should be called after home_bearing has been updated
532 void Copter::update_super_simple_bearing(bool force_update)
533 {
534  if (!force_update) {
535  if (ap.simple_mode != 2) {
536  return;
537  }
539  return;
540  }
541  }
542 
543  const int32_t bearing = home_bearing();
544 
545  // check the bearing to home has changed by at least 5 degrees
546  if (labs(super_simple_last_bearing - bearing) < 500) {
547  return;
548  }
549 
550  super_simple_last_bearing = bearing;
551  const float angle_rad = radians((super_simple_last_bearing+18000)/100);
552  super_simple_cos_yaw = cosf(angle_rad);
553  super_simple_sin_yaw = sinf(angle_rad);
554 }
555 
557 {
558  // Perform IMU calculations and get attitude info
559  //-----------------------------------------------
560 #if HIL_MODE != HIL_MODE_DISABLED
561  // update hil before ahrs update
562  gcs_check_input();
563 #endif
564 
565  // we tell AHRS to skip INS update as we have already done it in fast_loop()
566  ahrs.update(true);
567 }
568 
569 // read baro and rangefinder altitude at 10hz
571 {
572  // read in baro altitude
573  read_barometer();
574 
575  // write altitude info to dataflash logs
576  if (should_log(MASK_LOG_CTUN)) {
578  }
579 }
580 
float cos_yaw() const
void read_barometer(void)
Definition: sensors.cpp:4
#define MASK_LOG_RCIN
Definition: defines.h:320
#define DATA_INIT_SIMPLE_BEARING
Definition: defines.h:338
static void set_layout_copter(void)
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
#define MASK_LOG_ATTITUDE_FAST
Definition: defines.h:314
void read_radio()
Definition: radio.cpp:94
AP_Int8 frame_class
Definition: Parameters.h:560
void motors_output()
Definition: motors.cpp:292
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
void read_inertia()
Definition: inertia.cpp:4
#define MASK_LOG_CTUN
Definition: defines.h:318
void update(void)
void Log_Write_Control_Tuning()
Definition: Log.cpp:113
AP_Arming_Copter arming
Definition: Copter.h:280
void update_flight_mode()
Definition: mode.cpp:245
void read_control_switch()
Definition: switches.cpp:16
float simple_sin_yaw
Definition: Copter.h:436
#define SUPER_SIMPLE_RADIUS
Definition: config.h:538
float sin_yaw() const
uint8_t num_sensors(void) const
void update_land_and_crash_detectors()
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
AP_InertialSensor ins
Definition: Copter.h:236
RC_Channel * channel_roll
Definition: Copter.h:221
void update_simple_mode(void)
Definition: ArduCopter.cpp:503
void twentyfive_hz_logging()
Definition: ArduCopter.cpp:367
static const AP_Scheduler::Task scheduler_tasks[]
Definition: Copter.h:625
bool landing_with_GPS()
Definition: mode_land.cpp:162
void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
void Log_Write_Beacon(AP_Beacon &beacon)
AP_Beacon beacon
Definition: Parameters.h:529
void update_home_from_EKF()
Definition: commands.cpp:4
GCS_Copter & gcs()
Definition: Copter.h:301
uint8_t adsb
Definition: Copter.h:401
void loop() override
Definition: ArduCopter.cpp:211
void Log_Write_Proximity(AP_Proximity &proximity)
void update_throttle_thr_mix()
uint32_t last_message_time_ms(uint8_t instance) const
float get_last_loop_time_s(void) const
void three_hz_loop()
Definition: ArduCopter.cpp:392
void heli_update_landing_swash()
bool read()
#define AP_HAL_MAIN_CALLBACKS(CALLBACKS)
AP_Proximity proximity
Definition: Parameters.h:539
void Log_Write_EKF_POS()
Definition: Log.cpp:158
void fence_check()
Definition: fence.cpp:9
void terrain_logging()
Definition: terrain.cpp:21
bool should_log(uint32_t mask)
Definition: system.cpp:435
void set_orientation()
MOTOR_CLASS * motors
Definition: Copter.h:422
void Log_Write_Precland()
Definition: Log.cpp:420
void set_control_in(int16_t val)
void rc_loop()
Definition: ArduCopter.cpp:267
AP_Int8 frame_type
Definition: Parameters.h:443
void set_throttle(float thr_pct)
#define MASK_LOG_IMU
Definition: defines.h:321
int32_t super_simple_last_bearing
Definition: Copter.h:437
void send_message(enum ap_message id)
RC_Channel * channel_throttle
Definition: Copter.h:223
void update_ground_effect_detector(void)
void ten_hz_logging_loop()
Definition: ArduCopter.cpp:327
void Log_Write_RSSI(AP_RSSI &rssi)
void update_auto_armed()
Definition: system.cpp:383
int16_t get_control_in() const
#define GPS_MAX_INSTANCES
void update(void)
Definition: AP_Arming.cpp:4
void Log_Write_MotBatt()
Definition: Log.cpp:178
AP_Mount camera_mount
Definition: Copter.h:522
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0)
void update()
#define constexpr
#define MASK_LOG_COMPASS
Definition: defines.h:327
RC_Channel * channel_pitch
Definition: Copter.h:222
Mode * flightmode
Definition: Copter.h:955
AP_BattMonitor battery
Definition: Copter.h:445
AP_RSSI rssi
Definition: Copter.h:544
#define SCHED_TASK(func, rate_hz, max_time_micros)
Definition: ArduCopter.cpp:78
void update_using_interlock()
Definition: AP_State.cpp:81
void Log_Write_Attitude()
Definition: Log.cpp:143
void write_log()
float bearing
#define MASK_LOG_NTUN
Definition: defines.h:319
void update_sensor_status_flags(void)
Definition: sensors.cpp:226
void update(bool skip_ins_update=false) override
void failsafe_gcs_check()
Definition: events.cpp:87
#define MASK_LOG_ATTITUDE_MED
Definition: defines.h:315
void tuning()
Definition: tuning.cpp:10
void init_simple_bearing()
Definition: ArduCopter.cpp:485
#define SCHED_TASK_CLASS(classname, classptr, func, _rate_hz, _max_time_micros)
void Log_Write_RCOUT(void)
AP_Camera camera
Definition: Copter.h:516
static void enable_aux_servos(void)
void update_events()
Definition: events.cpp:286
void one_hz_loop()
Definition: ArduCopter.cpp:416
void update_GPS(void)
Definition: ArduCopter.cpp:459
#define MASK_LOG_PM
Definition: defines.h:317
#define ARRAY_SIZE(_arr)
bool have_ekf_logging(void) const override
void failsafe_terrain_check()
Definition: events.cpp:149
DataFlash_Class DataFlash
Definition: Copter.h:227
static constexpr int8_t _failsafe_priorities[]
Definition: Copter.h:638
void fourhundred_hz_logging()
Definition: ArduCopter.cpp:318
void read_AHRS(void)
Definition: ArduCopter.cpp:556
AP_GPS gps
Definition: Copter.h:229
void update_super_simple_bearing(bool force_update)
Definition: ArduCopter.cpp:532
MSG_SERVO_OUTPUT_RAW
AP_Scheduler scheduler
Definition: Copter.h:212
void set_voltage(float voltage)
Parameters g
Definition: Copter.h:208
AP_Int8 compass_enabled
Definition: Parameters.h:401
#define DATA_AP_STATE
Definition: defines.h:336
Compass compass
Definition: Copter.h:235
#define MASK_LOG_RCOUT
Definition: defines.h:324
void check_ekf_reset()
Definition: ekf_check.cpp:180
void update()
void Log_Sensor_Health()
Definition: Log.cpp:365
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
void setup() override
Definition: ArduCopter.cpp:197
void gcs_check_input(void)
void fast_loop()
Definition: ArduCopter.cpp:219
void update_batt_compass(void)
Definition: ArduCopter.cpp:299
int16_t get_radio_min() const
int16_t get_radio_max() const
AC_Sprayer sprayer
Definition: Copter.h:548
void update_heli_control_dynamics(void)
uint32_t home_distance()
Definition: navigation.cpp:14
AC_PosControl * pos_control
Definition: Copter.h:493
float super_simple_sin_yaw
Definition: Copter.h:439
float super_simple_cos_yaw
Definition: Copter.h:438
void update_altitude()
Definition: ArduCopter.cpp:570
#define MASK_LOG_MOTBATT
Definition: defines.h:330
virtual bool requires_GPS() const =0
ParametersG2 g2
Definition: Copter.h:209
int32_t home_bearing()
Definition: navigation.cpp:25
bool enabled() const
#define MASK_LOG_IMU_FAST
Definition: defines.h:331
void update(void)
void heli_update_rotor_speed_targets()
void Log_Write_Vibration()
float voltage(uint8_t instance) const
int32_t yaw_sensor
#define MASK_LOG_IMU_RAW
Definition: defines.h:332
void set_system_time_from_GPS()
Definition: commands.cpp:129
void Log_Write_RCIN(void)
float simple_cos_yaw
Definition: Copter.h:435
void Log_Write_IMU()
void Log_Write_Data(uint8_t id, int32_t value)
Definition: Log.cpp:264
float G_Dt
Definition: Copter.h:480
void update_fast()
void throttle_loop()
Definition: ArduCopter.cpp:277
void init_ardupilot()
Definition: system.cpp:21
void check_usb_mux(void)
Definition: system.cpp:421
static void setup_sketch_defaults(void)
#define MASK_LOG_ANY
Definition: defines.h:333