APM:Copter
system.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*****************************************************************************
4 * The init_ardupilot function processes everything we need for an in - air restart
5 * We will determine later if we are actually on the ground and process a
6 * ground start in that case.
7 *
8 *****************************************************************************/
9 
11 {
12  copter.mavlink_delay_cb();
13 }
14 
15 
16 static void failsafe_check_static()
17 {
18  copter.failsafe_check();
19 }
20 
22 {
23  // initialise serial port
25 
26  // init vehicle capabilties
28 
29  hal.console->printf("\n\nInit %s"
30  "\n\nFree RAM: %u\n",
32  (unsigned)hal.util->available_memory());
33 
34  //
35  // Report firmware version code expect on console (check of actual EEPROM format version is done in load_parameters function)
36  //
38 
39  // load parameters from EEPROM
41 
42  // time per loop - this gets updated in the main loop() based on
43  // actual loop rate
45 
46 #if STATS_ENABLED == ENABLED
47  // initialise stats module
48  g2.stats.init();
49 #endif
50 
52 
53  // identify ourselves correctly with the ground station
55 
56  // initialise serial ports
58 
59  // setup first port early to allow BoardConfig to report errors
61 
62 
63  // Register mavlink_delay_cb, which will run anytime you have
64  // more than 5ms remaining in your call to hal.scheduler->delay
66 
67  BoardConfig.init();
68 #if HAL_WITH_UAVCAN
69  BoardConfig_CAN.init();
70 #endif
71 
72  // init cargo gripper
73 #if GRIPPER_ENABLED == ENABLED
74  g2.gripper.init();
75 #endif
76 
77  // init winch and wheel encoder
78  winch_init();
79 
80  // initialise notify system
81  notify.init(true);
83 
84  // initialise battery monitor
85  battery.init();
86 
87  // Init RSSI
88  rssi.init();
89 
90  barometer.init();
91 
92  // we start by assuming USB connected, as we initialed the serial
93  // port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
94  ap.usb_connected = true;
95  check_usb_mux();
96 
97  // setup telem slots with serial ports
99 
100 #if FRSKY_TELEM_ENABLED == ENABLED
101  // setup frsky, and pass a number of parameters to the library
102  char firmware_buf[50];
103  snprintf(firmware_buf, sizeof(firmware_buf), "%s %s", fwver.fw_string, get_frame_string());
104  frsky_telemetry.init(serial_manager, firmware_buf,
106  &ap.value);
107 #endif
108 
109 #if DEVO_TELEM_ENABLED == ENABLED
110  // setup devo
112 #endif
113 
114 #if LOGGING_ENABLED == ENABLED
115  log_init();
116 #endif
117 
118  // update motor interlock state
120 
121 #if FRAME_CONFIG == HELI_FRAME
122  // trad heli specific initialisation
123  heli_init();
124 #endif
125 #if FRAME_CONFIG == HELI_FRAME
126  input_manager.set_loop_rate(scheduler.get_loop_rate_hz());
127 #endif
128 
129  init_rc_in(); // sets up rc channels from radio
130 
131  // default frame class to match firmware if possible
133 
134  // allocate the motors class
135  allocate_motors();
136 
137  // sets up motors and output to escs
138  init_rc_out();
139 
140  // motors initialised so parameters can be sent
141  ap.initialised_params = true;
142 
143  // initialise which outputs Servo and Relay events can use
144  ServoRelayEvents.set_channel_mask(~motors->get_motor_mask());
145 
146  relay.init();
147 
148  /*
149  * setup the 'main loop is dead' check. Note that this relies on
150  * the RC library being initialised.
151  */
153 
154 #if BEACON_ENABLED == ENABLED
155  // give AHRS the range beacon sensor
157 #endif
158 
159  // Do GPS init
162 
163  init_compass();
164 
165 #if OPTFLOW == ENABLED
166  // make optflow available to AHRS
168 #endif
169 
170  // init Location class
172 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
175 #endif
176 #if AC_AVOID_ENABLED == ENABLED
179 #endif
180 
181  attitude_control->parameter_sanity_check();
183 
184  // init the optical flow sensor
185  init_optflow();
186 
187 #if MOUNT == ENABLED
188  // initialise camera mount
190 #endif
191 
192 #if PRECISION_LANDING == ENABLED
193  // initialise precision landing
194  init_precland();
195 #endif
196 
197  // initialise landing gear position
198  landinggear.init();
199 
200 #ifdef USERHOOK_INIT
201  USERHOOK_INIT
202 #endif
203 
204 #if HIL_MODE != HIL_MODE_DISABLED
205  while (barometer.get_last_update() == 0) {
206  // the barometer begins updating when we get the first
207  // HIL_STATE message
208  gcs().send_text(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
209  delay(1000);
210  }
211 
212  // set INS to HIL mode
213  ins.set_hil_mode();
214 #endif
215 
216  // read Baro pressure at ground
217  //-----------------------------
220 
221  // initialise rangefinder
223 
224  // init proximity sensor
225  init_proximity();
226 
227 #if BEACON_ENABLED == ENABLED
228  // init beacons used for non-gps position estimation
229  g2.beacon.init();
230 #endif
231 
232  // init visual odometry
234 
235 #if RPM_ENABLED == ENABLED
236  // initialise AP_RPM library
237  rpm_sensor.init();
238 #endif
239 
240 #if MODE_AUTO_ENABLED == ENABLED
241  // initialise mission library
242  mission.init();
243 #endif
244 
245 #if MODE_SMARTRTL_ENABLED == ENABLED
246  // initialize SmartRTL
247  g2.smart_rtl.init();
248 #endif
249 
250  // initialise DataFlash library
251 #if MODE_AUTO_ENABLED == ENABLED
253 #endif
255 
256  // initialise the flight mode and aux switch
257  // ---------------------------
260 
262 
263  // set landed flags
264  set_land_complete(true);
266 
267  // we don't want writes to the serial port to cause us to pause
268  // mid-flight, so set the serial ports non-blocking once we are
269  // ready to fly
271 
272  // enable CPU failsafe
273  failsafe_enable();
274 
276 
277  // enable output to motors
278  if (arming.rc_calibration_checks(true)) {
280  }
281 
282  // disable safety if requested
284 
285  // default enable RC override
286  copter.ap.rc_override_enable = true;
287 
288  hal.console->printf("\nReady to FLY ");
289 
290  // flag that initialisation has completed
291  ap.initialised = true;
292 }
293 
294 
295 //******************************************************************************
296 //This function does all the calibrations, etc. that we need during a ground start
297 //******************************************************************************
299 {
300  // initialise ahrs (may push imu calibration into the mpu6000 if using that device).
301  ahrs.init();
303 
304  // Warm up and calibrate gyro offsets
306 
307  // reset ahrs including gyro bias
308  ahrs.reset();
309 }
310 
311 // position_ok - returns true if the horizontal absolute position is ok and home position is set
313 {
314  // return false if ekf failsafe has triggered
315  if (failsafe.ekf) {
316  return false;
317  }
318 
319  // check ekf position estimate
320  return (ekf_position_ok() || optflow_position_ok());
321 }
322 
323 // ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
325 {
326  if (!ahrs.have_inertial_nav()) {
327  // do not allow navigation with dcm position
328  return false;
329  }
330 
331  // with EKF use filter status and ekf check
333 
334  // if disarmed we accept a predicted horizontal position
335  if (!motors->armed()) {
336  return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));
337  } else {
338  // once armed we require a good absolute position and EKF must not be in const_pos_mode
339  return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
340  }
341 }
342 
343 // optflow_position_ok - returns true if optical flow based position estimate is ok
345 {
346 #if OPTFLOW != ENABLED && VISUAL_ODOMETRY_ENABLED != ENABLED
347  return false;
348 #else
349  // return immediately if EKF not used
350  if (!ahrs.have_inertial_nav()) {
351  return false;
352  }
353 
354  // return immediately if neither optflow nor visual odometry is enabled
355  bool enabled = false;
356 #if OPTFLOW == ENABLED
357  if (optflow.enabled()) {
358  enabled = true;
359  }
360 #endif
361 #if VISUAL_ODOMETRY_ENABLED == ENABLED
362  if (g2.visual_odom.enabled()) {
363  enabled = true;
364  }
365 #endif
366  if (!enabled) {
367  return false;
368  }
369 
370  // get filter status from EKF
372 
373  // if disarmed we accept a predicted horizontal relative position
374  if (!motors->armed()) {
375  return (filt_status.flags.pred_horiz_pos_rel);
376  } else {
377  return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
378  }
379 #endif
380 }
381 
382 // update_auto_armed - update status of auto_armed flag
384 {
385  // disarm checks
386  if(ap.auto_armed){
387  // if motors are disarmed, auto_armed should also be false
388  if(!motors->armed()) {
389  set_auto_armed(false);
390  return;
391  }
392  // if in stabilize or acro flight mode and throttle is zero, auto-armed should become false
393  if(flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio) {
394  set_auto_armed(false);
395  }
396 #if FRAME_CONFIG == HELI_FRAME
397  // if helicopters are on the ground, and the motor is switched off, auto-armed should be false
398  // so that rotor runup is checked again before attempting to take-off
399  if(ap.land_complete && !motors->rotor_runup_complete()) {
400  set_auto_armed(false);
401  }
402 #endif // HELI_FRAME
403  }else{
404  // arm checks
405 
406 #if FRAME_CONFIG == HELI_FRAME
407  // for tradheli if motors are armed and throttle is above zero and the motor is started, auto_armed should be true
408  if(motors->armed() && !ap.throttle_zero && motors->rotor_runup_complete()) {
409  set_auto_armed(true);
410  }
411 #else
412  // if motors are armed and throttle is above zero auto_armed should be true
413  // if motors are armed and we are in throw mode, then auto_armed should be true
414  if(motors->armed() && (!ap.throttle_zero || control_mode == THROW)) {
415  set_auto_armed(true);
416  }
417 #endif // HELI_FRAME
418  }
419 }
420 
422 {
423  bool usb_check = hal.gpio->usb_connected();
424  if (usb_check == ap.usb_connected) {
425  return;
426  }
427 
428  // the user has switched to/from the telemetry port
429  ap.usb_connected = usb_check;
430 }
431 
432 /*
433  should we log a message type now?
434  */
435 bool Copter::should_log(uint32_t mask)
436 {
437 #if LOGGING_ENABLED == ENABLED
438  ap.logging_started = DataFlash.logging_started();
439  return DataFlash.should_log(mask);
440 #else
441  return false;
442 #endif
443 }
444 
445 // default frame_class to match firmware if possible
447 {
448  if (FRAME_CONFIG == HELI_FRAME &&
452  }
453 }
454 
455 // return MAV_TYPE corresponding to frame class
457 {
461  return MAV_TYPE_QUADROTOR;
464  return MAV_TYPE_HEXAROTOR;
467  return MAV_TYPE_OCTOROTOR;
471  return MAV_TYPE_HELICOPTER;
473  return MAV_TYPE_TRICOPTER;
477  return MAV_TYPE_COAXIAL;
479  return MAV_TYPE_DODECAROTOR;
480  }
481  // unknown frame so return generic
482  return MAV_TYPE_GENERIC;
483 }
484 
485 // return string corresponding to frame_class
487 {
490  return "QUAD";
492  return "HEXA";
494  return "Y6";
496  return "OCTA";
498  return "OCTA_QUAD";
500  return "HELI";
502  return "HELI_DUAL";
504  return "HELI_QUAD";
506  return "TRI";
508  return "SINGLE";
510  return "COAX";
512  return "TAILSITTER";
514  return "DODECA_HEXA";
516  default:
517  return "UNKNOWN";
518  }
519 }
520 
521 /*
522  allocate the motors class
523  */
525 {
527 #if FRAME_CONFIG != HELI_FRAME
534  default:
535  motors = new AP_MotorsMatrix(copter.scheduler.get_loop_rate_hz());
537  break;
539  motors = new AP_MotorsTri(copter.scheduler.get_loop_rate_hz());
540  motors_var_info = AP_MotorsTri::var_info;
542  break;
544  motors = new AP_MotorsSingle(copter.scheduler.get_loop_rate_hz());
545  motors_var_info = AP_MotorsSingle::var_info;
546  break;
548  motors = new AP_MotorsCoax(copter.scheduler.get_loop_rate_hz());
549  motors_var_info = AP_MotorsCoax::var_info;
550  break;
552  motors = new AP_MotorsTailsitter(copter.scheduler.get_loop_rate_hz());
553  motors_var_info = AP_MotorsTailsitter::var_info;
554  break;
555 #else // FRAME_CONFIG == HELI_FRAME
557  motors = new AP_MotorsHeli_Dual(copter.scheduler.get_loop_rate_hz());
558  motors_var_info = AP_MotorsHeli_Dual::var_info;
560  break;
561 
563  motors = new AP_MotorsHeli_Quad(copter.scheduler.get_loop_rate_hz());
564  motors_var_info = AP_MotorsHeli_Quad::var_info;
566  break;
567 
569  default:
570  motors = new AP_MotorsHeli_Single(copter.scheduler.get_loop_rate_hz());
571  motors_var_info = AP_MotorsHeli_Single::var_info;
573  break;
574 #endif
575  }
576  if (motors == nullptr) {
577  AP_HAL::panic("Unable to allocate FRAME_CLASS=%u", (unsigned)g2.frame_class.get());
578  }
580 
582  if (ahrs_view == nullptr) {
583  AP_HAL::panic("Unable to allocate AP_AHRS_View");
584  }
585 
586  const struct AP_Param::GroupInfo *ac_var_info;
587 
588 #if FRAME_CONFIG != HELI_FRAME
591 #else
593  ac_var_info = AC_AttitudeControl_Heli::var_info;
594 #endif
595  if (attitude_control == nullptr) {
596  AP_HAL::panic("Unable to allocate AttitudeControl");
597  }
599 
601  if (pos_control == nullptr) {
602  AP_HAL::panic("Unable to allocate PosControl");
603  }
605 
607  if (wp_nav == nullptr) {
608  AP_HAL::panic("Unable to allocate WPNav");
609  }
611 
613  if (loiter_nav == nullptr) {
614  AP_HAL::panic("Unable to allocate LoiterNav");
615  }
617 
618 #if MODE_CIRCLE_ENABLED == ENABLED
619  circle_nav = new AC_Circle(inertial_nav, *ahrs_view, *pos_control);
620  if (circle_nav == nullptr) {
621  AP_HAL::panic("Unable to allocate CircleNav");
622  }
624 #endif
625 
626  // reload lines from the defaults file that may now be accessible
628 
629  // now setup some frame-class specific defaults
632  attitude_control->get_rate_roll_pid().kP().set_default(0.1);
633  attitude_control->get_rate_roll_pid().kD().set_default(0.006);
634  attitude_control->get_rate_pitch_pid().kP().set_default(0.1);
635  attitude_control->get_rate_pitch_pid().kD().set_default(0.006);
636  attitude_control->get_rate_yaw_pid().kP().set_default(0.15);
637  attitude_control->get_rate_yaw_pid().kI().set_default(0.015);
638  break;
640  attitude_control->get_rate_yaw_pid().filt_hz().set_default(100);
641  break;
642  default:
643  break;
644  }
645 
646  // brushed 16kHz defaults to 16kHz pulses
647  if (motors->get_pwm_type() == AP_Motors::PWM_TYPE_BRUSHED) {
648  g.rc_speed.set_default(16000);
649  }
650 
652  // do frame specific upgrade. This is only done the first time we run the new firmware
653 #if FRAME_CONFIG == HELI_FRAME
658 #else
660  const AP_Param::ConversionInfo tri_conversion_info[] = {
661  { Parameters::k_param_motors, 32, AP_PARAM_INT16, "SERVO7_TRIM" },
662  { Parameters::k_param_motors, 33, AP_PARAM_INT16, "SERVO7_MIN" },
663  { Parameters::k_param_motors, 34, AP_PARAM_INT16, "SERVO7_MAX" },
664  { Parameters::k_param_motors, 35, AP_PARAM_FLOAT, "MOT_YAW_SV_ANGLE" },
665  };
666  // we need to use CONVERT_FLAG_FORCE as the SERVO7_* parameters will already be set from RC7_*
667  AP_Param::convert_old_parameters(tri_conversion_info, ARRAY_SIZE(tri_conversion_info), AP_Param::CONVERT_FLAG_FORCE);
668  const AP_Param::ConversionInfo tri_conversion_info_rev { Parameters::k_param_motors, 31, AP_PARAM_INT8, "SERVO7_REVERSED" };
670  // AP_MotorsTri was converted from having nested var_info to one level
672  }
673 #endif
674  }
675 
676  // upgrade parameters. This must be done after allocating the objects
678 }
virtual uint32_t available_memory(void)
AC_Loiter * loiter_nav
Definition: Copter.h:495
#define CH_3
AP_DEVO_Telem devo_telemetry
Definition: Copter.h:454
#define HELI_FRAME
Definition: defines.h:84
AP_BoardConfig BoardConfig
Definition: Copter.h:381
AP_Relay relay
Definition: Copter.h:509
void set_dataflash(DataFlash_Class *dataflash)
static void convert_parent_class(uint8_t param_key, void *object_pointer, const struct AP_Param::GroupInfo *group_info)
AP_Int16 sysid_this_mav
Definition: Parameters.h:382
static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel)
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
void set_auto_armed(bool b)
Definition: AP_State.cpp:4
AP_Int8 frame_class
Definition: Parameters.h:560
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
AP_Baro barometer
Definition: Copter.h:234
static const struct AP_Param::GroupInfo var_info[]
virtual void setup_uarts(AP_SerialManager &serial_manager)
AP_Arming_Copter arming
Definition: Copter.h:280
bool upgrading_frame_params
Definition: Copter.h:623
void init(const AP_SerialManager &serial_manager)
AHRS_VEHICLE_COPTER
void set_land_complete_maybe(bool b)
#define FRAME_CONFIG
Definition: config.h:59
#define MASK_LOG_GPS
Definition: defines.h:316
bool have_inertial_nav() const override
AP_VisualOdom visual_odom
Definition: Parameters.h:534
static const struct AP_Param::GroupInfo var_info[]
AP_HAL::UARTDriver * console
void init(void)
AC_Circle * circle_nav
Definition: Copter.h:497
#define CH_1
ROTATION_NONE
void convert_pid_parameters(void)
uint16_t get_loop_rate_hz(void)
void set_channel_mask(uint16_t _mask)
bool logging_started(void)
AP_InertialSensor ins
Definition: Copter.h:236
void init_rangefinder(void)
Definition: sensors.cpp:14
void notify_flight_mode()
Definition: mode.cpp:312
bool should_log(uint32_t mask) const
void init_proximity()
Definition: sensors.cpp:214
MOTOR_FRAME_TAILSITTER
void init_rc_out()
Definition: radio.cpp:52
void init()
float get_loop_period_s()
AC_WPNav * wp_nav
Definition: Copter.h:494
void init(void)
AP_Beacon beacon
Definition: Parameters.h:529
GCS_Copter & gcs()
Definition: Copter.h:301
AP_HAL::Util * util
virtual void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms)
AP_Frsky_Telem frsky_telemetry
Definition: Copter.h:451
void set_log_baro_bit(uint32_t bit)
void init(void)
AP_Int16 rc_speed
Definition: Parameters.h:466
virtual bool usb_connected(void)=0
static const struct AP_Param::GroupInfo var_info[]
bool should_log(uint32_t mask)
Definition: system.cpp:435
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
bool optflow_position_ok()
Definition: system.cpp:344
AP_AHRS_View * create_view(enum Rotation rotation)
void Log_Write_Vehicle_Startup_Messages()
Definition: Log.cpp:524
bool rc_calibration_checks(bool display_failure) override
Definition: AP_Arming.cpp:349
MOTOR_CLASS * motors
Definition: Copter.h:422
AP_LandingGear landinggear
Definition: Copter.h:557
virtual void init()
static const struct AP_Param::GroupInfo var_info[]
void init()
#define CH_4
void heli_init()
void init()
AP_SerialManager serial_manager
Definition: Copter.h:297
bool enabled() const
void set_avoidance(AC_Avoid *avoid_ptr)
static void set_terrain(AP_Terrain *terrain)
#define FUNCTOR_BIND(obj, func, rettype,...)
void init_precland()
void calibrate(bool save=true)
static void set_ahrs(const AP_AHRS_NavEKF *ahrs)
#define MASK_LOG_IMU
Definition: defines.h:321
void init(const AP_SerialManager &serial_manager)
void log_init(void)
Definition: Log.cpp:537
const char * fw_string
uint8_t terrain
Definition: Copter.h:400
virtual void printf(const char *,...) FMT_PRINTF(2
nav_filter_status get_filter_status() const
void reset_control_switch()
Definition: switches.cpp:109
void init_capabilities(void)
Definition: capabilities.cpp:3
void allocate_motors(void)
Definition: system.cpp:524
void update_auto_armed()
Definition: system.cpp:383
void init(bool enable_external_leds)
bool enabled
Definition: Copter.h:240
static const struct AP_Param::GroupInfo var_info[]
AP_Mount camera_mount
Definition: Copter.h:522
AP_RPM rpm_sensor
Definition: Copter.h:249
void init_optflow()
Definition: sensors.cpp:128
static const struct AP_Param::GroupInfo var_info[]
void load_parameters(void)
const char * get_frame_string()
Definition: system.cpp:486
Mode * flightmode
Definition: Copter.h:955
void init(void)
AP_BattMonitor battery
Definition: Copter.h:445
AP_RSSI rssi
Definition: Copter.h:544
void reset(bool recover_eulers=false) override
void set_mission(const AP_Mission *mission)
void init(const AP_SerialManager &serial_manager)
void update_using_interlock()
Definition: AP_State.cpp:81
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
void init_compass()
Definition: sensors.cpp:90
AP_PARAM_INT8
AP_Notify notify
Definition: Copter.h:215
void init_aux_switches()
Definition: switches.cpp:158
MAV_TYPE get_frame_mav_type()
Definition: system.cpp:456
void set_vehicle_class(AHRS_VehicleClass vclass)
void set_dt(float delta_sec)
GCS_MAVLINK_Copter & chan(const uint8_t ofs) override
Definition: GCS_Copter.h:16
static const AP_FWVersion fwver
Definition: Copter.h:202
void init()
void set_optflow(const OpticalFlow *optflow)
CONVERT_FLAG_REVERSE
#define CH_2
static void set_frame_type_flags(uint16_t flags_to_set)
Definition: defines.h:107
void init_rc_in()
Definition: radio.cpp:22
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
#define ARRAY_SIZE(_arr)
static void mavlink_delay_cb_static()
Definition: system.cpp:10
void set_log_gps_bit(uint32_t bit)
void set_land_complete(bool b)
static const struct AP_Param::GroupInfo var_info[]
DataFlash_Class DataFlash
Definition: Copter.h:227
AP_PARAM_FLOAT
void report_version()
Definition: setup.cpp:76
AP_GPS gps
Definition: Copter.h:229
struct nav_filter_status::@138 flags
AP_Scheduler scheduler
Definition: Copter.h:212
virtual void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)=0
Parameters g
Definition: Copter.h:208
static void reload_defaults_file(bool panic_on_error=true)
AP_Stats stats
Definition: Parameters.h:508
AP_ServoRelayEvents ServoRelayEvents
Definition: Copter.h:512
static const struct AP_Param::GroupInfo var_info[]
void set_avoidance(AC_Avoid *avoid_ptr)
void init(uint16_t sample_rate_hz)
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
AP_HAL::GPIO * gpio
struct Copter::@2 failsafe
AC_PosControl * pos_control
Definition: Copter.h:493
AC_Avoid avoid
Definition: Copter.h:532
bool position_ok()
Definition: system.cpp:312
void set_beacon(AP_Beacon *beacon)
int snprintf(char *str, size_t size, const char *fmt,...)
static const struct AP_Param::GroupInfo var_info[]
virtual bool has_manual_throttle() const =0
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0)
void init_visual_odom()
Definition: sensors.cpp:425
void set_log_raw_bit(uint32_t log_raw_bit)
MOTOR_FRAME_DODECAHEXA
static void failsafe_check_static()
Definition: system.cpp:16
OpticalFlow optflow
Definition: Copter.h:284
ParametersG2 g2
Definition: Copter.h:209
void set_blocking_writes_all(bool blocking)
void startup_INS_ground()
Definition: system.cpp:298
void panic(const char *errormsg,...) FMT_PRINTF(1
void set_default_frame_class()
Definition: system.cpp:446
AP_PARAM_INT16
void init_safety(void)
void set_terrain(AP_Terrain *terrain_ptr)
control_mode_t control_mode
Definition: Copter.h:345
#define MASK_LOG_IMU_RAW
Definition: defines.h:332
#define AP_PARAM_FRAME_TRICOPTER
void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, const uint32_t *ap_valuep=nullptr)
void enable_motor_output()
Definition: radio.cpp:88
bool enabled() const
uint32_t get_last_update(void) const
#define AP_PARAM_FRAME_HELI
AP_Mission mission
Definition: Copter.h:263
AP_SmartRTL smart_rtl
Definition: Parameters.h:570
AP_Vehicle::MultiCopter aparm
Definition: Copter.h:205
void winch_init()
Definition: sensors.cpp:456
AP_HAL::Scheduler * scheduler
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0)
bool ekf_position_ok()
Definition: system.cpp:324
void delay(uint32_t ms)
Definition: compat.cpp:3
float G_Dt
Definition: Copter.h:480
void failsafe_enable()
Definition: failsafe.cpp:18
void set_hil_mode(void)
void init_ardupilot()
Definition: system.cpp:21
void check_usb_mux(void)
Definition: system.cpp:421
static const struct AP_Param::GroupInfo var_info[]
const struct AP_Param::GroupInfo * motors_var_info
Definition: Copter.h:423