2011-09-08 22:29:39 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2012-07-25 22:36:17 -03:00
#define THISFIRMWARE "ArduPlane V2.50"
2011-09-08 22:29:39 -03:00
/*
2011-12-26 13:13:37 -04:00
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler
2012-07-09 19:36:50 -03:00
Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier, Yury MonZon
2011-09-08 22:29:39 -03:00
Please contribute your ideas!
This firmware is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
*/
////////////////////////////////////////////////////////////////////////////////
// Header includes
////////////////////////////////////////////////////////////////////////////////
// AVR runtime
#include <avr/io.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <math.h>
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
2011-11-13 00:09:18 -04:00
#include <Arduino_Mega_ISR_Registry.h>
2011-09-08 22:29:39 -03:00
#include <APM_RC.h> // ArduPilot Mega RC Library
#include <AP_GPS.h> // ArduPilot GPS library
2011-12-28 05:32:55 -04:00
#include <I2C.h> // Wayne Truchsess I2C lib
2011-09-09 11:18:38 -03:00
#include <SPI.h> // Arduino SPI lib
2011-09-08 22:29:39 -03:00
#include <DataFlash.h> // ArduPilot Mega Flash Memory Library
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
2011-11-13 00:09:18 -04:00
#include <AP_AnalogSource.h>// ArduPilot Mega polymorphic analog getter
2011-12-16 15:48:39 -04:00
#include <AP_PeriodicProcess.h> // ArduPilot Mega TimerProcess
2011-11-27 01:51:47 -04:00
#include <AP_Baro.h> // ArduPilot barometer library
2011-09-08 22:29:39 -03:00
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
2012-06-13 15:44:35 -03:00
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibrated IMU) Library
2011-09-08 22:29:39 -03:00
#include <AP_IMU.h> // ArduPilot Mega IMU Library
2012-03-11 05:13:31 -03:00
#include <AP_AHRS.h> // ArduPilot Mega DCM Library
2011-09-08 22:29:39 -03:00
#include <PID.h> // PID library
#include <RC_Channel.h> // RC Channel Library
2011-09-09 11:18:38 -03:00
#include <AP_RangeFinder.h> // Range finder library
2012-02-26 04:05:56 -04:00
#include <Filter.h> // Filter library
#include <ModeFilter.h> // Mode Filter from Filter library
2012-06-19 23:26:58 -03:00
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
2011-10-01 19:55:41 -03:00
#include <AP_Relay.h> // APM relay
2012-06-13 16:00:20 -03:00
#include <AP_Camera.h> // Photo or video camera
2012-07-15 22:21:50 -03:00
#include <AP_Airspeed.h>
2011-09-09 11:18:38 -03:00
#include <memcheck.h>
2011-09-08 22:29:39 -03:00
// Configuration
#include "config.h"
2012-04-24 09:18:30 -03:00
#include <GCS_MAVLink.h> // MAVLink GCS definitions
2012-06-04 00:13:01 -03:00
2012-06-04 06:30:33 -03:00
#include <AP_Mount.h> // Camera/Antenna mount
2012-04-24 09:18:30 -03:00
2011-09-08 22:29:39 -03:00
// Local modules
#include "defines.h"
#include "Parameters.h"
#include "GCS.h"
2012-03-11 07:46:41 -03:00
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
2011-09-08 22:29:39 -03:00
////////////////////////////////////////////////////////////////////////////////
// Serial ports
////////////////////////////////////////////////////////////////////////////////
//
// Note that FastSerial port buffers are allocated at ::begin time,
// so there is not much of a penalty to defining ports that we don't
// use.
//
FastSerialPort0(Serial); // FTDI/console
FastSerialPort1(Serial1); // GPS port
2012-05-03 21:39:44 -03:00
#if TELEMETRY_UART2 == ENABLED
// solder bridge set to enable UART2 instead of USB MUX
FastSerialPort2(Serial3);
#else
FastSerialPort3(Serial3); // Telemetry port for APM1
#endif
2011-09-08 22:29:39 -03:00
2011-11-13 00:09:18 -04:00
////////////////////////////////////////////////////////////////////////////////
// ISR Registry
////////////////////////////////////////////////////////////////////////////////
Arduino_Mega_ISR_Registry isr_registry;
////////////////////////////////////////////////////////////////////////////////
// APM_RC_Class Instance
////////////////////////////////////////////////////////////////////////////////
2011-11-25 19:11:36 -04:00
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
APM_RC_APM2 APM_RC;
2011-11-13 00:09:18 -04:00
#else
APM_RC_APM1 APM_RC;
#endif
////////////////////////////////////////////////////////////////////////////////
// Dataflash
////////////////////////////////////////////////////////////////////////////////
2011-11-25 19:11:36 -04:00
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
DataFlash_APM2 DataFlash;
2011-11-13 00:09:18 -04:00
#else
DataFlash_APM1 DataFlash;
#endif
2011-09-08 22:29:39 -03:00
////////////////////////////////////////////////////////////////////////////////
// Parameters
////////////////////////////////////////////////////////////////////////////////
//
// Global parameters are all contained within the 'g' class.
//
2011-09-09 11:18:38 -03:00
static Parameters g;
2011-09-08 22:29:39 -03:00
////////////////////////////////////////////////////////////////////////////////
// prototypes
2011-09-09 11:18:38 -03:00
static void update_events(void);
2011-09-08 22:29:39 -03:00
////////////////////////////////////////////////////////////////////////////////
// Sensors
////////////////////////////////////////////////////////////////////////////////
//
// There are three basic options related to flight sensor selection.
//
// - Normal flight mode. Real sensors are used.
// - HIL Attitude mode. Most sensors are disabled, as the HIL
// protocol supplies attitude information directly.
// - HIL Sensors mode. Synthetic sensors are configured that
// supply data from the simulation.
//
// All GPS access should be through this pointer.
2011-09-09 11:18:38 -03:00
static GPS *g_gps;
// flight modes convenience array
static AP_Int8 *flight_modes = &g.flight_mode1;
2011-09-08 22:29:39 -03:00
#if HIL_MODE == HIL_MODE_DISABLED
// real sensors
2011-12-16 16:19:03 -04:00
#if CONFIG_ADC == ENABLED
2011-09-09 11:18:38 -03:00
static AP_ADC_ADS7844 adc;
2011-12-16 16:19:03 -04:00
#endif
2011-11-16 21:49:56 -04:00
#ifdef DESKTOP_BUILD
2011-11-27 01:51:47 -04:00
AP_Baro_BMP085_HIL barometer;
2011-11-16 21:49:56 -04:00
AP_Compass_HIL compass;
2012-06-29 02:10:35 -03:00
#include <SITL.h>
SITL sitl;
2011-11-16 21:49:56 -04:00
#else
2011-12-09 02:48:22 -04:00
#if CONFIG_BARO == AP_BARO_BMP085
2011-12-13 02:05:48 -04:00
# if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
2011-12-09 02:48:22 -04:00
static AP_Baro_BMP085 barometer(true);
# else
static AP_Baro_BMP085 barometer(false);
# endif
#elif CONFIG_BARO == AP_BARO_MS5611
static AP_Baro_MS5611 barometer;
#endif
2012-02-12 04:20:56 -04:00
static AP_Compass_HMC5843 compass;
2011-11-16 21:49:56 -04:00
#endif
2011-09-08 22:29:39 -03:00
// real GPS selection
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
AP_GPS_Auto g_gps_driver(&Serial1, &g_gps);
#elif GPS_PROTOCOL == GPS_PROTOCOL_NMEA
AP_GPS_NMEA g_gps_driver(&Serial1);
#elif GPS_PROTOCOL == GPS_PROTOCOL_SIRF
AP_GPS_SIRF g_gps_driver(&Serial1);
#elif GPS_PROTOCOL == GPS_PROTOCOL_UBLOX
AP_GPS_UBLOX g_gps_driver(&Serial1);
#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK
AP_GPS_MTK g_gps_driver(&Serial1);
#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK16
AP_GPS_MTK16 g_gps_driver(&Serial1);
#elif GPS_PROTOCOL == GPS_PROTOCOL_NONE
AP_GPS_None g_gps_driver(NULL);
#else
#error Unrecognised GPS_PROTOCOL setting.
#endif // GPS PROTOCOL
2011-11-13 02:15:45 -04:00
# if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN );
# else
AP_InertialSensor_Oilpan ins( &adc );
#endif // CONFIG_IMU_TYPE
2012-02-12 04:20:56 -04:00
AP_IMU_INS imu( &ins );
2012-03-03 03:33:40 -04:00
#if QUATERNION_ENABLE == ENABLED
2012-03-11 05:13:31 -03:00
AP_AHRS_Quaternion ahrs(&imu, g_gps);
2012-03-03 03:33:40 -04:00
#else
2012-03-11 05:13:31 -03:00
AP_AHRS_DCM ahrs(&imu, g_gps);
2012-03-03 03:33:40 -04:00
#endif
2011-11-13 02:15:45 -04:00
2011-09-08 22:29:39 -03:00
#elif HIL_MODE == HIL_MODE_SENSORS
// sensor emulators
AP_ADC_HIL adc;
2011-11-27 01:51:47 -04:00
AP_Baro_BMP085_HIL barometer;
2011-09-08 22:29:39 -03:00
AP_Compass_HIL compass;
AP_GPS_HIL g_gps_driver(NULL);
2011-11-13 02:15:45 -04:00
AP_InertialSensor_Oilpan ins( &adc );
AP_IMU_Shim imu;
2012-03-11 05:13:31 -03:00
AP_AHRS_DCM ahrs(&imu, g_gps);
2011-09-08 22:29:39 -03:00
#elif HIL_MODE == HIL_MODE_ATTITUDE
2011-09-09 11:18:38 -03:00
AP_ADC_HIL adc;
2012-03-11 05:13:31 -03:00
AP_IMU_Shim imu; // never used
AP_AHRS_HIL ahrs(&imu, g_gps);
2011-09-08 22:29:39 -03:00
AP_GPS_HIL g_gps_driver(NULL);
AP_Compass_HIL compass; // never used
2012-01-20 04:04:49 -04:00
AP_Baro_BMP085_HIL barometer;
2012-07-23 20:16:09 -03:00
#ifdef DESKTOP_BUILD
#include <SITL.h>
SITL sitl;
AP_InertialSensor_Oilpan ins( &adc );
#endif
2011-09-08 22:29:39 -03:00
#else
#error Unrecognised HIL_MODE setting.
#endif // HIL MODE
2011-12-21 08:23:17 -04:00
// we always have a timer scheduler
AP_TimerProcess timer_scheduler;
2011-09-08 22:29:39 -03:00
////////////////////////////////////////////////////////////////////////////////
// GCS selection
////////////////////////////////////////////////////////////////////////////////
//
2012-02-12 04:20:56 -04:00
GCS_MAVLINK gcs0;
GCS_MAVLINK gcs3;
2011-09-08 22:29:39 -03:00
2011-09-09 11:18:38 -03:00
////////////////////////////////////////////////////////////////////////////////
2011-11-13 00:09:18 -04:00
// PITOT selection
2011-09-09 11:18:38 -03:00
////////////////////////////////////////////////////////////////////////////////
//
2012-02-28 08:03:04 -04:00
ModeFilterInt16_Size5 sonar_mode_filter(2);
2011-09-09 11:18:38 -03:00
2011-11-13 00:09:18 -04:00
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
AP_AnalogSource_ADC pitot_analog_source( &adc,
2011-12-16 16:19:03 -04:00
CONFIG_PITOT_SOURCE_ADC_CHANNEL, 1.0);
2011-11-13 00:09:18 -04:00
#elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
2011-12-16 16:19:03 -04:00
AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN, 4.0);
2011-11-13 00:09:18 -04:00
#endif
2011-09-09 11:18:38 -03:00
#if SONAR_TYPE == MAX_SONAR_XL
2011-11-13 00:09:18 -04:00
AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter);
2011-09-09 11:18:38 -03:00
#elif SONAR_TYPE == MAX_SONAR_LV
// XXX honestly I think these output the same values
// If someone knows, can they confirm it?
2011-11-13 00:09:18 -04:00
AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter);
2011-09-09 11:18:38 -03:00
#endif
2011-09-08 22:29:39 -03:00
2012-01-16 13:28:03 -04:00
AP_Relay relay;
2011-09-08 22:29:39 -03:00
////////////////////////////////////////////////////////////////////////////////
// Global variables
////////////////////////////////////////////////////////////////////////////////
2012-01-11 15:37:43 -04:00
// APM2 only
2011-11-20 05:31:45 -04:00
#if USB_MUX_PIN > 0
static bool usb_connected;
#endif
2011-09-09 11:18:38 -03:00
static const char *comma = ",";
2011-09-08 22:29:39 -03:00
2011-09-09 11:18:38 -03:00
static const char* flight_mode_strings[] = {
2011-09-08 22:29:39 -03:00
"Manual",
"Circle",
"Stabilize",
"",
"",
"FBW_A",
"FBW_B",
"",
"",
"",
"Auto",
"RTL",
"Loiter",
"Takeoff",
"Land"};
/* Radio values
Channel assignments
1 Ailerons (rudder if no ailerons)
2 Elevator
3 Throttle
4 Rudder (if we have ailerons)
2011-09-27 17:12:45 -03:00
5 Aux5
6 Aux6
7 Aux7
8 Aux8/Mode
Each Aux channel can be configured to have any of the available auxiliary functions assigned to it.
See libraries/RC_Channel/RC_Channel_aux.h for more information
2011-09-08 22:29:39 -03:00
*/
2012-01-11 15:37:43 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Radio
2012-01-11 15:37:43 -04:00
////////////////////////////////////////////////////////////////////////////////
// This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO
byte control_mode = INITIALISING;
// Used to maintain the state of the previous control switch position
// This is set to -1 when we need to re-read the switch
byte oldSwitchPosition;
// This is used to enable the inverted flight feature
bool inverted_flight = false;
// These are trim values used for elevon control
// For elevons radio_in[CH_ROLL] and radio_in[CH_PITCH] are equivalent aileron and elevator, not left and right elevon
2012-06-10 17:10:07 -03:00
static uint16_t elevon1_trim = 1500;
2011-09-09 11:18:38 -03:00
static uint16_t elevon2_trim = 1500;
2012-01-11 15:37:43 -04:00
// These are used in the calculation of elevon1_trim and elevon2_trim
2012-06-10 17:10:07 -03:00
static uint16_t ch1_temp = 1500;
2011-09-09 11:18:38 -03:00
static uint16_t ch2_temp = 1500;
2012-01-11 15:37:43 -04:00
// These are values received from the GCS if the user is using GCS joystick
// control and are substituted for the values coming from the RC radio
2011-09-09 11:18:38 -03:00
static int16_t rc_override[8] = {0,0,0,0,0,0,0,0};
2012-01-11 15:37:43 -04:00
// A flag if GCS joystick control is in use
2011-09-09 11:18:38 -03:00
static bool rc_override_active = false;
2012-01-11 15:37:43 -04:00
////////////////////////////////////////////////////////////////////////////////
// Failsafe
////////////////////////////////////////////////////////////////////////////////
// A tracking variable for type of failsafe active
// Used for failsafe based on loss of RC signal or GCS signal
2012-07-06 06:22:19 -03:00
static int16_t failsafe;
2012-01-11 15:37:43 -04:00
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
// RC receiver should be set up to output a low throttle value when signal is lost
static bool ch3_failsafe;
2012-06-10 17:10:07 -03:00
// A timer used to help recovery from unusual attitudes. If we enter an unusual attitude
2012-01-11 15:37:43 -04:00
// while in autonomous flight this variable is used to hold roll at 0 for a recovery period
static byte crash_timer;
// A timer used to track how long since we have received the last GCS heartbeat or rc override message
2011-09-09 11:18:38 -03:00
static uint32_t rc_override_fs_timer = 0;
2012-01-11 15:37:43 -04:00
// A timer used to track how long we have been in a "short failsafe" condition due to loss of RC signal
2011-09-09 11:18:38 -03:00
static uint32_t ch3_failsafe_timer = 0;
2012-01-11 15:37:43 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// LED output
2012-01-11 15:37:43 -04:00
////////////////////////////////////////////////////////////////////////////////
// state of the GPS light (on/off)
2012-06-10 17:10:07 -03:00
static bool GPS_light;
2011-09-08 22:29:39 -03:00
2012-01-11 15:37:43 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// GPS variables
2012-01-11 15:37:43 -04:00
////////////////////////////////////////////////////////////////////////////////
// This is used to scale GPS values for EEPROM storage
// 10^7 times Decimal GPS means 1 == 1cm
// This approximation makes calculations integer and it's easy to read
2012-06-10 17:10:07 -03:00
static const float t7 = 10000000.0;
2012-01-11 15:37:43 -04:00
// We use atan2 and other trig techniques to calaculate angles
// A counter used to count down valid gps fixes to allow the gps estimate to settle
// before recording our home position (and executing a ground start if we booted with an air start)
static byte ground_start_count = 5;
2012-06-10 17:10:07 -03:00
// Used to compute a speed estimate from the first valid gps fixes to decide if we are
2012-01-11 15:37:43 -04:00
// on the ground or in the air. Used to decide if a ground start is appropriate if we
// booted with an air start.
2012-07-06 06:22:19 -03:00
static int16_t ground_start_avg;
2012-01-11 15:37:43 -04:00
// Tracks if GPS is enabled based on statup routine
2012-06-10 17:10:07 -03:00
// If we do not detect GPS at startup, we stop trying and assume GPS is not connected
static bool GPS_enabled = false;
2011-09-08 22:29:39 -03:00
2012-01-15 19:11:02 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Location & Navigation
2012-01-15 19:11:02 -04:00
////////////////////////////////////////////////////////////////////////////////
// Constants
2011-09-08 22:29:39 -03:00
const float radius_of_earth = 6378100; // meters
const float gravity = 9.81; // meters/ sec^2
2012-06-10 17:10:07 -03:00
// This is the currently calculated direction to fly.
2012-01-15 19:11:02 -04:00
// deg * 100 : 0 to 360
2012-07-06 06:22:19 -03:00
static int32_t nav_bearing;
2012-06-10 17:10:07 -03:00
// This is the direction to the next waypoint or loiter center
2012-01-15 19:11:02 -04:00
// deg * 100 : 0 to 360
2012-07-06 06:22:19 -03:00
static int32_t target_bearing;
2012-06-10 17:10:07 -03:00
//This is the direction from the last waypoint to the next waypoint
2012-01-15 19:11:02 -04:00
// deg * 100 : 0 to 360
2012-07-06 06:22:19 -03:00
static int32_t crosstrack_bearing;
2012-01-15 19:11:02 -04:00
// Direction held during phases of takeoff and landing
// deg * 100 dir of plane, A value of -1 indicates the course has not been set/is not in use
2012-07-06 06:22:19 -03:00
static int32_t hold_course = -1; // deg * 100 dir of plane
2011-09-09 11:18:38 -03:00
2012-06-10 17:10:07 -03:00
// There may be two active commands in Auto mode.
2012-01-16 12:45:42 -04:00
// This indicates the active navigation command by index number
2012-06-10 17:10:07 -03:00
static byte nav_command_index;
2012-01-16 12:45:42 -04:00
// This indicates the active non-navigation command by index number
2012-06-10 17:10:07 -03:00
static byte non_nav_command_index;
2012-01-16 12:45:42 -04:00
// This is the command type (eg navigate to waypoint) of the active navigation command
2012-06-10 17:10:07 -03:00
static byte nav_command_ID = NO_COMMAND;
static byte non_nav_command_ID = NO_COMMAND;
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Airspeed
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// The calculated airspeed to use in FBW-B. Also used in higher modes for insuring min ground speed is met.
2012-07-06 06:22:19 -03:00
// Also used for flap deployment criteria. Centimeters per second.static int32_t target_airspeed;
static int32_t target_airspeed;
2012-01-16 12:45:42 -04:00
// The difference between current and desired airspeed. Used in the pitch controller. Centimeters per second.
2012-06-10 17:10:07 -03:00
static float airspeed_error;
// The calculated total energy error (kinetic (altitude) plus potential (airspeed)).
2012-01-16 12:45:42 -04:00
// Used by the throttle controller
2012-07-06 06:22:19 -03:00
static int32_t energy_error;
2012-01-16 12:45:42 -04:00
// kinetic portion of energy error (m^2/s^2)
2012-07-06 06:22:19 -03:00
static int32_t airspeed_energy_error;
2012-06-10 17:10:07 -03:00
// An amount that the airspeed should be increased in auto modes based on the user positioning the
2012-01-16 12:45:42 -04:00
// throttle stick in the top half of the range. Centimeters per second.
2012-07-06 06:22:19 -03:00
static int16_t airspeed_nudge;
2012-01-16 12:45:42 -04:00
// Similar to airspeed_nudge, but used when no airspeed sensor.
// 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel
2012-07-06 06:22:19 -03:00
static int16_t throttle_nudge = 0;
2011-12-09 19:40:56 -04:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-12-09 19:40:56 -04:00
// Ground speed
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// The amount current ground speed is below min ground speed. Centimeters per second
2012-07-06 06:22:19 -03:00
static int32_t groundspeed_undershoot = 0;
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Location Errors
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Difference between current bearing and desired bearing. Hundredths of a degree
2012-07-06 06:22:19 -03:00
static int32_t bearing_error;
2012-01-16 12:45:42 -04:00
// Difference between current altitude and desired altitude. Centimeters
2012-07-06 06:22:19 -03:00
static int32_t altitude_error;
2012-06-10 17:10:07 -03:00
// Distance perpandicular to the course line that we are off trackline. Meters
2012-01-16 12:45:42 -04:00
static float crosstrack_error;
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Battery Sensors
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Battery pack 1 voltage. Initialized above the low voltage threshold to pre-load the filter and prevent low voltage events at startup.
static float battery_voltage1 = LOW_VOLTAGE * 1.05;
// Battery pack 1 instantaneous currrent draw. Amperes
static float current_amps1;
// Totalized current (Amp-hours) from battery 1
2012-06-10 17:10:07 -03:00
static float current_total1;
2012-01-15 19:10:28 -04:00
// To Do - Add support for second battery pack
//static float battery_voltage2 = LOW_VOLTAGE * 1.05; // Battery 2 Voltage, initialized above threshold for filter
//static float current_amps2; // Current (Amperes) draw from battery 2
//static float current_total2; // Totalized current (Amp-hours) from battery 2
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Airspeed Sensors
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2012-07-15 22:21:50 -03:00
AP_Airspeed airspeed(&pitot_analog_source, AIRSPEED_RATIO, AIRSPEED_SENSOR);
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Altitude Sensor variables
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Altitude from the sonar sensor. Meters. Not yet implemented.
2012-07-06 06:22:19 -03:00
static int16_t sonar_alt;
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// flight mode specific
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Flag for using gps ground course instead of IMU yaw. Set false when takeoff command in process.
2012-06-10 17:10:07 -03:00
static bool takeoff_complete = true;
2012-01-16 12:45:42 -04:00
// Flag to indicate if we have landed.
//Set land_complete if we are within 2 seconds distance or within 3 meters altitude of touchdown
2011-09-09 11:18:38 -03:00
static bool land_complete;
2012-01-16 12:45:42 -04:00
// Altitude threshold to complete a takeoff command in autonomous modes. Centimeters
2012-07-06 06:22:19 -03:00
static int32_t takeoff_altitude;
2012-01-16 12:45:42 -04:00
// Minimum pitch to hold during takeoff command execution. Hundredths of a degree
2012-07-06 06:22:19 -03:00
static int16_t takeoff_pitch;
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Loiter management
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Previous target bearing. Used to calculate loiter rotations. Hundredths of a degree
2012-07-06 06:22:19 -03:00
static int32_t old_target_bearing;
2012-01-16 12:45:42 -04:00
// Total desired rotation in a loiter. Used for Loiter Turns commands. Degrees
2012-07-06 06:22:19 -03:00
static int16_t loiter_total;
2012-01-16 12:45:42 -04:00
// The amount in degrees we have turned since recording old_target_bearing
2012-07-06 06:22:19 -03:00
static int16_t loiter_delta;
2012-01-16 12:45:42 -04:00
// Total rotation in a loiter. Used for Loiter Turns commands and to check for missed waypoints. Degrees
2012-07-06 06:22:19 -03:00
static int16_t loiter_sum;
2012-01-16 12:45:42 -04:00
// The amount of time we have been in a Loiter. Used for the Loiter Time command. Milliseconds.
2012-07-06 06:22:19 -03:00
static int32_t loiter_time;
2012-01-16 12:45:42 -04:00
// The amount of time we should stay in a loiter for the Loiter Time command. Milliseconds.
2012-07-06 06:22:19 -03:00
static int16_t loiter_time_max;
2011-09-08 22:29:39 -03:00
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Navigation control variables
////////////////////////////////////////////////////////////////////////////////
// The instantaneous desired bank angle. Hundredths of a degree
2012-07-06 06:22:19 -03:00
static int32_t nav_roll;
2012-01-16 12:45:42 -04:00
// The instantaneous desired pitch angle. Hundredths of a degree
2012-07-06 06:22:19 -03:00
static int32_t nav_pitch;
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Waypoint distances
////////////////////////////////////////////////////////////////////////////////
// Distance between plane and next waypoint. Meters
2012-06-13 16:00:20 -03:00
// is not static because AP_Camera uses it
long wp_distance;
2012-01-16 12:45:42 -04:00
// Distance between previous and next waypoint. Meters
2012-07-06 06:22:19 -03:00
static int32_t wp_totalDistance;
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// repeating event control
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Flag indicating current event type
static byte event_id;
// when the event was started in ms
2012-07-06 06:22:19 -03:00
static int32_t event_timer;
2012-01-16 12:45:42 -04:00
// how long to delay the next firing of event in millis
2012-06-10 17:10:07 -03:00
static uint16_t event_delay;
2012-01-16 12:45:42 -04:00
// how many times to cycle : -1 (or -2) = forever, 2 = do one cycle, 4 = do two cycles
2012-07-06 06:22:19 -03:00
static int16_t event_repeat = 0;
2012-01-16 12:45:42 -04:00
// per command value, such as PWM for servos
2012-07-06 06:22:19 -03:00
static int16_t event_value;
2012-01-16 12:45:42 -04:00
// the value used to cycle events (alternate value to event_value)
2012-07-06 06:22:19 -03:00
static int16_t event_undo_value;
2012-01-16 12:45:42 -04:00
////////////////////////////////////////////////////////////////////////////////
// Conditional command
////////////////////////////////////////////////////////////////////////////////
// A value used in condition commands (eg delay, change alt, etc.)
// For example in a change altitude command, it is the altitude to change to.
2012-07-06 06:22:19 -03:00
static int32_t condition_value;
2012-01-16 12:45:42 -04:00
// A starting value used to check the status of a conditional command.
// For example in a delay command the condition_start records that start time for the delay
2012-07-06 06:22:19 -03:00
static uint32_t condition_start;
2012-01-16 12:45:42 -04:00
// A value used in condition commands. For example the rate at which to change altitude.
2012-07-06 06:22:19 -03:00
static int16_t condition_rate;
2011-09-08 22:29:39 -03:00
2012-01-16 13:28:03 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// 3D Location vectors
2012-01-16 13:28:03 -04:00
// Location structure defined in AP_Common
////////////////////////////////////////////////////////////////////////////////
// The home location used for RTL. The location is set when we first get stable GPS lock
static struct Location home;
// Flag for if we have g_gps lock and have set the home location
static bool home_is_set;
// The location of the previous waypoint. Used for track following and altitude ramp calculations
static struct Location prev_WP;
// The plane's current location
static struct Location current_loc;
// The location of the current/active waypoint. Used for altitude ramp, track following and loiter calculations.
static struct Location next_WP;
// The location of the active waypoint in Guided mode.
static struct Location guided_WP;
// The location structure information from the Nav command being processed
2012-06-10 17:10:07 -03:00
static struct Location next_nav_command;
2012-01-16 13:28:03 -04:00
// The location structure information from the Non-Nav command being processed
static struct Location next_nonnav_command;
////////////////////////////////////////////////////////////////////////////////
// Altitude / Climb rate control
////////////////////////////////////////////////////////////////////////////////
// The current desired altitude. Altitude is linearly ramped between waypoints. Centimeters
2012-07-06 06:22:19 -03:00
static int32_t target_altitude;
2012-01-16 13:28:03 -04:00
// Altitude difference between previous and current waypoint. Centimeters
2012-07-06 06:22:19 -03:00
static int32_t offset_altitude;
2011-09-08 22:29:39 -03:00
2012-01-16 13:28:03 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// IMU variables
2012-01-16 13:28:03 -04:00
////////////////////////////////////////////////////////////////////////////////
// The main loop execution time. Seconds
//This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
2012-06-10 17:10:07 -03:00
static float G_Dt = 0.02;
2011-09-08 22:29:39 -03:00
2012-01-16 13:28:03 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// Performance monitoring
2012-01-16 13:28:03 -04:00
////////////////////////////////////////////////////////////////////////////////
// Timer used to accrue data and trigger recording of the performanc monitoring log message
2012-07-06 06:22:19 -03:00
static int32_t perf_mon_timer;
2012-01-16 13:28:03 -04:00
// The maximum main loop execution time recorded in the current performance monitoring interval
static int G_Dt_max = 0;
// The number of gps fixes recorded in the current performance monitoring interval
2012-07-06 06:22:19 -03:00
static int16_t gps_fix_count = 0;
2012-01-16 13:28:03 -04:00
// A variable used by developers to track performanc metrics.
// Currently used to record the number of GCS heartbeat messages received
2012-07-06 06:22:19 -03:00
static int16_t pmTest1 = 0;
2011-09-08 22:45:13 -03:00
2011-09-08 22:29:39 -03:00
2012-01-16 13:28:03 -04:00
////////////////////////////////////////////////////////////////////////////////
2011-09-08 22:29:39 -03:00
// System Timers
2012-01-16 13:28:03 -04:00
////////////////////////////////////////////////////////////////////////////////
// Time in miliseconds of start of main control loop. Milliseconds
2012-07-06 06:22:19 -03:00
static uint32_t fast_loopTimer;
2012-01-16 13:28:03 -04:00
// Time Stamp when fast loop was complete. Milliseconds
2012-07-06 06:22:19 -03:00
static uint32_t fast_loopTimeStamp;
2012-01-16 13:28:03 -04:00
// Number of milliseconds used in last main loop cycle
static uint8_t delta_ms_fast_loop;
// Counter of main loop executions. Used for performance monitoring and failsafe processing
2011-12-21 08:23:55 -04:00
static uint16_t mainLoop_count;
2011-09-09 11:18:38 -03:00
2012-01-16 13:28:03 -04:00
// Time in miliseconds of start of medium control loop. Milliseconds
2012-07-06 06:22:19 -03:00
static uint32_t medium_loopTimer;
2012-01-16 13:28:03 -04:00
// Counters for branching from main control loop to slower loops
2012-06-10 17:10:07 -03:00
static byte medium_loopCounter;
2012-01-16 13:28:03 -04:00
// Number of milliseconds used in last medium loop cycle
2011-09-09 11:18:38 -03:00
static uint8_t delta_ms_medium_loop;
2011-09-08 22:45:13 -03:00
2012-01-16 13:28:03 -04:00
// Counters for branching from medium control loop to slower loops
2011-09-09 11:18:38 -03:00
static byte slow_loopCounter;
2012-01-16 13:28:03 -04:00
// Counter to trigger execution of very low rate processes
2011-09-09 11:18:38 -03:00
static byte superslow_loopCounter;
2012-01-16 13:28:03 -04:00
// Counter to trigger execution of 1 Hz processes
static byte counter_one_herz;
2011-09-08 22:45:13 -03:00
2012-01-16 13:28:03 -04:00
// % MCU cycles used
static float load;
2011-09-08 22:45:13 -03:00
2011-10-31 18:55:58 -03:00
2012-06-13 15:55:19 -03:00
// Camera/Antenna mount tracking and stabilisation stuff
// --------------------------------------
#if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only.
// mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
AP_Mount camera_mount(¤t_loc, g_gps, &ahrs);
#endif
2012-06-13 16:00:20 -03:00
#if CAMERA == ENABLED
//pinMode(camtrig, OUTPUT); // these are free pins PE3(5), PH3(15), PH6(18), PB4(23), PB5(24), PL1(36), PL3(38), PA6(72), PA7(71), PK0(89), PK1(88), PK2(87), PK3(86), PK4(83), PK5(84), PK6(83), PK7(82)
#endif
2011-10-31 18:55:58 -03:00
2011-09-08 22:29:39 -03:00
////////////////////////////////////////////////////////////////////////////////
// Top-level logic
////////////////////////////////////////////////////////////////////////////////
void setup() {
2011-09-09 11:18:38 -03:00
memcheck_init();
2011-09-08 22:29:39 -03:00
init_ardupilot();
}
void loop()
{
// We want this to execute at 50Hz if possible
// -------------------------------------------
if (millis()-fast_loopTimer > 19) {
delta_ms_fast_loop = millis() - fast_loopTimer;
load = (float)(fast_loopTimeStamp - fast_loopTimer)/delta_ms_fast_loop;
G_Dt = (float)delta_ms_fast_loop / 1000.f;
fast_loopTimer = millis();
mainLoop_count++;
// Execute the fast loop
// ---------------------
fast_loop();
// Execute the medium loop
// -----------------------
medium_loop();
counter_one_herz++;
if(counter_one_herz == 50){
one_second_loop();
counter_one_herz = 0;
}
if (millis() - perf_mon_timer > 20000) {
if (mainLoop_count != 0) {
if (g.log_bitmask & MASK_LOG_PM)
2011-11-16 11:29:40 -04:00
#if HIL_MODE != HIL_MODE_ATTITUDE
2011-09-08 22:29:39 -03:00
Log_Write_Performance();
2011-11-16 11:29:40 -04:00
#endif
2011-09-08 22:29:39 -03:00
resetPerfData();
}
}
fast_loopTimeStamp = millis();
}
}
// Main loop 50Hz
2011-09-09 11:18:38 -03:00
static void fast_loop()
2011-09-08 22:29:39 -03:00
{
// This is the fast loop - we want it to execute at 50Hz if possible
// -----------------------------------------------------------------
if (delta_ms_fast_loop > G_Dt_max)
G_Dt_max = delta_ms_fast_loop;
// Read radio
// ----------
read_radio();
2011-09-09 11:18:38 -03:00
// try to send any deferred messages if the serial port now has
2011-12-09 19:40:56 -04:00
// some space available
2011-09-18 00:46:42 -03:00
gcs_send_message(MSG_RETRY_DEFERRED);
2011-09-09 11:18:38 -03:00
2011-09-08 22:29:39 -03:00
// check for loss of control signal failsafe condition
// ------------------------------------
check_short_failsafe();
2011-12-09 19:40:56 -04:00
// Read Airspeed
// -------------
2012-07-15 22:21:50 -03:00
if (airspeed.enabled()) {
2012-07-23 20:16:09 -03:00
#if HIL_MODE != HIL_MODE_ATTITUDE
2011-09-08 22:29:39 -03:00
read_airspeed();
2012-07-23 20:16:09 -03:00
#endif
2011-09-08 22:29:39 -03:00
}
#if HIL_MODE == HIL_MODE_SENSORS
2012-03-11 05:13:31 -03:00
// update hil before AHRS update
2011-10-13 11:22:03 -03:00
gcs_update();
2011-09-08 22:29:39 -03:00
#endif
2012-03-11 05:13:31 -03:00
ahrs.update();
2011-09-08 22:29:39 -03:00
// uses the yaw from the DCM to give more accurate turns
calc_bearing_error();
# if HIL_MODE == HIL_MODE_DISABLED
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
2012-07-06 06:22:19 -03:00
Log_Write_Attitude(ahrs.roll_sensor, ahrs.pitch_sensor, ahrs.yaw_sensor);
2011-09-08 22:29:39 -03:00
if (g.log_bitmask & MASK_LOG_RAW)
Log_Write_Raw();
#endif
// inertial navigation
// ------------------
#if INERTIAL_NAVIGATION == ENABLED
// TODO: implement inertial nav function
inertialNavigation();
#endif
// custom code/exceptions for flight modes
// ---------------------------------------
update_current_flight_mode();
// apply desired roll, pitch and yaw to the plane
// ----------------------------------------------
if (control_mode > MANUAL)
stabilize();
// write out the servo PWM values
// ------------------------------
2011-09-09 11:18:38 -03:00
set_servos();
2011-09-08 22:29:39 -03:00
2011-09-18 01:00:49 -03:00
gcs_update();
2012-04-01 20:24:05 -03:00
gcs_data_stream_send();
2011-09-08 22:29:39 -03:00
}
2011-09-09 11:18:38 -03:00
static void medium_loop()
2011-09-08 22:29:39 -03:00
{
2011-10-31 18:55:58 -03:00
#if MOUNT == ENABLED
camera_mount.update_mount_position();
#endif
2012-06-13 16:00:20 -03:00
#if CAMERA == ENABLED
g.camera.trigger_pic_cleanup();
#endif
2011-09-08 22:29:39 -03:00
// This is the start of the medium (10 Hz) loop pieces
// -----------------------------------------
switch(medium_loopCounter) {
// This case deals with the GPS
//-------------------------------
case 0:
medium_loopCounter++;
2011-12-09 19:40:56 -04:00
if(GPS_enabled){
update_GPS();
calc_gndspeed_undershoot();
}
2011-09-08 22:29:39 -03:00
#if HIL_MODE != HIL_MODE_ATTITUDE
2011-12-28 05:33:47 -04:00
if (g.compass_enabled && compass.read()) {
2012-03-11 05:13:31 -03:00
ahrs.set_compass(&compass);
2012-03-27 01:16:41 -03:00
compass.null_offsets();
2012-02-24 23:26:54 -04:00
} else {
2012-03-11 05:13:31 -03:00
ahrs.set_compass(NULL);
2011-12-28 05:33:47 -04:00
}
2011-09-08 22:29:39 -03:00
#endif
/*{
2012-03-11 05:13:31 -03:00
Serial.print(ahrs.roll_sensor, DEC); Serial.printf_P(PSTR("\t"));
Serial.print(ahrs.pitch_sensor, DEC); Serial.printf_P(PSTR("\t"));
Serial.print(ahrs.yaw_sensor, DEC); Serial.printf_P(PSTR("\t"));
2011-09-08 22:29:39 -03:00
Vector3f tempaccel = imu.get_accel();
Serial.print(tempaccel.x, DEC); Serial.printf_P(PSTR("\t"));
Serial.print(tempaccel.y, DEC); Serial.printf_P(PSTR("\t"));
Serial.println(tempaccel.z, DEC);
}*/
break;
// This case performs some navigation computations
//------------------------------------------------
case 1:
medium_loopCounter++;
if(g_gps->new_data){
g_gps->new_data = false;
// calculate the plane's desired bearing
// -------------------------------------
navigate();
}
break;
// command processing
//------------------------------
case 2:
medium_loopCounter++;
// Read altitude from sensors
// ------------------
update_alt();
2011-09-09 11:18:38 -03:00
if(g.sonar_enabled) sonar_alt = sonar.read();
2011-09-08 22:29:39 -03:00
// altitude smoothing
// ------------------
if (control_mode != FLY_BY_WIRE_B)
calc_altitude_error();
// perform next command
// --------------------
update_commands();
break;
// This case deals with sending high rate telemetry
//-------------------------------------------------
case 3:
medium_loopCounter++;
#if HIL_MODE != HIL_MODE_ATTITUDE
if ((g.log_bitmask & MASK_LOG_ATTITUDE_MED) && !(g.log_bitmask & MASK_LOG_ATTITUDE_FAST))
2012-07-06 06:22:19 -03:00
Log_Write_Attitude(ahrs.roll_sensor, ahrs.pitch_sensor, ahrs.yaw_sensor);
2011-09-08 22:29:39 -03:00
if (g.log_bitmask & MASK_LOG_CTUN)
Log_Write_Control_Tuning();
#endif
if (g.log_bitmask & MASK_LOG_NTUN)
Log_Write_Nav_Tuning();
if (g.log_bitmask & MASK_LOG_GPS)
Log_Write_GPS(g_gps->time, current_loc.lat, current_loc.lng, g_gps->altitude, current_loc.alt, (long) g_gps->ground_speed, g_gps->ground_course, g_gps->fix, g_gps->num_sats);
break;
// This case controls the slow loop
//---------------------------------
case 4:
medium_loopCounter = 0;
delta_ms_medium_loop = millis() - medium_loopTimer;
medium_loopTimer = millis();
if (g.battery_monitoring != 0){
read_battery();
}
slow_loop();
break;
}
}
2011-09-09 11:18:38 -03:00
static void slow_loop()
2011-09-08 22:29:39 -03:00
{
// This is the slow (3 1/3 Hz) loop pieces
//----------------------------------------
switch (slow_loopCounter){
case 0:
slow_loopCounter++;
check_long_failsafe();
superslow_loopCounter++;
if(superslow_loopCounter >=200) { // 200 = Execute every minute
#if HIL_MODE != HIL_MODE_ATTITUDE
if(g.compass_enabled) {
compass.save_offsets();
}
#endif
superslow_loopCounter = 0;
}
break;
case 1:
slow_loopCounter++;
// Read 3-position switch on radio
// -------------------------------
read_control_switch();
// Read Control Surfaces/Mix switches
// ----------------------------------
2011-09-09 11:18:38 -03:00
update_servo_switches();
2012-07-18 17:01:19 -03:00
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
2011-09-12 20:54:47 -03:00
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
2012-07-18 17:01:19 -03:00
#else
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11);
#endif
2011-09-08 22:29:39 -03:00
break;
case 2:
slow_loopCounter = 0;
update_events();
2011-09-17 23:15:23 -03:00
mavlink_system.sysid = g.sysid_this_mav; // This is just an ugly hack to keep mavlink_system.sysid sync'd with our parameter
2011-11-20 05:31:45 -04:00
#if USB_MUX_PIN > 0
check_usb_mux();
#endif
2011-09-08 22:29:39 -03:00
break;
}
}
2011-09-09 11:18:38 -03:00
static void one_second_loop()
2011-09-08 22:29:39 -03:00
{
if (g.log_bitmask & MASK_LOG_CUR)
Log_Write_Current();
// send a heartbeat
2011-09-18 00:46:42 -03:00
gcs_send_message(MSG_HEARTBEAT);
2011-09-08 22:29:39 -03:00
}
2011-09-09 11:18:38 -03:00
static void update_GPS(void)
2011-09-08 22:29:39 -03:00
{
g_gps->update();
update_GPS_light();
if (g_gps->new_data && g_gps->fix) {
// for performance
// ---------------
gps_fix_count++;
if(ground_start_count > 1){
ground_start_count--;
ground_start_avg += g_gps->ground_speed;
} else if (ground_start_count == 1) {
// We countdown N number of good GPS fixes
// so that the altitude is more accurate
// -------------------------------------
if (current_loc.lat == 0) {
ground_start_count = 5;
} else {
if(ENABLE_AIR_START == 1 && (ground_start_avg / 5) < SPEEDFILT){
startup_ground();
if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
init_home();
} else if (ENABLE_AIR_START == 0) {
init_home();
}
2012-03-11 07:46:41 -03:00
if (g.compass_enabled) {
2012-03-10 19:20:54 -04:00
// Set compass declination automatically
2012-03-30 00:19:02 -03:00
compass.set_initial_location(g_gps->latitude, g_gps->longitude);
2012-03-10 19:20:54 -04:00
}
2011-09-08 22:29:39 -03:00
ground_start_count = 0;
}
}
current_loc.lng = g_gps->longitude; // Lon * 10**7
current_loc.lat = g_gps->latitude; // Lat * 10**7
2011-12-15 03:09:29 -04:00
// see if we've breached the geo-fence
2011-12-15 21:41:11 -04:00
geofence_check(false);
2011-09-08 22:29:39 -03:00
}
}
2011-09-09 11:18:38 -03:00
static void update_current_flight_mode(void)
2011-09-08 22:29:39 -03:00
{
if(control_mode == AUTO){
crash_checker();
2011-10-25 22:27:23 -03:00
switch(nav_command_ID){
2011-09-08 22:29:39 -03:00
case MAV_CMD_NAV_TAKEOFF:
2012-02-14 17:44:33 -04:00
if (hold_course != -1) {
2011-09-08 22:29:39 -03:00
calc_nav_roll();
} else {
nav_roll = 0;
}
2012-07-15 22:21:50 -03:00
if(airspeed.use()) {
2011-09-08 22:29:39 -03:00
calc_nav_pitch();
2012-06-10 17:10:07 -03:00
if(nav_pitch < (long)takeoff_pitch)
nav_pitch = (long)takeoff_pitch;
2011-09-08 22:29:39 -03:00
} else {
2012-07-18 21:52:08 -03:00
nav_pitch = (long)((float)g_gps->ground_speed / (float)g.airspeed_cruise_cm * (float)takeoff_pitch * 0.5);
2011-09-08 22:29:39 -03:00
nav_pitch = constrain(nav_pitch, 500l, (long)takeoff_pitch);
}
g.channel_throttle.servo_out = g.throttle_max; //TODO: Replace with THROTTLE_TAKEOFF or other method of controlling throttle
// What is the case for doing something else? Why wouldn't you want max throttle for TO?
// ******************************
break;
case MAV_CMD_NAV_LAND:
calc_nav_roll();
2012-07-15 22:21:50 -03:00
if (airspeed.use()) {
2011-09-08 22:29:39 -03:00
calc_nav_pitch();
calc_throttle();
}else{
calc_nav_pitch(); // calculate nav_pitch just to use for calc_throttle
calc_throttle(); // throttle based on altitude error
2012-07-18 03:06:23 -03:00
nav_pitch = g.land_pitch_cd; // pitch held constant
2011-09-08 22:29:39 -03:00
}
2012-02-14 17:44:33 -04:00
if (land_complete) {
// we are in the final stage of a landing - force
// zero throttle
2011-09-08 22:29:39 -03:00
g.channel_throttle.servo_out = 0;
}
break;
default:
2012-02-14 17:44:33 -04:00
// we are doing normal AUTO flight, the special cases
// are for takeoff and landing
2011-09-08 22:29:39 -03:00
hold_course = -1;
calc_nav_roll();
calc_nav_pitch();
calc_throttle();
break;
}
}else{
2012-02-14 17:44:33 -04:00
// hold_course is only used in takeoff and landing
hold_course = -1;
2011-09-08 22:29:39 -03:00
switch(control_mode){
case RTL:
case LOITER:
2011-09-09 11:18:38 -03:00
case GUIDED:
2011-09-08 22:29:39 -03:00
crash_checker();
calc_nav_roll();
calc_nav_pitch();
calc_throttle();
break;
case FLY_BY_WIRE_A:
2011-09-30 10:22:56 -03:00
// set nav_roll and nav_pitch using sticks
2011-09-08 22:29:39 -03:00
nav_roll = g.channel_roll.norm_input() * g.roll_limit;
nav_pitch = g.channel_pitch.norm_input() * (-1) * g.pitch_limit_min;
// We use pitch_min above because it is usually greater magnitude then pitch_max. -1 is to compensate for its sign.
nav_pitch = constrain(nav_pitch, -3000, 3000); // trying to give more pitch authority
2011-09-09 11:18:38 -03:00
if (inverted_flight) nav_pitch = -nav_pitch;
2011-09-08 22:29:39 -03:00
break;
case FLY_BY_WIRE_B:
2011-10-17 02:11:40 -03:00
// Substitute stick inputs for Navigation control output
2011-09-08 22:29:39 -03:00
// We use g.pitch_limit_min because its magnitude is
// normally greater than g.pitch_limit_max
2012-07-18 17:01:19 -03:00
2012-07-09 19:36:50 -03:00
// Thanks to Yury MonZon for the altitude limit code!
2011-09-08 22:29:39 -03:00
nav_roll = g.channel_roll.norm_input() * g.roll_limit;
altitude_error = g.channel_pitch.norm_input() * g.pitch_limit_min;
2011-12-31 18:44:40 -04:00
if ((current_loc.alt>=home.alt+g.FBWB_min_altitude) || (g.FBWB_min_altitude == 0)) {
2011-10-17 02:11:40 -03:00
altitude_error = g.channel_pitch.norm_input() * g.pitch_limit_min;
} else {
2011-12-09 19:40:56 -04:00
if (g.channel_pitch.norm_input()<0)
altitude_error =( (home.alt + g.FBWB_min_altitude) - current_loc.alt) + g.channel_pitch.norm_input() * g.pitch_limit_min ;
else altitude_error =( (home.alt + g.FBWB_min_altitude) - current_loc.alt) ;
2011-10-17 02:11:40 -03:00
}
2011-09-08 22:29:39 -03:00
calc_throttle();
calc_nav_pitch();
break;
case STABILIZE:
nav_roll = 0;
nav_pitch = 0;
// throttle is passthrough
break;
case CIRCLE:
// we have no GPS installed and have lost radio contact
// or we just want to fly around in a gentle circle w/o GPS
// ----------------------------------------------------
nav_roll = g.roll_limit / 3;
nav_pitch = 0;
if (failsafe != FAILSAFE_NONE){
g.channel_throttle.servo_out = g.throttle_cruise;
}
break;
case MANUAL:
// servo_out is for Sim control only
// ---------------------------------
g.channel_roll.servo_out = g.channel_roll.pwm_to_angle();
g.channel_pitch.servo_out = g.channel_pitch.pwm_to_angle();
g.channel_rudder.servo_out = g.channel_rudder.pwm_to_angle();
break;
//roll: -13788.000, pitch: -13698.000, thr: 0.000, rud: -13742.000
}
}
}
2011-09-09 11:18:38 -03:00
static void update_navigation()
2011-09-08 22:29:39 -03:00
{
// wp_distance is in ACTUAL meters, not the *100 meters we get from the GPS
// ------------------------------------------------------------------------
// distance and bearing calcs only
if(control_mode == AUTO){
verify_commands();
}else{
switch(control_mode){
case LOITER:
2011-09-09 11:18:38 -03:00
case RTL:
case GUIDED:
2011-09-08 22:29:39 -03:00
update_loiter();
calc_bearing_error();
break;
}
}
}
2011-09-09 11:18:38 -03:00
static void update_alt()
2011-09-08 22:29:39 -03:00
{
#if HIL_MODE == HIL_MODE_ATTITUDE
current_loc.alt = g_gps->altitude;
#else
// this function is in place to potentially add a sonar sensor in the future
//altitude_sensor = BARO;
2011-12-28 05:34:11 -04:00
if (barometer.healthy) {
current_loc.alt = (1 - g.altitude_mix) * g_gps->altitude; // alt_MSL centimeters (meters * 100)
current_loc.alt += g.altitude_mix * (read_barometer() + home.alt);
} else if (g_gps->fix) {
2012-06-10 17:10:07 -03:00
current_loc.alt = g_gps->altitude; // alt_MSL centimeters (meters * 100)
2011-12-28 05:34:11 -04:00
}
2011-09-08 22:29:39 -03:00
#endif
2011-12-15 21:41:11 -04:00
geofence_check(true);
2011-09-08 22:29:39 -03:00
// Calculate new climb rate
2011-09-09 11:18:38 -03:00
//if(medium_loopCounter == 0 && slow_loopCounter == 0)
// add_altitude_data(millis() / 100, g_gps->altitude / 10);
2011-09-08 22:29:39 -03:00
}