2015-05-29 23:12:49 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2016-05-05 19:10:08 -03:00
# pragma once
2015-05-29 23:12:49 -03:00
/*
This is the main Copter class
*/
////////////////////////////////////////////////////////////////////////////////
// Header includes
////////////////////////////////////////////////////////////////////////////////
2016-03-31 18:43:36 -03:00
# include <cmath>
2015-05-29 23:12:49 -03:00
# include <stdio.h>
# include <stdarg.h>
2015-10-19 15:25:33 -03:00
# include <AP_HAL/AP_HAL.h>
2015-05-29 23:12:49 -03:00
// Common dependencies
2021-06-29 08:44:10 -03:00
# include <AP_Common/AP_Common.h> // Common definitions and utility routines for the ArduPilot libraries
# include <AP_Common/Location.h> // Library having the implementation of location class
# include <AP_Param/AP_Param.h> // A system for managing and storing variables that are of general interest to the system.
# include <StorageManager/StorageManager.h> // library for Management for hal.storage to allow for backwards compatible mapping of storage offsets to available storage
2015-05-29 23:12:49 -03:00
// Application dependencies
2021-06-29 08:44:10 -03:00
# include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
# include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
# include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
# include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
# include <AP_AHRS/AP_AHRS.h> // AHRS (Attitude Heading Reference System) interface library for ArduPilot
# include <AP_Mission/AP_Mission.h> // Mission command library
2022-01-07 21:25:10 -04:00
# include <AP_Mission/AP_Mission_ChangeDetector.h> // Mission command change detection library
2021-06-29 08:44:10 -03:00
# include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
# include <AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h> // 6DoF Attitude control library
# include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
# include <AC_AttitudeControl/AC_PosControl.h> // Position control library
2022-06-15 00:08:53 -03:00
# include <AC_AttitudeControl/AC_CommandModel.h> // Command model library
2021-06-29 08:44:10 -03:00
# include <AP_Motors/AP_Motors.h> // AP Motors library
# include <AP_Stats/AP_Stats.h> // statistics library
# include <Filter/Filter.h> // Filter library
# include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
2021-10-18 23:15:00 -03:00
# include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
2021-06-29 08:44:10 -03:00
# include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
# include <AC_WPNav/AC_Loiter.h> // ArduCopter Loiter Mode Library
# include <AC_WPNav/AC_Circle.h> // circle navigation library
# include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
2015-08-11 03:28:40 -03:00
# include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
2021-06-29 08:44:10 -03:00
# include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
# include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
2016-01-20 20:38:39 -04:00
# include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
# include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
2021-06-29 08:44:10 -03:00
# include <AP_Arming/AP_Arming.h> // ArduPilot motor arming library
# include <AP_SmartRTL/AP_SmartRTL.h> // ArduPilot Smart Return To Launch Mode (SRTL) library
# include <AP_TempCalibration/AP_TempCalibration.h> // temperature calibration library
2020-05-02 01:21:22 -03:00
# include <AC_AutoTune/AC_AutoTune_Multi.h> // ArduCopter autotune library. support for autotune of multirotors.
# include <AC_AutoTune/AC_AutoTune_Heli.h> // ArduCopter autotune library. support for autotune of helicopters.
2021-06-29 08:44:10 -03:00
# include <AP_Parachute/AP_Parachute.h> // ArduPilot parachute release library
# include <AC_Sprayer/AC_Sprayer.h> // Crop sprayer library
# include <AP_ADSB/AP_ADSB.h> // ADS-B RF based collision avoidance module library
# include <AP_Proximity/AP_Proximity.h> // ArduPilot proximity sensor library
2016-01-20 20:38:39 -04:00
// Configuration
# include "defines.h"
# include "config.h"
2019-09-07 20:33:56 -03:00
# if FRAME_CONFIG == HELI_FRAME
# define AC_AttitudeControl_t AC_AttitudeControl_Heli
# else
# define AC_AttitudeControl_t AC_AttitudeControl_Multi
# endif
# if FRAME_CONFIG == HELI_FRAME
# define MOTOR_CLASS AP_MotorsHeli
# else
# define MOTOR_CLASS AP_MotorsMulticopter
# endif
2019-11-28 16:21:07 -04:00
# if MODE_AUTOROTATE_ENABLED == ENABLED
# include <AC_Autorotation/AC_Autorotation.h> // Autorotation controllers
# endif
2018-06-04 00:06:32 -03:00
# include "RC_Channel.h" // RC Channel Library
2016-05-27 09:59:22 -03:00
# include "GCS_Mavlink.h"
2017-02-13 22:14:55 -04:00
# include "GCS_Copter.h"
2016-07-19 19:52:56 -03:00
# include "AP_Rally.h" // Rally point library
2016-12-26 04:05:08 -04:00
# include "AP_Arming.h"
2016-05-27 09:59:22 -03:00
2016-01-20 20:38:39 -04:00
// libraries which are dependent on #defines in defines.h and/or config.h
2018-02-28 07:18:10 -04:00
# if BEACON_ENABLED == ENABLED
# include <AP_Beacon/AP_Beacon.h>
# endif
2019-11-28 16:21:07 -04:00
2018-02-28 07:18:10 -04:00
# if AC_AVOID_ENABLED == ENABLED
# include <AC_Avoidance/AC_Avoid.h>
# endif
2019-06-05 07:47:32 -03:00
# if AC_OAPATHPLANNER_ENABLED == ENABLED
# include <AC_WPNav/AC_WPNav_OA.h>
# include <AC_Avoidance/AP_OAPathPlanner.h>
# endif
2022-09-20 04:37:48 -03:00
# include <AP_Gripper/AP_Gripper_config.h>
# if AP_GRIPPER_ENABLED
2018-02-21 08:53:33 -04:00
# include <AP_Gripper / AP_Gripper.h>
2016-10-28 19:08:22 -03:00
# endif
2015-02-16 00:39:18 -04:00
# if PRECISION_LANDING == ENABLED
2018-02-21 08:53:33 -04:00
# include <AC_PrecLand / AC_PrecLand.h>
2021-07-21 16:33:37 -03:00
# include <AC_PrecLand / AC_PrecLand_StateMachine.h>
2015-02-16 00:39:18 -04:00
# endif
2018-02-06 02:16:09 -04:00
# if MODE_FOLLOW_ENABLED == ENABLED
# include <AP_Follow / AP_Follow.h>
# endif
2021-02-12 23:40:10 -04:00
# if AP_TERRAIN_AVAILABLE
2018-02-21 08:53:33 -04:00
# include <AP_Terrain / AP_Terrain.h>
2018-02-16 12:49:27 -04:00
# endif
2018-02-21 08:53:33 -04:00
# include <AP_OpticalFlow / AP_OpticalFlow.h>
2018-02-16 12:49:27 -04:00
# if RANGEFINDER_ENABLED == ENABLED
2018-02-21 08:53:33 -04:00
# include <AP_RangeFinder / AP_RangeFinder.h>
2018-02-16 12:49:27 -04:00
# endif
2020-07-24 14:02:40 -03:00
# include <AP_Mount/AP_Mount.h>
2022-06-02 05:28:26 -03:00
# include <AP_Camera/AP_Camera.h>
2021-08-12 00:38:21 -03:00
# if HAL_BUTTON_ENABLED
2019-10-06 10:59:15 -03:00
# include <AP_Button / AP_Button.h>
# endif
2018-03-04 05:41:06 -04:00
2020-10-19 17:31:18 -03:00
# if OSD_ENABLED || OSD_PARAM_ENABLED
2018-06-23 04:11:05 -03:00
# include <AP_OSD/AP_OSD.h>
# endif
2016-08-16 07:23:27 -03:00
# if ADVANCED_FAILSAFE == ENABLED
2018-02-21 08:53:33 -04:00
# include "afs_copter.h"
2016-08-16 07:23:27 -03:00
# endif
2018-01-18 02:49:20 -04:00
# if TOY_MODE_ENABLED == ENABLED
2018-02-21 08:53:33 -04:00
# include "toy_mode.h"
2018-01-18 02:49:20 -04:00
# endif
2018-02-10 10:23:06 -04:00
# if WINCH_ENABLED == ENABLED
2018-02-21 08:53:33 -04:00
# include <AP_Winch / AP_Winch.h>
2018-02-10 10:23:06 -04:00
# endif
2022-07-15 20:59:12 -03:00
# include <AP_RPM/AP_RPM.h>
2018-02-10 10:23:06 -04:00
2021-11-15 01:08:33 -04:00
# if AP_SCRIPTING_ENABLED
2019-03-01 02:40:53 -04:00
# include <AP_Scripting/AP_Scripting.h>
# endif
2022-07-16 22:49:47 -03:00
# if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
# include <AC_CustomControl/AC_CustomControl.h> // Custom control library
# endif
2022-03-04 12:36:07 -04:00
# if AC_AVOID_ENABLED && !AP_FENCE_ENABLED
# error AC_Avoidance relies on AP_FENCE_ENABLED which is disabled
# endif
# if AC_OAPATHPLANNER_ENABLED && !AP_FENCE_ENABLED
# error AP_OAPathPlanner relies on AP_FENCE_ENABLED which is disabled
# endif
2015-05-29 23:12:49 -03:00
// Local modules
2018-08-21 10:02:40 -03:00
# ifdef USER_PARAMS_ENABLED
# include "UserParameters.h"
# endif
2015-05-29 23:12:49 -03:00
# include "Parameters.h"
2020-09-19 05:37:52 -03:00
# if HAL_ADSB_ENABLED
2016-07-21 09:44:09 -03:00
# include "avoidance_adsb.h"
2018-02-16 10:21:55 -04:00
# endif
2015-05-29 23:12:49 -03:00
2019-05-09 23:18:49 -03:00
# include "mode.h"
2016-08-16 07:23:27 -03:00
2018-12-27 02:34:09 -04:00
class Copter : public AP_Vehicle {
2015-10-19 15:25:33 -03:00
public :
2016-05-27 09:59:22 -03:00
friend class GCS_MAVLINK_Copter ;
2017-02-13 22:14:55 -04:00
friend class GCS_Copter ;
2016-07-19 19:52:56 -03:00
friend class AP_Rally_Copter ;
2015-05-29 23:12:49 -03:00
friend class Parameters ;
2016-08-16 07:23:27 -03:00
friend class ParametersG2 ;
2016-07-21 09:44:09 -03:00
friend class AP_Avoidance_Copter ;
2018-03-13 21:23:30 -03:00
2016-08-16 07:23:27 -03:00
# if ADVANCED_FAILSAFE == ENABLED
friend class AP_AdvancedFailsafe_Copter ;
# endif
2017-01-09 03:45:48 -04:00
friend class AP_Arming_Copter ;
2018-01-18 02:49:20 -04:00
friend class ToyMode ;
2018-06-04 00:06:32 -03:00
friend class RC_Channel_Copter ;
friend class RC_Channels_Copter ;
2015-05-29 23:12:49 -03:00
2019-05-09 23:18:49 -03:00
friend class AutoTune ;
friend class Mode ;
friend class ModeAcro ;
friend class ModeAcro_Heli ;
friend class ModeAltHold ;
friend class ModeAuto ;
friend class ModeAutoTune ;
friend class ModeAvoidADSB ;
friend class ModeBrake ;
friend class ModeCircle ;
friend class ModeDrift ;
friend class ModeFlip ;
friend class ModeFlowHold ;
friend class ModeFollow ;
friend class ModeGuided ;
friend class ModeLand ;
friend class ModeLoiter ;
friend class ModePosHold ;
friend class ModeRTL ;
friend class ModeSmartRTL ;
friend class ModeSport ;
friend class ModeStabilize ;
friend class ModeStabilize_Heli ;
2019-07-29 04:55:40 -03:00
friend class ModeSystemId ;
2019-05-09 23:18:49 -03:00
friend class ModeThrow ;
friend class ModeZigZag ;
2019-11-28 16:21:07 -04:00
friend class ModeAutorotate ;
2021-07-27 16:51:19 -03:00
friend class ModeTurtle ;
2019-05-09 23:18:49 -03:00
2015-05-29 23:12:49 -03:00
Copter ( void ) ;
2015-10-19 15:25:33 -03:00
2015-05-29 23:12:49 -03:00
private :
2017-08-18 19:45:02 -03:00
2015-05-29 23:12:49 -03:00
// key aircraft parameters passed to multiple libraries
AP_Vehicle : : MultiCopter aparm ;
// Global parameters are all contained within the 'g' class.
Parameters g ;
2016-06-04 23:37:55 -03:00
ParametersG2 g2 ;
2015-05-29 23:12:49 -03:00
// used to detect MAVLink acks from GCS to stop compassmot
uint8_t command_ack_counter ;
// primary input control channels
RC_Channel * channel_roll ;
RC_Channel * channel_pitch ;
RC_Channel * channel_throttle ;
RC_Channel * channel_yaw ;
2019-01-18 00:23:42 -04:00
AP_Logger logger ;
2015-05-29 23:12:49 -03:00
// flight modes convenience array
AP_Int8 * flight_modes ;
2018-06-04 00:06:32 -03:00
const uint8_t num_flight_modes = 6 ;
2015-05-29 23:12:49 -03:00
2019-08-23 22:59:22 -03:00
struct RangeFinderState {
2016-05-07 04:55:40 -03:00
bool enabled : 1 ;
bool alt_healthy : 1 ; // true if we can trust the altitude from the rangefinder
int16_t alt_cm ; // tilt compensated altitude (in cm) from rangefinder
2020-02-18 18:22:31 -04:00
float inertial_alt_cm ; // inertial alt at time of last rangefinder sample
2016-04-28 00:30:41 -03:00
uint32_t last_healthy_ms ;
LowPassFilterFloat alt_cm_filt ; // altitude filter
2019-08-22 09:05:45 -03:00
int16_t alt_cm_glitch_protected ; // last glitch protected altitude
int8_t glitch_count ; // non-zero number indicates rangefinder is glitching
uint32_t glitch_cleared_ms ; // system time glitch cleared
2019-08-23 22:59:22 -03:00
} rangefinder_state , rangefinder_up_state ;
2015-05-29 23:12:49 -03:00
2022-06-15 00:24:26 -03:00
// return rangefinder height interpolated using inertial altitude
bool get_rangefinder_height_interpolated_cm ( int32_t & ret ) const ;
2020-02-18 18:22:31 -04:00
2019-06-11 00:13:24 -03:00
class SurfaceTracking {
public :
2021-08-31 01:17:59 -03:00
// update_surface_offset - manages the vertical offset of the position controller to follow the
// measured ground or ceiling level measured using the range finder.
void update_surface_offset ( ) ;
2019-08-22 02:22:30 -03:00
// get/set target altitude (in cm) above ground
2019-06-11 00:13:24 -03:00
bool get_target_alt_cm ( float & target_alt_cm ) const ;
void set_target_alt_cm ( float target_alt_cm ) ;
2019-08-22 02:22:30 -03:00
2019-08-23 22:59:22 -03:00
// get target and actual distances (in m) for logging purposes
2019-11-10 23:55:43 -04:00
bool get_target_dist_for_logging ( float & target_dist ) const ;
float get_dist_for_logging ( ) const ;
2019-08-22 02:22:30 -03:00
void invalidate_for_logging ( ) { valid_for_logging = false ; }
2019-06-11 00:13:24 -03:00
2019-10-25 08:31:31 -03:00
// surface tracking surface
enum class Surface {
NONE = 0 ,
GROUND = 1 ,
CEILING = 2
2019-08-23 22:59:22 -03:00
} ;
2019-10-25 08:31:31 -03:00
// set surface to track
void set_surface ( Surface new_surface ) ;
2021-10-13 11:13:03 -03:00
// initialise surface tracking
void init ( Surface surf ) { surface = surf ; }
2019-08-23 22:59:22 -03:00
2019-06-11 00:13:24 -03:00
private :
2021-10-13 11:13:03 -03:00
Surface surface ;
2019-04-11 00:20:43 -03:00
uint32_t last_update_ms ; // system time of last update to target_alt_cm
2019-08-22 09:05:45 -03:00
uint32_t last_glitch_cleared_ms ; // system time of last handle glitch recovery
2021-11-09 06:49:15 -04:00
bool valid_for_logging ; // true if we have a desired target altitude
bool reset_target ; // true if target should be reset because of change in surface being tracked
2019-04-11 00:20:43 -03:00
} surface_tracking ;
2022-07-15 20:59:12 -03:00
# if AP_RPM_ENABLED
2017-12-12 21:06:15 -04:00
AP_RPM rpm_sensor ;
2018-03-29 10:49:27 -03:00
# endif
2015-08-07 02:34:56 -03:00
2019-11-24 19:19:29 -04:00
// Inertial Navigation EKF - different viewpoint
2018-12-12 23:53:56 -04:00
AP_AHRS_View * ahrs_view ;
2015-05-29 23:12:49 -03:00
2019-03-25 20:57:55 -03:00
// Arming/Disarming management class
2018-06-25 00:42:17 -03:00
AP_Arming_Copter arming ;
2017-01-09 03:45:48 -04:00
2015-05-29 23:12:49 -03:00
// Optical flow sensor
2021-12-24 01:47:22 -04:00
# if AP_OPTICALFLOW_ENABLED
2022-08-14 22:31:14 -03:00
AP_OpticalFlow optflow ;
2015-05-29 23:12:49 -03:00
# endif
2015-09-24 03:57:22 -03:00
// system time in milliseconds of last recorded yaw reset from ekf
2018-02-22 00:30:48 -04:00
uint32_t ekfYawReset_ms ;
2016-10-13 03:20:16 -03:00
int8_t ekf_primary_core ;
2015-09-17 19:01:27 -03:00
2019-03-21 06:51:35 -03:00
// vibration check
struct {
bool high_vibes ; // true while high vibration are detected
uint32_t start_ms ; // system time high vibration were last detected
uint32_t clear_ms ; // system time high vibrations stopped
} vibration_check ;
2022-06-28 08:19:10 -03:00
// takeoff check
uint32_t takeoff_check_warning_ms ; // system time user was last warned of takeoff check failure
2015-05-29 23:12:49 -03:00
// GCS selection
2017-02-13 22:14:55 -04:00
GCS_Copter _gcs ; // avoid using this; use gcs()
GCS_Copter & gcs ( ) { return _gcs ; }
2015-05-29 23:12:49 -03:00
// User variables
# ifdef USERHOOK_VARIABLES
# include USERHOOK_VARIABLES
# endif
// Documentation of GLobals:
2016-08-24 01:28:55 -03:00
typedef union {
2015-05-29 23:12:49 -03:00
struct {
2016-01-21 21:56:10 -04:00
uint8_t unused1 : 1 ; // 0
2020-06-15 10:05:09 -03:00
uint8_t unused_was_simple_mode : 2 ; // 1,2
2016-01-21 21:56:10 -04:00
uint8_t pre_arm_rc_check : 1 ; // 3 // true if rc input pre-arm checks have been completed successfully
uint8_t pre_arm_check : 1 ; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
uint8_t auto_armed : 1 ; // 5 // stops auto missions from beginning until throttle is raised
2019-02-11 04:11:20 -04:00
uint8_t logging_started : 1 ; // 6 // true if logging has started
2016-01-21 21:56:10 -04:00
uint8_t land_complete : 1 ; // 7 // true if we have detected a landing
uint8_t new_radio_frame : 1 ; // 8 // Set true if we have new PWM data to act on from the Radio
2018-06-19 21:33:37 -03:00
uint8_t usb_connected_unused : 1 ; // 9 // UNUSED
2016-01-21 21:56:10 -04:00
uint8_t rc_receiver_present : 1 ; // 10 // true if we have an rc receiver present (i.e. if we've ever received an update
uint8_t compass_mot : 1 ; // 11 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1 ; // 12 // true if we are currently performing the motors test
uint8_t initialised : 1 ; // 13 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1 ; // 14 // true if we may have landed (less strict version of land_complete)
uint8_t throttle_zero : 1 ; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
2018-03-09 12:14:51 -04:00
uint8_t system_time_set_unused : 1 ; // 16 // true if the system time has been set from the GPS
2018-03-26 06:16:35 -03:00
uint8_t gps_glitching : 1 ; // 17 // true if GPS glitching is affecting navigation accuracy
2016-01-21 21:56:10 -04:00
uint8_t using_interlock : 1 ; // 20 // aux switch motor interlock function is in use
2019-01-25 14:57:36 -04:00
uint8_t land_repo_active : 1 ; // 21 // true if the pilot is overriding the landing position
uint8_t motor_interlock_switch : 1 ; // 22 // true if pilot is requesting motor interlock enable
uint8_t in_arming_delay : 1 ; // 23 // true while we are armed but waiting to spin motors
uint8_t initialised_params : 1 ; // 24 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
2020-02-18 12:04:26 -04:00
uint8_t unused3 : 1 ; // 25 // was compass_init_location; true when the compass's initial location has been set
2019-01-25 14:57:36 -04:00
uint8_t unused2 : 1 ; // 26 // aux switch rc_override is allowed
2021-09-13 21:08:28 -03:00
uint8_t armed_with_airmode_switch : 1 ; // 27 // we armed using a arming switch
2021-09-05 17:07:57 -03:00
uint8_t prec_land_active : 1 ; // 28 // true if precland is active
2015-05-29 23:12:49 -03:00
} ;
uint32_t value ;
2016-08-24 01:28:55 -03:00
} ap_t ;
ap_t ap ;
2015-05-29 23:12:49 -03:00
2022-01-24 19:38:32 -04:00
AirMode air_mode ; // air mode is 0 = not-configured ; 1 = disabled; 2 = enabled;
bool force_flying ; // force flying is enabled when true;
2020-05-24 08:26:00 -03:00
2018-03-09 12:14:51 -04:00
static_assert ( sizeof ( uint32_t ) = = sizeof ( ap ) , " ap_t must be uint32_t " ) ;
2015-05-29 23:12:49 -03:00
// This is the state of the flight control system
// There are multiple states defined such as STABILIZE, ACRO,
2020-01-30 03:29:36 -04:00
Mode * flightmode ;
2019-09-07 20:33:56 -03:00
Mode : : Number prev_control_mode ;
2016-01-26 20:08:45 -04:00
2017-12-12 21:06:15 -04:00
RCMapper rcmap ;
2015-05-29 23:12:49 -03:00
2021-01-06 11:19:23 -04:00
// inertial nav alt when we armed
2018-01-18 02:49:20 -04:00
float arming_altitude_m ;
2018-03-09 12:14:51 -04:00
2015-05-29 23:12:49 -03:00
// Failsafe
struct {
2016-04-22 08:37:48 -03:00
uint32_t terrain_first_failure_ms ; // the first time terrain data access failed - used to calculate the duration of the failure
uint32_t terrain_last_failure_ms ; // the most recent time terrain data access failed
2018-02-28 19:32:16 -04:00
int8_t radio_counter ; // number of iterations with throttle below throttle_fs_value
uint8_t radio : 1 ; // A status flag for the radio failsafe
uint8_t gcs : 1 ; // A status flag for the ground station failsafe
uint8_t ekf : 1 ; // true if ekf failsafe has occurred
uint8_t terrain : 1 ; // true if the missing terrain data failsafe has occurred
uint8_t adsb : 1 ; // true if an adsb related failsafe has occurred
2022-05-10 23:17:13 -03:00
uint8_t deadreckon : 1 ; // true if a dead reckoning failsafe has triggered
2015-05-29 23:12:49 -03:00
} failsafe ;
2018-03-22 05:50:24 -03:00
bool any_failsafe_triggered ( ) const {
2022-05-10 23:17:13 -03:00
return failsafe . radio | | battery . has_failsafed ( ) | | failsafe . gcs | | failsafe . ekf | | failsafe . terrain | | failsafe . adsb | | failsafe . deadreckon ;
2018-03-22 05:50:24 -03:00
}
2022-05-10 23:17:13 -03:00
// dead reckoning state
struct {
bool active ; // true if dead reckoning (position estimate using estimated airspeed, no position or velocity source)
bool timeout ; // true if dead reckoning has timedout and EKF's position and velocity estimate should no longer be trusted
uint32_t start_ms ; // system time that EKF began deadreckoning
} dead_reckoning ;
2015-05-29 23:12:49 -03:00
// Motor Output
2017-01-09 03:31:26 -04:00
MOTOR_CLASS * motors ;
2017-03-14 06:47:18 -03:00
const struct AP_Param : : GroupInfo * motors_var_info ;
2015-05-29 23:12:49 -03:00
2017-12-05 23:34:33 -04:00
int32_t _home_bearing ;
uint32_t _home_distance ;
2015-05-29 23:12:49 -03:00
// SIMPLE Mode
2017-11-27 08:07:50 -04:00
// Used to track the orientation of the vehicle for Simple mode. This value is reset at each arming
// or in SuperSimple mode when the vehicle leaves a 20m radius from home.
2020-06-15 10:05:09 -03:00
enum class SimpleMode {
NONE = 0 ,
SIMPLE = 1 ,
SUPERSIMPLE = 2 ,
} simple_mode ;
2015-05-29 23:12:49 -03:00
float simple_cos_yaw ;
float simple_sin_yaw ;
int32_t super_simple_last_bearing ;
float super_simple_cos_yaw ;
float super_simple_sin_yaw ;
// Stores initial bearing when armed - initial simple bearing is modified in super simple mode so not suitable
int32_t initial_armed_bearing ;
// Battery Sensors
2018-02-28 19:32:16 -04:00
AP_BattMonitor battery { MASK_LOG_CURRENT ,
FUNCTOR_BIND_MEMBER ( & Copter : : handle_battery_failsafe , void , const char * , const int8_t ) ,
_failsafe_priorities } ;
2015-05-29 23:12:49 -03:00
2020-10-19 17:31:18 -03:00
# if OSD_ENABLED || OSD_PARAM_ENABLED
2018-06-23 04:34:25 -03:00
AP_OSD osd ;
# endif
2017-08-29 14:44:54 -03:00
2015-05-29 23:12:49 -03:00
// Altitude
int32_t baro_alt ; // barometer altitude in cm above home
2015-06-17 08:37:15 -03:00
LowPassFilterVector3f land_accel_ef_filter ; // accelerations for land and crash detector tests
2015-05-29 23:12:49 -03:00
2016-01-14 01:47:26 -04:00
// filtered pilot's throttle input used to cancel landing if throttle held high
2016-01-06 17:39:36 -04:00
LowPassFilterFloat rc_throttle_control_in_filter ;
2015-05-29 23:12:49 -03:00
// 3D Location vectors
2017-11-27 08:07:50 -04:00
// Current location of the vehicle (altitude is relative to home)
2019-01-01 22:54:31 -04:00
Location current_loc ;
2015-05-29 23:12:49 -03:00
// Inertial Navigation
2021-10-18 23:15:00 -03:00
AP_InertialNav inertial_nav ;
2015-05-29 23:12:49 -03:00
// Attitude, Position and Waypoint navigation objects
// To-Do: move inertial nav up or other navigation variables down here
2016-03-21 01:33:42 -03:00
AC_AttitudeControl_t * attitude_control ;
2017-01-09 03:31:26 -04:00
AC_PosControl * pos_control ;
AC_WPNav * wp_nav ;
2018-03-27 23:13:37 -03:00
AC_Loiter * loiter_nav ;
2019-11-28 16:21:07 -04:00
2022-07-16 22:49:47 -03:00
# if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
AC_CustomControl custom_control { ahrs_view , attitude_control , motors , scheduler . get_loop_period_s ( ) } ;
# endif
2018-02-23 05:51:17 -04:00
# if MODE_CIRCLE_ENABLED == ENABLED
2017-01-09 03:31:26 -04:00
AC_Circle * circle_nav ;
2018-02-23 05:51:17 -04:00
# endif
2015-05-29 23:12:49 -03:00
// System Timers
// --------------
2016-01-21 22:59:47 -04:00
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
uint32_t arm_time_ms ;
2015-05-29 23:12:49 -03:00
// Used to exit the roll and pitch auto trim function
uint8_t auto_trim_counter ;
2020-06-03 00:28:04 -03:00
bool auto_trim_started = false ;
2015-05-29 23:12:49 -03:00
2017-08-29 15:49:08 -03:00
// Camera
2022-06-02 05:28:26 -03:00
# if AP_CAMERA_ENABLED
2019-03-26 08:06:32 -03:00
AP_Camera camera { MASK_LOG_CAMERA } ;
2015-05-29 23:12:49 -03:00
# endif
// Camera/Antenna mount tracking and stabilisation stuff
2020-07-24 14:02:40 -03:00
# if HAL_MOUNT_ENABLED
2019-03-26 08:36:55 -03:00
AP_Mount camera_mount ;
2015-05-29 23:12:49 -03:00
# endif
2017-01-02 20:36:26 -04:00
# if AC_AVOID_ENABLED == ENABLED
2019-05-22 03:04:18 -03:00
AC_Avoid avoid ;
2017-01-02 20:36:26 -04:00
# endif
2017-08-29 20:28:35 -03:00
2015-05-29 23:12:49 -03:00
// Rally library
2022-09-21 10:13:20 -03:00
# if HAL_RALLY_ENABLED
2019-02-18 05:38:37 -04:00
AP_Rally_Copter rally ;
2015-05-29 23:12:49 -03:00
# endif
// Crop Sprayer
2018-04-13 23:16:11 -03:00
# if SPRAYER_ENABLED == ENABLED
2018-04-11 08:07:29 -03:00
AC_Sprayer sprayer ;
2015-05-29 23:12:49 -03:00
# endif
// Parachute release
# if PARACHUTE == ENABLED
2017-12-12 21:06:15 -04:00
AP_Parachute parachute { relay } ;
2015-05-29 23:12:49 -03:00
# endif
// Landing Gear Controller
2021-02-06 23:29:33 -04:00
# if LANDING_GEAR_ENABLED == ENABLED
2017-12-12 21:06:15 -04:00
AP_LandingGear landinggear ;
2021-02-06 23:29:33 -04:00
# endif
2015-05-29 23:12:49 -03:00
// terrain handling
2022-02-01 23:28:34 -04:00
# if AP_TERRAIN_AVAILABLE
AP_Terrain terrain ;
2015-05-29 23:12:49 -03:00
# endif
2015-02-16 00:39:18 -04:00
// Precision Landing
# if PRECISION_LANDING == ENABLED
2018-07-15 21:30:08 -03:00
AC_PrecLand precland ;
2021-07-21 16:33:37 -03:00
AC_PrecLand_StateMachine precland_statemachine ;
2015-02-16 00:39:18 -04:00
# endif
2015-10-12 11:27:26 -03:00
// Pilot Input Management Library
2017-08-29 21:18:40 -03:00
// Only used for Helicopter for now
2015-10-12 11:27:26 -03:00
# if FRAME_CONFIG == HELI_FRAME
2017-12-12 21:06:15 -04:00
AC_InputManager_Heli input_manager ;
2015-10-12 11:27:26 -03:00
# endif
2020-09-19 05:37:52 -03:00
# if HAL_ADSB_ENABLED
2018-01-01 16:41:46 -04:00
AP_ADSB adsb ;
2015-11-25 19:22:21 -04:00
2017-11-27 08:07:50 -04:00
// avoidance of adsb enabled vehicles (normally manned vehicles)
2019-07-09 03:05:42 -03:00
AP_Avoidance_Copter avoidance_adsb { adsb } ;
2018-02-16 10:21:55 -04:00
# endif
2016-07-21 09:44:09 -03:00
2016-08-16 07:23:27 -03:00
// last valid RC input time
uint32_t last_radio_update_ms ;
2017-03-01 07:18:11 -04:00
2017-05-09 03:57:40 -03:00
// last esc calibration notification update
uint32_t esc_calibration_notify_update_ms ;
2015-05-29 23:12:49 -03:00
// Top-level logic
// setup the var_info table
AP_Param param_loader ;
2015-05-31 19:10:30 -03:00
# if FRAME_CONFIG == HELI_FRAME
// Mode filter to reject RC Input glitches. Filter size is 5, and it draws the 4th element, so it can reject 3 low glitches,
// and 1 high glitch. This is because any "off" glitches can be highly problematic for a helicopter running an ESC
// governor. Even a single "off" frame can cause the rotor to slow dramatically and take a long time to restart.
ModeFilterInt16_Size5 rotor_speed_deglitch_filter { 4 } ;
// Tradheli flags
2017-11-09 21:09:27 -04:00
typedef struct {
2015-05-31 19:10:30 -03:00
uint8_t dynamic_flight : 1 ; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
2019-02-28 05:03:00 -04:00
uint8_t inverted_flight : 1 ; // 1 // true for inverted flight mode
2019-11-28 16:21:07 -04:00
uint8_t in_autorotation : 1 ; // 2 // true when heli is in autorotation
2021-10-29 13:17:45 -03:00
bool coll_stk_low ; // 3 // true when collective stick is on lower limit
2017-11-09 21:09:27 -04:00
} heli_flags_t ;
heli_flags_t heli_flags ;
2016-06-04 23:37:55 -03:00
int16_t hover_roll_trim_scalar_slew ;
2015-05-31 19:10:30 -03:00
# endif
2015-12-22 15:27:24 -04:00
// ground effect detector
struct {
bool takeoff_expected ;
bool touchdown_expected ;
uint32_t takeoff_time_ms ;
float takeoff_alt_cm ;
} gndeffect_state ;
2019-09-28 10:37:57 -03:00
bool standby_active ;
2015-05-29 23:12:49 -03:00
static const AP_Scheduler : : Task scheduler_tasks [ ] ;
static const AP_Param : : Info var_info [ ] ;
static const struct LogStructure log_structure [ ] ;
2019-10-04 06:08:35 -03:00
// enum for ESC CALIBRATION
enum ESCCalibrationModes : uint8_t {
ESCCAL_NONE = 0 ,
ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH = 1 ,
ESCCAL_PASSTHROUGH_ALWAYS = 2 ,
ESCCAL_AUTO = 3 ,
ESCCAL_DISABLED = 9 ,
} ;
2021-08-04 05:58:08 -03:00
enum class FailsafeAction : uint8_t {
NONE = 0 ,
LAND = 1 ,
RTL = 2 ,
SMARTRTL = 3 ,
SMARTRTL_LAND = 4 ,
TERMINATE = 5 ,
AUTO_DO_LAND_START = 6
2018-02-28 19:32:16 -04:00
} ;
2019-09-21 21:09:18 -03:00
enum class FailsafeOption {
RC_CONTINUE_IF_AUTO = ( 1 < < 0 ) , // 1
GCS_CONTINUE_IF_AUTO = ( 1 < < 1 ) , // 2
RC_CONTINUE_IF_GUIDED = ( 1 < < 2 ) , // 4
CONTINUE_IF_LANDING = ( 1 < < 3 ) , // 8
GCS_CONTINUE_IF_PILOT_CONTROL = ( 1 < < 4 ) , // 16
2020-08-14 16:40:20 -03:00
RELEASE_GRIPPER = ( 1 < < 5 ) , // 32
2019-09-21 21:09:18 -03:00
} ;
2021-02-17 07:19:22 -04:00
enum class FlightOptions {
DISABLE_THRUST_LOSS_CHECK = ( 1 < < 0 ) , // 1
DISABLE_YAW_IMBALANCE_WARNING = ( 1 < < 1 ) , // 2
2022-01-26 16:01:03 -04:00
RELEASE_GRIPPER_ON_THRUST_LOSS = ( 1 < < 2 ) , // 4
2021-02-17 07:19:22 -04:00
} ;
2018-02-28 19:32:16 -04:00
static constexpr int8_t _failsafe_priorities [ ] = {
2021-08-04 05:58:08 -03:00
( int8_t ) FailsafeAction : : TERMINATE ,
( int8_t ) FailsafeAction : : LAND ,
( int8_t ) FailsafeAction : : RTL ,
( int8_t ) FailsafeAction : : SMARTRTL_LAND ,
( int8_t ) FailsafeAction : : SMARTRTL ,
( int8_t ) FailsafeAction : : NONE ,
2018-02-28 19:32:16 -04:00
- 1 // the priority list must end with a sentinel of -1
} ;
# define FAILSAFE_LAND_PRIORITY 1
2021-08-04 05:58:08 -03:00
static_assert ( _failsafe_priorities [ FAILSAFE_LAND_PRIORITY ] = = ( int8_t ) FailsafeAction : : LAND ,
2018-02-28 19:32:16 -04:00
" FAILSAFE_LAND_PRIORITY must match the entry in _failsafe_priorities " ) ;
static_assert ( _failsafe_priorities [ ARRAY_SIZE ( _failsafe_priorities ) - 1 ] = = - 1 ,
" _failsafe_priorities is missing the sentinel " ) ;
2017-12-14 07:40:46 -04:00
// AP_State.cpp
void set_auto_armed ( bool b ) ;
2020-06-15 10:05:09 -03:00
void set_simple_mode ( SimpleMode b ) ;
2017-12-14 07:40:46 -04:00
void set_failsafe_radio ( bool b ) ;
void set_failsafe_gcs ( bool b ) ;
void update_using_interlock ( ) ;
2020-01-16 06:31:50 -04:00
// Copter.cpp
void get_scheduler_tasks ( const AP_Scheduler : : Task * & tasks ,
uint8_t & task_count ,
uint32_t & log_bit ) override ;
2021-11-15 01:08:33 -04:00
# if AP_SCRIPTING_ENABLED
2020-03-06 22:29:32 -04:00
bool start_takeoff ( float alt ) override ;
2020-02-18 00:11:31 -04:00
bool set_target_location ( const Location & target_loc ) override ;
2021-08-11 08:24:26 -03:00
bool set_target_pos_NED ( const Vector3f & target_pos , bool use_yaw , float yaw_deg , bool use_yaw_rate , float yaw_rate_degs , bool yaw_relative , bool terrain_alt ) override ;
2021-03-21 13:51:58 -03:00
bool set_target_posvel_NED ( const Vector3f & target_pos , const Vector3f & target_vel ) override ;
2021-08-11 08:24:26 -03:00
bool set_target_posvelaccel_NED ( const Vector3f & target_pos , const Vector3f & target_vel , const Vector3f & target_accel , bool use_yaw , float yaw_deg , bool use_yaw_rate , float yaw_rate_degs , bool yaw_relative ) override ;
2020-03-06 22:29:32 -04:00
bool set_target_velocity_NED ( const Vector3f & vel_ned ) override ;
2021-08-11 08:24:26 -03:00
bool set_target_velaccel_NED ( const Vector3f & target_vel , const Vector3f & target_accel , bool use_yaw , float yaw_deg , bool use_yaw_rate , float yaw_rate_degs , bool relative_yaw ) override ;
2020-05-31 20:29:13 -03:00
bool set_target_angle_and_climbrate ( float roll_deg , float pitch_deg , float yaw_deg , float climb_rate_ms , bool use_yaw_rate , float yaw_rate_degs ) override ;
2021-08-24 08:11:42 -03:00
bool get_circle_radius ( float & radius_m ) override ;
bool set_circle_rate ( float rate_dps ) override ;
2022-06-30 15:43:32 -03:00
bool set_desired_speed ( float speed ) override ;
2022-02-17 08:59:16 -04:00
bool nav_scripting_enable ( uint8_t mode ) override ;
2022-10-13 21:37:52 -03:00
bool nav_script_time ( uint16_t & id , uint8_t & cmd , float & arg1 , float & arg2 , int16_t & arg3 , int16_t & arg4 ) override ;
2022-02-17 08:59:16 -04:00
void nav_script_time_done ( uint16_t id ) override ;
2022-04-22 23:19:14 -03:00
// lua scripts use this to retrieve EKF failsafe state
// returns true if the EKF failsafe has triggered
bool has_ekf_failsafed ( ) const override ;
2021-11-15 01:08:33 -04:00
# endif // AP_SCRIPTING_ENABLED
2015-05-29 23:12:49 -03:00
void rc_loop ( ) ;
void throttle_loop ( ) ;
void update_batt_compass ( void ) ;
2022-08-06 12:34:55 -03:00
void loop_rate_logging ( ) ;
2015-05-29 23:12:49 -03:00
void ten_hz_logging_loop ( ) ;
2016-05-03 00:21:23 -03:00
void twentyfive_hz_logging ( ) ;
2015-05-29 23:12:49 -03:00
void three_hz_loop ( ) ;
void one_hz_loop ( ) ;
void init_simple_bearing ( ) ;
void update_simple_mode ( void ) ;
void update_super_simple_bearing ( bool force_update ) ;
void read_AHRS ( void ) ;
void update_altitude ( ) ;
2022-06-10 01:05:02 -03:00
bool get_wp_distance_m ( float & distance ) const override ;
bool get_wp_bearing_deg ( float & bearing ) const override ;
bool get_wp_crosstrack_error_m ( float & xtrack_error ) const override ;
2022-06-10 01:06:02 -03:00
bool get_rate_bf_targets ( Vector3f & rate_bf_targets ) const override ;
2017-12-14 07:40:46 -04:00
// Attitude.cpp
2016-06-09 09:42:15 -03:00
void update_throttle_hover ( ) ;
2015-05-29 23:12:49 -03:00
float get_pilot_desired_climb_rate ( float throttle_control ) ;
float get_non_takeoff_throttle ( ) ;
2016-10-14 03:34:24 -03:00
void set_accel_throttle_I_from_pilot_throttle ( ) ;
2015-08-11 08:25:20 -03:00
void rotate_body_frame_to_NE ( float & x , float & y ) ;
2021-02-01 12:26:21 -04:00
uint16_t get_pilot_speed_dn ( ) const ;
2022-04-01 16:56:16 -03:00
void run_rate_controller ( ) { attitude_control - > rate_controller_run ( ) ; }
2017-12-14 07:40:46 -04:00
2022-07-16 22:49:47 -03:00
# if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
void run_custom_controller ( ) { custom_control . update ( ) ; }
# endif
2021-02-09 13:56:15 -04:00
// avoidance.cpp
void low_alt_avoidance ( ) ;
2020-09-19 05:37:52 -03:00
# if HAL_ADSB_ENABLED
2017-12-14 07:40:46 -04:00
// avoidance_adsb.cpp
void avoidance_adsb_update ( void ) ;
2018-02-16 10:21:55 -04:00
# endif
2017-12-14 07:40:46 -04:00
// baro_ground_effect.cpp
void update_ground_effect_detector ( void ) ;
2020-06-22 01:00:44 -03:00
void update_ekf_terrain_height_stable ( ) ;
2017-12-14 07:40:46 -04:00
// commands.cpp
void update_home_from_EKF ( ) ;
void set_home_to_current_location_inflight ( ) ;
2018-05-29 21:47:08 -03:00
bool set_home_to_current_location ( bool lock ) WARN_IF_UNUSED ;
bool set_home ( const Location & loc , bool lock ) WARN_IF_UNUSED ;
2017-12-14 07:40:46 -04:00
bool far_from_EKF_origin ( const Location & loc ) ;
// compassmot.cpp
2019-06-21 20:49:52 -03:00
MAV_RESULT mavlink_compassmot ( const GCS_MAVLINK & gcs_chan ) ;
2017-12-14 07:40:46 -04:00
// crash_check.cpp
void crash_check ( ) ;
2018-08-12 11:19:47 -03:00
void thrust_loss_check ( ) ;
2020-11-07 14:33:10 -04:00
void yaw_imbalance_check ( ) ;
LowPassFilterFloat yaw_I_filt { 0.05f } ;
uint32_t last_yaw_warn_ms ;
2017-12-14 07:40:46 -04:00
void parachute_check ( ) ;
void parachute_release ( ) ;
void parachute_manual_release ( ) ;
// ekf_check.cpp
void ekf_check ( ) ;
bool ekf_over_threshold ( ) ;
void failsafe_ekf_event ( ) ;
void failsafe_ekf_off_event ( void ) ;
2022-05-25 09:25:33 -03:00
void failsafe_ekf_recheck ( ) ;
2017-12-14 07:40:46 -04:00
void check_ekf_reset ( ) ;
2019-03-21 06:51:35 -03:00
void check_vibration ( ) ;
2017-12-14 07:40:46 -04:00
// esc_calibration.cpp
void esc_calibration_startup_check ( ) ;
void esc_calibration_passthrough ( ) ;
void esc_calibration_auto ( ) ;
void esc_calibration_notify ( ) ;
2019-04-05 05:53:47 -03:00
void esc_calibration_setup ( ) ;
2017-12-14 07:40:46 -04:00
// events.cpp
2019-09-21 21:09:18 -03:00
bool failsafe_option ( FailsafeOption opt ) const ;
2017-12-14 07:40:46 -04:00
void failsafe_radio_on_event ( ) ;
void failsafe_radio_off_event ( ) ;
2018-02-28 19:32:16 -04:00
void handle_battery_failsafe ( const char * type_str , const int8_t action ) ;
2017-12-14 07:40:46 -04:00
void failsafe_gcs_check ( ) ;
2019-09-21 21:09:18 -03:00
void failsafe_gcs_on_event ( void ) ;
2017-12-14 07:40:46 -04:00
void failsafe_gcs_off_event ( void ) ;
void failsafe_terrain_check ( ) ;
void failsafe_terrain_set_status ( bool data_ok ) ;
void failsafe_terrain_on_event ( ) ;
void gpsglitch_check ( ) ;
2022-05-10 23:17:13 -03:00
void failsafe_deadreckon_check ( ) ;
2019-10-17 00:49:22 -03:00
void set_mode_RTL_or_land_with_pause ( ModeReason reason ) ;
void set_mode_SmartRTL_or_RTL ( ModeReason reason ) ;
void set_mode_SmartRTL_or_land_with_pause ( ModeReason reason ) ;
2021-07-24 20:25:40 -03:00
void set_mode_auto_do_land_start_or_RTL ( ModeReason reason ) ;
2017-12-14 07:40:46 -04:00
bool should_disarm_on_failsafe ( ) ;
2021-08-04 05:58:08 -03:00
void do_failsafe_action ( FailsafeAction action , ModeReason reason ) ;
2022-04-05 04:34:41 -03:00
void announce_failsafe ( const char * type , const char * action_undertaken = nullptr ) ;
2017-12-14 07:40:46 -04:00
// failsafe.cpp
void failsafe_enable ( ) ;
void failsafe_disable ( ) ;
# if ADVANCED_FAILSAFE == ENABLED
void afs_fs_check ( void ) ;
# endif
// fence.cpp
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2017-12-14 07:40:46 -04:00
void fence_check ( ) ;
2021-01-06 11:19:23 -04:00
# endif
2017-12-14 07:40:46 -04:00
// heli.cpp
void heli_init ( ) ;
void check_dynamic_flight ( void ) ;
2019-11-01 00:47:47 -03:00
bool should_use_landing_swash ( ) const ;
2017-12-14 07:40:46 -04:00
void update_heli_control_dynamics ( void ) ;
void heli_update_landing_swash ( ) ;
2020-01-07 01:12:54 -04:00
float get_pilot_desired_rotor_speed ( ) const ;
2017-12-14 07:40:46 -04:00
void heli_update_rotor_speed_targets ( ) ;
2019-11-28 16:21:07 -04:00
void heli_update_autorotation ( ) ;
# if MODE_AUTOROTATE_ENABLED == ENABLED
void heli_set_autorotation ( bool autotrotation ) ;
# endif
2021-10-29 13:17:45 -03:00
void update_collective_low_flag ( int16_t throttle_control ) ;
2017-12-14 07:40:46 -04:00
// inertia.cpp
void read_inertia ( ) ;
// landing_detector.cpp
void update_land_and_crash_detectors ( ) ;
void update_land_detector ( ) ;
void set_land_complete ( bool b ) ;
void set_land_complete_maybe ( bool b ) ;
2020-02-21 02:50:56 -04:00
void update_throttle_mix ( ) ;
2017-12-14 07:40:46 -04:00
2021-02-06 23:29:33 -04:00
# if LANDING_GEAR_ENABLED == ENABLED
2017-12-14 07:40:46 -04:00
// landing_gear.cpp
void landinggear_update ( ) ;
2021-02-06 23:29:33 -04:00
# endif
2017-12-14 07:40:46 -04:00
2019-09-28 10:37:57 -03:00
// standby.cpp
void standby_update ( ) ;
2017-12-14 07:40:46 -04:00
// Log.cpp
2015-05-29 23:12:49 -03:00
void Log_Write_Control_Tuning ( ) ;
void Log_Write_Attitude ( ) ;
2017-05-23 02:30:57 -03:00
void Log_Write_EKF_POS ( ) ;
2022-08-10 15:19:46 -03:00
void Log_Write_PIDS ( ) ;
2019-10-25 03:06:05 -03:00
void Log_Write_Data ( LogDataID id , int32_t value ) ;
void Log_Write_Data ( LogDataID id , uint32_t value ) ;
void Log_Write_Data ( LogDataID id , int16_t value ) ;
void Log_Write_Data ( LogDataID id , uint16_t value ) ;
void Log_Write_Data ( LogDataID id , float value ) ;
2019-04-03 09:32:26 -03:00
void Log_Write_Parameter_Tuning ( uint8_t param , float tuning_val , float tune_min , float tune_max ) ;
2022-04-01 16:56:16 -03:00
void Log_Video_Stabilisation ( ) ;
2015-06-18 18:09:39 -03:00
# if FRAME_CONFIG == HELI_FRAME
void Log_Write_Heli ( void ) ;
# endif
2022-01-25 12:28:04 -04:00
void Log_Write_Guided_Position_Target ( ModeGuided : : SubMode submode , const Vector3f & pos_target , bool terrain_alt , const Vector3f & vel_target , const Vector3f & accel_target ) ;
void Log_Write_Guided_Attitude_Target ( ModeGuided : : SubMode target_type , float roll , float pitch , float yaw , const Vector3f & ang_vel , float thrust , float climb_rate ) ;
2019-07-29 04:55:40 -03:00
void Log_Write_SysID_Setup ( uint8_t systemID_axis , float waveform_magnitude , float frequency_start , float frequency_stop , float time_fade_in , float time_const_freq , float time_record , float time_fade_out ) ;
void Log_Write_SysID_Data ( float waveform_time , float waveform_sample , float waveform_freq , float angle_x , float angle_y , float angle_z , float accel_x , float accel_y , float accel_z ) ;
2015-08-06 09:18:39 -03:00
void Log_Write_Vehicle_Startup_Messages ( ) ;
2017-12-14 07:40:46 -04:00
void log_init ( void ) ;
// mode.cpp
2019-10-17 00:49:22 -03:00
bool set_mode ( Mode : : Number mode , ModeReason reason ) ;
bool set_mode ( const uint8_t new_mode , const ModeReason reason ) override ;
2021-08-03 21:30:10 -03:00
ModeReason _last_reason ;
2020-07-06 01:32:32 -03:00
// called when an attempt to change into a mode is unsuccessful:
void mode_change_failed ( const Mode * mode , const char * reason ) ;
2020-01-30 03:29:36 -04:00
uint8_t get_mode ( ) const override { return ( uint8_t ) flightmode - > mode_number ( ) ; }
2017-12-14 07:40:46 -04:00
void update_flight_mode ( ) ;
void notify_flight_mode ( ) ;
// mode_land.cpp
2019-10-17 00:49:22 -03:00
void set_mode_land_with_pause ( ModeReason reason ) ;
2015-05-29 23:12:49 -03:00
bool landing_with_GPS ( ) ;
2017-12-14 07:40:46 -04:00
// motor_test.cpp
2015-05-29 23:12:49 -03:00
void motor_test_output ( ) ;
2021-07-27 16:51:19 -03:00
bool mavlink_motor_control_check ( const GCS_MAVLINK & gcs_chan , bool check_rc , const char * mode ) ;
2020-07-14 04:22:35 -03:00
MAV_RESULT mavlink_motor_test_start ( const GCS_MAVLINK & gcs_chan , uint8_t motor_seq , uint8_t throttle_type , float throttle_value , float timeout_sec , uint8_t motor_count ) ;
2015-05-29 23:12:49 -03:00
void motor_test_stop ( ) ;
2017-12-14 07:40:46 -04:00
// motors.cpp
2015-05-29 23:12:49 -03:00
void arm_motors_check ( ) ;
void auto_disarm_check ( ) ;
void motors_output ( ) ;
void lost_vehicle_check ( ) ;
2017-12-14 07:40:46 -04:00
// navigation.cpp
2015-05-29 23:12:49 -03:00
void run_nav_updates ( void ) ;
2017-12-14 07:40:46 -04:00
int32_t home_bearing ( ) ;
uint32_t home_distance ( ) ;
// Parameters.cpp
2020-01-16 06:40:53 -04:00
void load_parameters ( void ) override ;
2017-12-14 07:40:46 -04:00
void convert_pid_parameters ( void ) ;
2022-08-21 14:26:44 -03:00
# if HAL_PROXIMITY_ENABLED
void convert_prx_parameters ( ) ;
# endif
2018-11-09 02:36:42 -04:00
void convert_lgr_parameters ( void ) ;
2021-02-01 12:26:21 -04:00
void convert_tradheli_parameters ( void ) const ;
void convert_fs_options_params ( void ) const ;
2017-12-14 07:40:46 -04:00
// precision_landing.cpp
void init_precland ( ) ;
void update_precland ( ) ;
// radio.cpp
2015-05-29 23:12:49 -03:00
void default_dead_zones ( ) ;
void init_rc_in ( ) ;
void init_rc_out ( ) ;
void enable_motor_output ( ) ;
void read_radio ( ) ;
void set_throttle_and_failsafe ( uint16_t throttle_pwm ) ;
void set_throttle_zero_flag ( int16_t throttle_control ) ;
2016-02-05 21:43:16 -04:00
void radio_passthrough_to_motors ( ) ;
2018-01-18 02:49:20 -04:00
int16_t get_throttle_mid ( void ) ;
2017-12-14 07:40:46 -04:00
// sensors.cpp
2015-05-29 23:12:49 -03:00
void read_barometer ( void ) ;
2016-04-27 08:37:04 -03:00
void init_rangefinder ( void ) ;
2016-04-27 09:20:03 -03:00
void read_rangefinder ( void ) ;
2021-02-01 12:26:21 -04:00
bool rangefinder_alt_ok ( ) const ;
bool rangefinder_up_ok ( ) const ;
2015-05-29 23:12:49 -03:00
void update_optical_flow ( void ) ;
2017-12-14 07:40:46 -04:00
2022-06-28 08:19:10 -03:00
// takeoff_check.cpp
void takeoff_check ( ) ;
2020-06-03 00:28:04 -03:00
// RC_Channel.cpp
2015-05-29 23:12:49 -03:00
void save_trim ( ) ;
void auto_trim ( ) ;
2020-06-03 00:28:04 -03:00
void auto_trim_cancel ( ) ;
2017-12-14 07:40:46 -04:00
// system.cpp
2020-01-16 06:31:50 -04:00
void init_ardupilot ( ) override ;
2015-09-17 03:44:14 -03:00
void startup_INS_ground ( ) ;
2019-07-04 21:12:57 -03:00
bool position_ok ( ) const ;
2020-10-28 06:55:21 -03:00
bool ekf_has_absolute_position ( ) const ;
bool ekf_has_relative_position ( ) const ;
2020-08-18 03:07:21 -03:00
bool ekf_alt_ok ( ) const ;
2015-05-29 23:12:49 -03:00
void update_auto_armed ( ) ;
bool should_log ( uint32_t mask ) ;
2021-02-01 12:26:21 -04:00
const char * get_frame_string ( ) const ;
2017-12-14 07:40:46 -04:00
void allocate_motors ( void ) ;
2019-01-08 06:43:51 -04:00
bool is_tradheli ( ) const ;
2017-12-14 07:40:46 -04:00
// terrain.cpp
void terrain_update ( ) ;
void terrain_logging ( ) ;
// tuning.cpp
2015-05-29 23:12:49 -03:00
void tuning ( ) ;
2017-12-14 07:40:46 -04:00
// UserCode.cpp
void userhook_init ( ) ;
void userhook_FastLoop ( ) ;
void userhook_50Hz ( ) ;
void userhook_MediumLoop ( ) ;
void userhook_SlowLoop ( ) ;
void userhook_SuperSlowLoop ( ) ;
2021-11-30 05:57:23 -04:00
void userhook_auxSwitch1 ( const RC_Channel : : AuxSwitchPos ch_flag ) ;
void userhook_auxSwitch2 ( const RC_Channel : : AuxSwitchPos ch_flag ) ;
void userhook_auxSwitch3 ( const RC_Channel : : AuxSwitchPos ch_flag ) ;
2016-03-21 01:33:42 -03:00
2018-03-14 17:14:49 -03:00
# if MODE_ACRO_ENABLED == ENABLED
2016-03-21 01:20:54 -03:00
# if FRAME_CONFIG == HELI_FRAME
2018-02-07 22:21:09 -04:00
ModeAcro_Heli mode_acro ;
2016-03-21 01:20:54 -03:00
# else
2018-02-07 22:21:09 -04:00
ModeAcro mode_acro ;
2018-03-14 17:14:49 -03:00
# endif
2016-03-21 01:20:54 -03:00
# endif
2018-02-07 22:21:09 -04:00
ModeAltHold mode_althold ;
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeAuto mode_auto ;
2018-02-21 22:06:07 -04:00
# endif
2016-03-22 20:36:52 -03:00
# if AUTOTUNE_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeAutoTune mode_autotune ;
# endif
2018-02-23 01:40:29 -04:00
# if MODE_BRAKE_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeBrake mode_brake ;
2018-02-23 01:40:29 -04:00
# endif
2018-02-23 05:51:17 -04:00
# if MODE_CIRCLE_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeCircle mode_circle ;
2018-02-23 05:51:17 -04:00
# endif
2018-02-22 23:55:51 -04:00
# if MODE_DRIFT_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeDrift mode_drift ;
2018-02-22 23:55:51 -04:00
# endif
2018-11-25 19:47:55 -04:00
# if MODE_FLIP_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeFlip mode_flip ;
2018-11-25 19:47:55 -04:00
# endif
2018-02-06 02:16:09 -04:00
# if MODE_FOLLOW_ENABLED == ENABLED
2018-02-05 22:44:05 -04:00
ModeFollow mode_follow ;
2018-02-06 02:16:09 -04:00
# endif
2018-02-23 00:09:07 -04:00
# if MODE_GUIDED_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeGuided mode_guided ;
2018-02-23 00:09:07 -04:00
# endif
2018-02-07 22:21:09 -04:00
ModeLand mode_land ;
2018-02-22 01:23:35 -04:00
# if MODE_LOITER_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeLoiter mode_loiter ;
2018-02-22 01:23:35 -04:00
# endif
2018-02-21 23:45:02 -04:00
# if MODE_POSHOLD_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModePosHold mode_poshold ;
2018-02-21 23:45:02 -04:00
# endif
2018-02-23 01:33:49 -04:00
# if MODE_RTL_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeRTL mode_rtl ;
2018-02-23 01:33:49 -04:00
# endif
2017-01-14 01:23:33 -04:00
# if FRAME_CONFIG == HELI_FRAME
2018-02-07 22:21:09 -04:00
ModeStabilize_Heli mode_stabilize ;
2017-01-14 01:23:33 -04:00
# else
2018-02-07 22:21:09 -04:00
ModeStabilize mode_stabilize ;
2017-01-14 01:23:33 -04:00
# endif
2018-02-22 23:48:02 -04:00
# if MODE_SPORT_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeSport mode_sport ;
2018-02-22 23:48:02 -04:00
# endif
2019-07-29 04:55:40 -03:00
# if MODE_SYSTEMID_ENABLED == ENABLED
ModeSystemId mode_systemid ;
# endif
2020-09-19 05:37:52 -03:00
# if HAL_ADSB_ENABLED
2018-02-07 22:21:09 -04:00
ModeAvoidADSB mode_avoid_adsb ;
2018-02-16 10:21:55 -04:00
# endif
2018-03-14 17:16:16 -03:00
# if MODE_THROW_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeThrow mode_throw ;
2018-03-14 17:16:16 -03:00
# endif
2018-02-23 03:54:34 -04:00
# if MODE_GUIDED_NOGPS_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeGuidedNoGPS mode_guided_nogps ;
2018-02-23 03:54:34 -04:00
# endif
2018-02-21 23:58:28 -04:00
# if MODE_SMARTRTL_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeSmartRTL mode_smartrtl ;
2018-02-21 23:58:28 -04:00
# endif
2022-08-16 23:18:38 -03:00
# if MODE_FLOWHOLD_ENABLED == ENABLED
2018-02-07 22:21:09 -04:00
ModeFlowHold mode_flowhold ;
2018-01-18 02:12:29 -04:00
# endif
2018-09-07 01:23:33 -03:00
# if MODE_ZIGZAG_ENABLED == ENABLED
ModeZigZag mode_zigzag ;
# endif
2019-11-28 16:21:07 -04:00
# if MODE_AUTOROTATE_ENABLED == ENABLED
ModeAutorotate mode_autorotate ;
# endif
2021-07-27 16:51:19 -03:00
# if MODE_TURTLE_ENABLED == ENABLED
ModeTurtle mode_turtle ;
# endif
2017-01-14 01:23:33 -04:00
2017-12-14 07:40:46 -04:00
// mode.cpp
2019-09-07 20:33:56 -03:00
Mode * mode_from_mode_num ( const Mode : : Number mode ) ;
2017-12-10 23:51:13 -04:00
void exit_mode ( Mode * & old_flightmode , Mode * & new_flightmode ) ;
2017-12-05 19:52:54 -04:00
2015-05-29 23:12:49 -03:00
public :
2017-12-14 07:40:46 -04:00
void failsafe_check ( ) ; // failsafe.cpp
2015-05-29 23:12:49 -03:00
} ;
extern Copter copter ;
2015-08-24 03:26:17 -03:00
2015-11-19 23:04:45 -04:00
using AP_HAL : : millis ;
using AP_HAL : : micros ;