2011-03-19 07:20:11 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2014-08-17 23:45:54 -03:00
|
|
|
#define THISFIRMWARE "ArduCopter V3.3-dev"
|
2013-08-29 02:34:47 -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/>.
|
|
|
|
*/
|
2010-12-19 12:40:33 -04:00
|
|
|
/*
|
2013-05-01 05:53:11 -03:00
|
|
|
* ArduCopter Version 3.0
|
2013-05-03 04:58:00 -03:00
|
|
|
* Creator: Jason Short
|
|
|
|
* Lead Developer: Randy Mackay
|
2013-11-15 23:10:38 -04:00
|
|
|
* Lead Tester: Marco Robustini
|
|
|
|
* Based on code and ideas from the Arducopter team: Leonard Hall, Andrew Tridgell, Robert Lefebvre, Pat Hickey, Michael Oborne, Jani Hirvinen,
|
|
|
|
Olivier Adler, Kevin Hester, Arthur Benemann, Jonathan Challinger, John Arne Birkeland,
|
|
|
|
Jean-Louis Naudin, Mike Smith, and more
|
|
|
|
* Thanks to: Chris Anderson, Jordi Munoz, Jason Short, Doug Weibel, Jose Julio
|
2012-08-21 23:19:50 -03:00
|
|
|
*
|
2013-11-15 23:10:38 -04:00
|
|
|
* Special Thanks to contributors (in alphabetical order by first name):
|
2012-08-21 23:19:50 -03:00
|
|
|
*
|
2014-04-23 23:26:10 -03:00
|
|
|
* Adam M Rivera :Auto Compass Declination
|
|
|
|
* Amilcar Lucas :Camera mount library
|
|
|
|
* Andrew Tridgell :General development, Mavlink Support
|
|
|
|
* Angel Fernandez :Alpha testing
|
2013-11-15 23:10:38 -04:00
|
|
|
* AndreasAntonopoulous:GeoFence
|
|
|
|
* Arthur Benemann :DroidPlanner GCS
|
|
|
|
* Benjamin Pelletier :Libraries
|
|
|
|
* Bill King :Single Copter
|
2014-04-23 23:26:10 -03:00
|
|
|
* Christof Schmid :Alpha testing
|
2013-11-15 23:10:38 -04:00
|
|
|
* Craig Elder :Release Management, Support
|
2013-01-11 02:28:08 -04:00
|
|
|
* Dani Saez :V Octo Support
|
2014-04-23 23:26:10 -03:00
|
|
|
* Doug Weibel :DCM, Libraries, Control law advice
|
|
|
|
* Emile Castelnuovo :VRBrain port, bug fixes
|
|
|
|
* Gregory Fletcher :Camera mount orientation math
|
|
|
|
* Guntars :Arming safety suggestion
|
|
|
|
* HappyKillmore :Mavlink GCS
|
2013-11-15 23:10:38 -04:00
|
|
|
* Hein Hollander :Octo Support, Heli Testing
|
2012-08-21 23:19:50 -03:00
|
|
|
* Igor van Airde :Control Law optimization
|
2014-04-23 23:26:10 -03:00
|
|
|
* Jack Dunkle :Alpha testing
|
|
|
|
* James Goppert :Mavlink Support
|
|
|
|
* Jani Hiriven :Testing feedback
|
2013-11-15 23:10:38 -04:00
|
|
|
* Jean-Louis Naudin :Auto Landing
|
2012-08-21 23:19:50 -03:00
|
|
|
* John Arne Birkeland :PPM Encoder
|
2014-04-23 23:26:10 -03:00
|
|
|
* Jose Julio :Stabilization Control laws, MPU6k driver
|
2014-07-11 02:08:09 -03:00
|
|
|
* Julien Dubois :PosHold flight mode
|
2013-11-15 23:10:38 -04:00
|
|
|
* Julian Oes :Pixhawk
|
|
|
|
* Jonathan Challinger :Inertial Navigation, CompassMot, Spin-When-Armed
|
|
|
|
* Kevin Hester :Andropilot GCS
|
2014-04-23 23:26:10 -03:00
|
|
|
* Max Levine :Tri Support, Graphics
|
|
|
|
* Leonard Hall :Flight Dynamics, Throttle, Loiter and Navigation Controllers
|
|
|
|
* Marco Robustini :Lead tester
|
|
|
|
* Michael Oborne :Mission Planner GCS
|
|
|
|
* Mike Smith :Pixhawk driver, coding support
|
2013-11-15 23:10:38 -04:00
|
|
|
* Olivier Adler :PPM Encoder, piezo buzzer
|
2014-04-23 23:26:10 -03:00
|
|
|
* Pat Hickey :Hardware Abstraction Layer (HAL)
|
|
|
|
* Robert Lefebvre :Heli Support, Copter LEDs
|
2013-11-15 23:10:38 -04:00
|
|
|
* Roberto Navoni :Library testing, Porting to VRBrain
|
|
|
|
* Sandro Benigno :Camera support, MinimOSD
|
2014-07-11 02:08:09 -03:00
|
|
|
* Sandro Tognana :PosHold flight mode
|
2013-11-15 23:10:38 -04:00
|
|
|
* ..and many more.
|
2012-08-21 23:19:50 -03:00
|
|
|
*
|
2013-11-15 23:10:38 -04:00
|
|
|
* Code commit statistics can be found here: https://github.com/diydrones/ardupilot/graphs/contributors
|
|
|
|
* Wiki: http://copter.ardupilot.com/
|
|
|
|
* Requires modified version of Arduino, which can be found here: http://ardupilot.com/downloads/?category=6
|
2012-08-21 23:19:50 -03:00
|
|
|
*
|
|
|
|
*/
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Header includes
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
2012-12-12 21:25:09 -04:00
|
|
|
#include <math.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdarg.h>
|
2012-12-12 19:46:20 -04:00
|
|
|
|
|
|
|
// Common dependencies
|
2010-12-19 12:40:33 -04:00
|
|
|
#include <AP_Common.h>
|
2012-10-27 00:55:17 -03:00
|
|
|
#include <AP_Progmem.h>
|
2012-10-19 00:53:39 -03:00
|
|
|
#include <AP_Menu.h>
|
2012-08-20 20:22:44 -03:00
|
|
|
#include <AP_Param.h>
|
2014-08-13 01:44:31 -03:00
|
|
|
#include <StorageManager.h>
|
2012-12-12 19:46:20 -04:00
|
|
|
// AP_HAL
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <AP_HAL_AVR.h>
|
|
|
|
#include <AP_HAL_AVR_SITL.h>
|
2013-01-02 07:08:40 -04:00
|
|
|
#include <AP_HAL_PX4.h>
|
2014-03-31 14:57:45 -03:00
|
|
|
#include <AP_HAL_VRBRAIN.h>
|
2013-09-23 04:06:51 -03:00
|
|
|
#include <AP_HAL_FLYMAPLE.h>
|
2013-09-28 08:46:14 -03:00
|
|
|
#include <AP_HAL_Linux.h>
|
2012-12-18 06:15:11 -04:00
|
|
|
#include <AP_HAL_Empty.h>
|
2012-12-12 21:25:09 -04:00
|
|
|
|
2012-12-12 19:46:20 -04:00
|
|
|
// Application dependencies
|
2014-01-16 03:35:43 -04:00
|
|
|
#include <GCS.h>
|
2012-12-12 19:46:20 -04:00
|
|
|
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
2015-01-19 09:52:54 -04:00
|
|
|
#include <AP_SerialManager.h> // Serial manager library
|
2012-11-10 01:29:56 -04:00
|
|
|
#include <AP_GPS.h> // ArduPilot GPS library
|
2013-09-19 03:56:36 -03:00
|
|
|
#include <AP_GPS_Glitch.h> // GPS glitch protection library
|
2012-11-10 01:29:56 -04:00
|
|
|
#include <DataFlash.h> // ArduPilot Mega Flash Memory Library
|
|
|
|
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
2012-12-12 20:16:32 -04:00
|
|
|
#include <AP_ADC_AnalogSource.h>
|
2011-11-27 01:35:23 -04:00
|
|
|
#include <AP_Baro.h>
|
2014-07-28 05:38:32 -03:00
|
|
|
#include <AP_Baro_Glitch.h> // Baro glitch protection library
|
2012-11-10 01:29:56 -04:00
|
|
|
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
|
|
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
|
|
|
#include <AP_Curve.h> // Curve used to linearlise throttle pwm to thrust
|
|
|
|
#include <AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
2012-03-11 05:36:12 -03:00
|
|
|
#include <AP_AHRS.h>
|
2014-01-02 01:05:06 -04:00
|
|
|
#include <AP_NavEKF.h>
|
2014-02-27 21:16:54 -04:00
|
|
|
#include <AP_Mission.h> // Mission command library
|
2014-04-06 22:18:43 -03:00
|
|
|
#include <AP_Rally.h> // Rally point library
|
2012-11-10 01:29:56 -04:00
|
|
|
#include <AC_PID.h> // PID library
|
2014-05-02 18:44:09 -03:00
|
|
|
#include <AC_HELI_PID.h> // Heli specific Rate PID library
|
2014-02-14 03:08:59 -04:00
|
|
|
#include <AC_P.h> // P library
|
2014-01-29 09:51:08 -04:00
|
|
|
#include <AC_AttitudeControl.h> // Attitude control library
|
|
|
|
#include <AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
|
2013-12-29 02:42:58 -04:00
|
|
|
#include <AC_PosControl.h> // Position control library
|
2012-11-10 01:29:56 -04:00
|
|
|
#include <RC_Channel.h> // RC Channel Library
|
2012-08-21 23:19:50 -03:00
|
|
|
#include <AP_Motors.h> // AP Motors library
|
|
|
|
#include <AP_RangeFinder.h> // Range finder library
|
2012-11-10 01:29:56 -04:00
|
|
|
#include <AP_OpticalFlow.h> // Optical Flow library
|
|
|
|
#include <Filter.h> // Filter library
|
|
|
|
#include <AP_Buffer.h> // APM FIFO Buffer
|
2012-08-21 23:19:50 -03:00
|
|
|
#include <AP_Relay.h> // APM relay
|
2014-01-20 01:05:31 -04:00
|
|
|
#include <AP_ServoRelayEvents.h>
|
2012-08-21 23:19:50 -03:00
|
|
|
#include <AP_Camera.h> // Photo or video camera
|
|
|
|
#include <AP_Mount.h> // Camera/Antenna mount
|
2012-11-10 01:29:56 -04:00
|
|
|
#include <AP_Airspeed.h> // needed for AHRS build
|
2013-09-12 22:47:03 -03:00
|
|
|
#include <AP_Vehicle.h> // needed for AHRS build
|
2012-11-07 09:24:00 -04:00
|
|
|
#include <AP_InertialNav.h> // ArduPilot Mega inertial navigation library
|
2013-03-20 10:29:08 -03:00
|
|
|
#include <AC_WPNav.h> // ArduCopter waypoint navigation library
|
2014-01-27 01:10:12 -04:00
|
|
|
#include <AC_Circle.h> // circle navigation library
|
2012-12-12 19:46:20 -04:00
|
|
|
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
2013-04-26 06:51:07 -03:00
|
|
|
#include <AC_Fence.h> // Arducopter Fence library
|
2013-01-11 21:01:10 -04:00
|
|
|
#include <SITL.h> // software in the loop support
|
|
|
|
#include <AP_Scheduler.h> // main loop scheduler
|
2013-03-24 23:48:06 -03:00
|
|
|
#include <AP_RCMapper.h> // RC input mapping library
|
2013-08-24 05:58:48 -03:00
|
|
|
#include <AP_Notify.h> // Notify library
|
2013-10-01 10:34:44 -03:00
|
|
|
#include <AP_BattMonitor.h> // Battery monitor library
|
2014-01-19 21:58:12 -04:00
|
|
|
#include <AP_BoardConfig.h> // board configuration library
|
2014-07-28 19:25:40 -03:00
|
|
|
#include <AP_Frsky_Telem.h>
|
2013-09-08 22:18:06 -03:00
|
|
|
#if SPRAYER == ENABLED
|
|
|
|
#include <AC_Sprayer.h> // crop sprayer library
|
|
|
|
#endif
|
2013-12-17 00:58:11 -04:00
|
|
|
#if EPM_ENABLED == ENABLED
|
|
|
|
#include <AP_EPM.h> // EPM cargo gripper stuff
|
|
|
|
#endif
|
2014-04-02 12:19:54 -03:00
|
|
|
#if PARACHUTE == ENABLED
|
|
|
|
#include <AP_Parachute.h> // Parachute release library
|
|
|
|
#endif
|
2015-01-06 00:24:50 -04:00
|
|
|
#include <AP_LandingGear.h> // Landing Gear library
|
2014-07-22 05:22:36 -03:00
|
|
|
#include <AP_Terrain.h>
|
2011-04-13 13:33:06 -03:00
|
|
|
|
2012-12-12 20:16:32 -04:00
|
|
|
// AP_HAL to Arduino compatibility layer
|
|
|
|
#include "compat.h"
|
2010-12-19 12:40:33 -04:00
|
|
|
// Configuration
|
2011-06-24 01:37:54 -03:00
|
|
|
#include "defines.h"
|
2010-12-19 12:40:33 -04:00
|
|
|
#include "config.h"
|
2012-01-01 16:24:38 -04:00
|
|
|
#include "config_channels.h"
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2013-10-18 05:03:31 -03:00
|
|
|
// key aircraft parameters passed to multiple libraries
|
|
|
|
static AP_Vehicle::MultiCopter aparm;
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
// Local modules
|
2011-02-17 03:09:13 -04:00
|
|
|
#include "Parameters.h"
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2014-05-10 10:34:30 -03:00
|
|
|
// Heli modules
|
|
|
|
#include "heli.h"
|
|
|
|
|
2012-12-13 19:27:42 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// cliSerial
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// cliSerial isn't strictly necessary - it is an alias for hal.console. It may
|
|
|
|
// be deprecated in favor of hal.console in later releases.
|
2013-04-17 08:35:11 -03:00
|
|
|
static AP_HAL::BetterStream* cliSerial;
|
2012-12-13 19:27:42 -04:00
|
|
|
|
|
|
|
// N.B. we need to keep a static declaration which isn't guarded by macros
|
2013-10-29 01:28:27 -03:00
|
|
|
// at the top to cooperate with the prototype mangler.
|
2012-12-13 19:27:42 -04:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2012-12-12 19:46:20 -04:00
|
|
|
// AP_HAL instance
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2012-12-13 19:27:42 -04:00
|
|
|
|
2012-12-18 06:15:11 -04:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
2012-08-06 22:03:26 -03:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Parameters
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
//
|
|
|
|
// Global parameters are all contained within the 'g' class.
|
|
|
|
//
|
2012-08-21 23:19:50 -03:00
|
|
|
static Parameters g;
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2013-01-11 21:01:10 -04:00
|
|
|
// main loop scheduler
|
2013-04-17 08:35:11 -03:00
|
|
|
static AP_Scheduler scheduler;
|
2011-05-09 14:40:32 -03:00
|
|
|
|
2013-08-29 00:14:07 -03:00
|
|
|
// AP_Notify instance
|
|
|
|
static AP_Notify notify;
|
2013-08-08 10:15:25 -03:00
|
|
|
|
2014-02-07 01:31:34 -04:00
|
|
|
// used to detect MAVLink acks from GCS to stop compassmot
|
|
|
|
static uint8_t command_ack_counter;
|
2013-08-09 00:18:01 -03:00
|
|
|
|
2014-10-16 21:37:49 -03:00
|
|
|
// has a log download started?
|
|
|
|
static bool in_log_download;
|
|
|
|
|
2011-03-17 22:50:46 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// prototypes
|
2011-11-12 23:47:16 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2012-12-12 19:46:20 -04:00
|
|
|
static void update_events(void);
|
2013-04-20 02:18:22 -03:00
|
|
|
static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
2015-02-15 19:02:53 -04:00
|
|
|
static void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
|
|
|
|
2011-11-12 23:47:16 -04:00
|
|
|
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Dataflash
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2012-12-12 19:46:20 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
2013-04-17 08:35:11 -03:00
|
|
|
static DataFlash_APM2 DataFlash;
|
2012-12-13 22:16:32 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
2013-04-17 08:35:11 -03:00
|
|
|
static DataFlash_APM1 DataFlash;
|
2014-07-06 23:05:28 -03:00
|
|
|
#elif defined(HAL_BOARD_LOG_DIRECTORY)
|
|
|
|
static DataFlash_File DataFlash(HAL_BOARD_LOG_DIRECTORY);
|
2013-01-02 07:08:40 -04:00
|
|
|
#else
|
2013-04-17 08:35:11 -03:00
|
|
|
static DataFlash_Empty DataFlash;
|
2011-11-12 23:47:16 -04:00
|
|
|
#endif
|
|
|
|
|
2011-05-09 14:40:32 -03:00
|
|
|
|
2012-11-29 07:56:54 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// the rate we run the main loop at
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-12-16 23:25:33 -04:00
|
|
|
#if MAIN_LOOP_RATE == 400
|
|
|
|
static const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_400HZ;
|
|
|
|
#else
|
2013-08-02 05:48:03 -03:00
|
|
|
static const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_100HZ;
|
2013-12-16 23:25:33 -04:00
|
|
|
#endif
|
2012-11-29 07:56:54 -04:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Sensors
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
//
|
|
|
|
// There are three basic options related to flight sensor selection.
|
|
|
|
//
|
2012-11-10 01:29:56 -04:00
|
|
|
// - Normal flight mode. Real sensors are used.
|
|
|
|
// - HIL Attitude mode. Most sensors are disabled, as the HIL
|
2011-02-17 03:09:13 -04:00
|
|
|
// protocol supplies attitude information directly.
|
2012-11-10 01:29:56 -04:00
|
|
|
// - HIL Sensors mode. Synthetic sensors are configured that
|
2011-02-17 03:09:13 -04:00
|
|
|
// supply data from the simulation.
|
|
|
|
//
|
|
|
|
|
2014-03-31 04:07:46 -03:00
|
|
|
static AP_GPS gps;
|
|
|
|
|
|
|
|
static GPS_Glitch gps_glitch(gps);
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-07-17 07:30:53 -03:00
|
|
|
// flight modes convenience array
|
2012-12-12 19:46:20 -04:00
|
|
|
static AP_Int8 *flight_modes = &g.flight_mode1;
|
2011-07-17 07:30:53 -03:00
|
|
|
|
2015-01-05 07:28:00 -04:00
|
|
|
static AP_Baro barometer;
|
|
|
|
|
2014-07-28 05:38:32 -03:00
|
|
|
static Baro_Glitch baro_glitch(barometer);
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2014-07-06 23:05:28 -03:00
|
|
|
#if CONFIG_COMPASS == HAL_COMPASS_PX4
|
2013-04-17 08:35:11 -03:00
|
|
|
static AP_Compass_PX4 compass;
|
2014-07-06 23:05:28 -03:00
|
|
|
#elif CONFIG_COMPASS == HAL_COMPASS_VRBRAIN
|
2014-03-31 14:57:45 -03:00
|
|
|
static AP_Compass_VRBRAIN compass;
|
2014-07-06 23:05:28 -03:00
|
|
|
#elif CONFIG_COMPASS == HAL_COMPASS_HMC5843
|
2013-04-17 08:35:11 -03:00
|
|
|
static AP_Compass_HMC5843 compass;
|
2014-07-06 23:05:28 -03:00
|
|
|
#elif CONFIG_COMPASS == HAL_COMPASS_HIL
|
|
|
|
static AP_Compass_HIL compass;
|
2014-11-21 12:29:42 -04:00
|
|
|
#elif CONFIG_COMPASS == HAL_COMPASS_AK8963
|
|
|
|
static AP_Compass_AK8963_MPU9250 compass;
|
2014-07-06 23:05:28 -03:00
|
|
|
#else
|
|
|
|
#error Unrecognized CONFIG_COMPASS setting
|
|
|
|
#endif
|
|
|
|
|
2014-10-15 20:33:24 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
2014-07-06 23:05:28 -03:00
|
|
|
AP_ADC_ADS7844 apm1_adc;
|
2013-03-31 05:35:23 -03:00
|
|
|
#endif
|
|
|
|
|
2014-10-15 20:33:24 -03:00
|
|
|
AP_InertialSensor ins;
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2014-02-16 21:34:34 -04:00
|
|
|
// Inertial Navigation EKF
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
2014-03-31 04:07:46 -03:00
|
|
|
AP_AHRS_NavEKF ahrs(ins, barometer, gps);
|
2014-02-16 21:34:34 -04:00
|
|
|
#else
|
2014-03-31 04:07:46 -03:00
|
|
|
AP_AHRS_DCM ahrs(ins, barometer, gps);
|
2014-02-16 21:34:34 -04:00
|
|
|
#endif
|
|
|
|
|
2014-07-06 23:05:28 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
|
|
|
SITL sitl;
|
|
|
|
#endif
|
|
|
|
|
2014-02-27 21:16:54 -04:00
|
|
|
// Mission library
|
|
|
|
// forward declaration to keep compiler happy
|
|
|
|
static bool start_command(const AP_Mission::Mission_Command& cmd);
|
|
|
|
static bool verify_command(const AP_Mission::Mission_Command& cmd);
|
|
|
|
static void exit_mission();
|
2014-08-13 01:44:31 -03:00
|
|
|
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission);
|
2014-02-27 21:16:54 -04:00
|
|
|
|
2013-03-18 01:40:43 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Optical flow sensor
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2015-01-02 04:30:44 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
|
|
|
static OpticalFlow optflow;
|
2014-07-11 23:33:49 -03:00
|
|
|
#endif
|
2014-12-07 22:16:33 -04:00
|
|
|
|
2014-11-15 20:51:46 -04:00
|
|
|
// gnd speed limit required to observe optical flow sensor limits
|
|
|
|
static float ekfGndSpdLimit;
|
2014-11-15 21:42:56 -04:00
|
|
|
// scale factor applied to velocity controller gain to prevent optical flow noise causing excessive angle demand noise
|
|
|
|
static float ekfNavVelGainScaler;
|
2013-03-18 01:40:43 -03:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// GCS selection
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2015-01-19 09:52:54 -04:00
|
|
|
static AP_SerialManager serial_manager;
|
2013-11-23 06:45:42 -04:00
|
|
|
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
|
|
|
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
|
2011-03-26 03:35:52 -03:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2014-06-27 01:23:56 -03:00
|
|
|
// SONAR
|
2011-11-12 23:47:16 -04:00
|
|
|
#if CONFIG_SONAR == ENABLED
|
2014-06-27 01:23:56 -03:00
|
|
|
static RangeFinder sonar;
|
|
|
|
static bool sonar_enabled = true; // enable user switch for sonar
|
2011-11-12 23:47:16 -04:00
|
|
|
#endif
|
2011-02-20 19:09:28 -04:00
|
|
|
|
2011-10-15 19:29:33 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// User variables
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
#ifdef USERHOOK_VARIABLES
|
2012-08-21 23:19:50 -03:00
|
|
|
#include USERHOOK_VARIABLES
|
2011-10-15 19:29:33 -03:00
|
|
|
#endif
|
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Global variables
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
/* Radio values
|
2012-08-21 23:19:50 -03:00
|
|
|
* Channel assignments
|
|
|
|
* 1 Ailerons (rudder if no ailerons)
|
|
|
|
* 2 Elevator
|
|
|
|
* 3 Throttle
|
|
|
|
* 4 Rudder (if we have ailerons)
|
|
|
|
* 5 Mode - 3 position switch
|
|
|
|
* 6 User assignable
|
|
|
|
* 7 trainer switch - sets throttle nominal (toggle switch), sets accels to Level (hold > 1 second)
|
|
|
|
* 8 TBD
|
|
|
|
* 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
|
|
|
|
*/
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
//Documentation of GLobals:
|
2012-11-10 01:39:41 -04:00
|
|
|
static union {
|
|
|
|
struct {
|
2015-02-09 07:23:49 -04:00
|
|
|
uint8_t unused1 : 1; // 0
|
2013-10-01 10:34:44 -03:00
|
|
|
uint8_t simple_mode : 2; // 1,2 // This is the state of simple mode : 0 = disabled ; 1 = SIMPLE ; 2 = SUPERSIMPLE
|
|
|
|
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
|
|
|
|
uint8_t logging_started : 1; // 6 // true if dataflash logging has started
|
2014-02-03 03:22:25 -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
|
|
|
|
uint8_t CH7_flag : 2; // 9,10 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
|
|
|
uint8_t CH8_flag : 2; // 11,12 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
|
|
|
|
uint8_t usb_connected : 1; // 13 // true if APM is powered from USB connection
|
|
|
|
uint8_t rc_receiver_present : 1; // 14 // true if we have an rc receiver present (i.e. if we've ever received an update
|
2014-02-19 00:29:36 -04:00
|
|
|
uint8_t compass_mot : 1; // 15 // true if we are currently performing compassmot calibration
|
2014-04-28 04:27:27 -03:00
|
|
|
uint8_t motor_test : 1; // 16 // true if we are currently performing the motors test
|
2014-09-09 10:17:46 -03:00
|
|
|
uint8_t initialised : 1; // 17 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
|
2014-09-19 03:54:36 -03:00
|
|
|
uint8_t land_complete_maybe : 1; // 18 // true if we may have landed (less strict version of land_complete)
|
2014-10-07 11:01:15 -03:00
|
|
|
uint8_t throttle_zero : 1; // 19 // true if the throttle stick is at zero, debounced
|
2015-02-09 07:23:49 -04:00
|
|
|
uint8_t system_time_set : 1; // 20 // true if the system time has been set from the GPS
|
|
|
|
uint8_t gps_base_pos_set : 1; // 21 // true when the gps base position has been set (used for RTK gps only)
|
|
|
|
enum HomeState home_state : 2; // 22,23 - home status (unset, set, locked)
|
2012-11-10 01:39:41 -04:00
|
|
|
};
|
2014-04-28 04:27:27 -03:00
|
|
|
uint32_t value;
|
2012-11-10 01:39:41 -04:00
|
|
|
} ap;
|
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2010-12-19 12:40:33 -04:00
|
|
|
// Radio
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// This is the state of the flight control system
|
|
|
|
// There are multiple states defined such as STABILIZE, ACRO,
|
2012-11-10 01:39:41 -04:00
|
|
|
static int8_t control_mode = STABILIZE;
|
2014-10-31 03:48:28 -03:00
|
|
|
// Structure used to detect changes in the flight mode control switch
|
2014-10-07 11:50:26 -03:00
|
|
|
static struct {
|
2014-10-31 03:48:28 -03:00
|
|
|
int8_t debounced_switch_position; // currently used switch position
|
|
|
|
int8_t last_switch_position; // switch position in previous iteration
|
|
|
|
uint32_t last_edge_time_ms; // system time that switch position was last changed
|
2014-10-07 11:50:26 -03:00
|
|
|
} control_switch_state;
|
|
|
|
|
2013-03-24 23:48:06 -03:00
|
|
|
static RCMapper rcmap;
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2014-01-19 21:58:12 -04:00
|
|
|
// board specific config
|
|
|
|
static AP_BoardConfig BoardConfig;
|
|
|
|
|
2012-11-22 05:59:33 -04:00
|
|
|
// receiver RSSI
|
|
|
|
static uint8_t receiver_rssi;
|
|
|
|
|
2013-09-26 05:54:33 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Failsafe
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
static struct {
|
|
|
|
uint8_t rc_override_active : 1; // 0 // true if rc control are overwritten by ground station
|
|
|
|
uint8_t radio : 1; // 1 // A status flag for the radio failsafe
|
2013-10-13 01:52:52 -03:00
|
|
|
uint8_t battery : 1; // 2 // A status flag for the battery failsafe
|
2013-09-26 05:54:33 -03:00
|
|
|
uint8_t gps : 1; // 3 // A status flag for the gps failsafe
|
|
|
|
uint8_t gcs : 1; // 4 // A status flag for the ground station failsafe
|
2014-07-21 07:12:17 -03:00
|
|
|
uint8_t ekf : 1; // 5 // true if ekf failsafe has occurred
|
2013-09-26 05:54:33 -03:00
|
|
|
|
|
|
|
int8_t radio_counter; // number of iterations with throttle below throttle_fs_value
|
|
|
|
|
|
|
|
uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe
|
|
|
|
} failsafe;
|
2012-01-04 02:54:29 -04:00
|
|
|
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Motor Output
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2012-11-10 01:29:56 -04:00
|
|
|
#if FRAME_CONFIG == QUAD_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsQuad
|
2013-09-09 03:57:54 -03:00
|
|
|
#elif FRAME_CONFIG == TRI_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsTri
|
2013-09-09 03:57:54 -03:00
|
|
|
#elif FRAME_CONFIG == HEXA_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsHexa
|
2013-09-09 03:57:54 -03:00
|
|
|
#elif FRAME_CONFIG == Y6_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsY6
|
2013-09-09 03:57:54 -03:00
|
|
|
#elif FRAME_CONFIG == OCTA_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsOcta
|
2013-09-09 03:57:54 -03:00
|
|
|
#elif FRAME_CONFIG == OCTA_QUAD_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsOctaQuad
|
2013-09-09 03:57:54 -03:00
|
|
|
#elif FRAME_CONFIG == HELI_FRAME
|
2012-08-21 23:19:50 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsHeli
|
2013-11-13 13:57:48 -04:00
|
|
|
#elif FRAME_CONFIG == SINGLE_FRAME
|
2013-10-02 06:59:04 -03:00
|
|
|
#define MOTOR_CLASS AP_MotorsSingle
|
2014-02-06 08:28:55 -04:00
|
|
|
#elif FRAME_CONFIG == COAX_FRAME
|
|
|
|
#define MOTOR_CLASS AP_MotorsCoax
|
2013-09-09 03:57:54 -03:00
|
|
|
#else
|
|
|
|
#error Unrecognised frame type
|
2012-04-04 10:50:43 -03:00
|
|
|
#endif
|
|
|
|
|
2012-11-10 01:29:56 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments
|
2014-02-10 00:25:11 -04:00
|
|
|
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.rc_7, g.rc_8, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4);
|
2012-05-13 00:36:46 -03:00
|
|
|
#elif FRAME_CONFIG == TRI_FRAME // tri constructor requires additional rc_7 argument to allow tail servo reversing
|
2014-02-10 00:25:11 -04:00
|
|
|
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.rc_7);
|
2013-11-13 13:57:48 -04:00
|
|
|
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
|
2014-02-10 00:25:11 -04:00
|
|
|
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.single_servo_1, g.single_servo_2, g.single_servo_3, g.single_servo_4);
|
2014-02-06 08:28:55 -04:00
|
|
|
#elif FRAME_CONFIG == COAX_FRAME // single constructor requires extra servos for flaps
|
2014-02-10 00:25:11 -04:00
|
|
|
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.single_servo_1, g.single_servo_2);
|
2012-04-04 10:50:43 -03:00
|
|
|
#else
|
2014-02-10 00:25:11 -04:00
|
|
|
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4);
|
2012-04-04 10:50:43 -03:00
|
|
|
#endif
|
2011-11-20 04:21:19 -04:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2010-12-19 12:40:33 -04:00
|
|
|
// GPS variables
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// We use atan2 and other trig techniques to calaculate angles
|
|
|
|
// We need to scale the longitude up to make these calcs work
|
2012-01-15 19:11:02 -04:00
|
|
|
// to account for decreasing distance between lines of longitude away from the equator
|
2012-11-10 01:29:56 -04:00
|
|
|
static float scaleLongUp = 1;
|
2012-01-04 02:54:29 -04:00
|
|
|
// Sometimes we need to remove the scaling for distance calcs
|
2012-11-10 01:29:56 -04:00
|
|
|
static float scaleLongDown = 1;
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Location & Navigation
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-03-22 09:59:17 -03:00
|
|
|
// This is the angle from the copter to the next waypoint in centi-degrees
|
2012-12-08 01:23:32 -04:00
|
|
|
static int32_t wp_bearing;
|
2013-03-22 09:59:17 -03:00
|
|
|
// The location of home in relation to the copter in centi-degrees
|
|
|
|
static int32_t home_bearing;
|
|
|
|
// distance between plane and home in cm
|
|
|
|
static int32_t home_distance;
|
2013-07-14 20:56:45 -03:00
|
|
|
// distance between plane and next waypoint in cm.
|
|
|
|
static uint32_t wp_distance;
|
2013-05-10 10:37:15 -03:00
|
|
|
static uint8_t land_state; // records state of land (flying to location, descending)
|
2012-08-16 19:39:50 -03:00
|
|
|
|
2014-01-27 23:21:16 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Auto
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
static AutoMode auto_mode; // controls which auto controller is run
|
|
|
|
|
2014-06-02 06:06:11 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Guided
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
static GuidedMode guided_mode; // controls which controller is run (pos or vel)
|
|
|
|
|
2014-01-27 23:21:16 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// RTL
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
RTLState rtl_state; // records state of rtl (initial climb, returning home, etc)
|
|
|
|
bool rtl_state_complete; // set to true if the current state is completed
|
|
|
|
|
2014-02-08 23:36:20 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Circle
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
bool circle_pilot_yaw_override; // true if pilot is overriding yaw
|
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// SIMPLE Mode
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Used to track the orientation of the copter for Simple mode. This value is reset at each arming
|
|
|
|
// or in SuperSimple mode when the copter leaves a 20m radius from home.
|
2013-10-05 06:25:03 -03:00
|
|
|
static float simple_cos_yaw = 1.0;
|
|
|
|
static float simple_sin_yaw;
|
|
|
|
static int32_t super_simple_last_bearing;
|
|
|
|
static float super_simple_cos_yaw = 1.0;
|
|
|
|
static float super_simple_sin_yaw;
|
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2013-05-30 13:11:47 -03:00
|
|
|
// Stores initial bearing when armed - initial simple bearing is modified in super simple mode so not suitable
|
|
|
|
static int32_t initial_armed_bearing;
|
|
|
|
|
2012-11-23 02:57:49 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Throttle variables
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
static float throttle_avg; // g.throttle_cruise as a float
|
2012-11-24 03:45:28 -04:00
|
|
|
static int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only
|
2012-11-23 02:57:49 -04:00
|
|
|
|
|
|
|
|
2012-02-19 01:16:19 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// ACRO Mode
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-08-04 05:46:04 -03:00
|
|
|
static float acro_level_mix; // scales back roll, pitch and yaw inversely proportional to input from pilot
|
2012-03-09 03:13:04 -04:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2014-04-16 04:24:09 -03:00
|
|
|
// Loiter control
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2014-02-03 03:22:25 -04:00
|
|
|
static uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds)
|
|
|
|
static uint32_t loiter_time; // How long have we been loitering - The start time in millis
|
2011-11-13 01:43:21 -04:00
|
|
|
|
2014-06-06 00:07:23 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Flip
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
static Vector3f flip_orig_attitude; // original copter attitude before flip
|
2012-01-04 02:54:29 -04:00
|
|
|
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2011-02-25 01:33:39 -04:00
|
|
|
// Battery Sensors
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-10-01 10:34:44 -03:00
|
|
|
static AP_BattMonitor battery;
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2014-07-28 19:25:40 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// FrSky telemetry support
|
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
|
|
|
static AP_Frsky_Telem frsky_telemetry(ahrs, battery);
|
|
|
|
#endif
|
2011-11-05 01:41:51 -03:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Altitude
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2012-03-07 02:22:14 -04:00
|
|
|
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
2012-08-21 23:19:50 -03:00
|
|
|
static int16_t climb_rate;
|
2014-01-19 10:35:55 -04:00
|
|
|
// The altitude as reported by Sonar in cm - Values are 20 to 700 generally.
|
2012-08-21 23:19:50 -03:00
|
|
|
static int16_t sonar_alt;
|
2013-01-08 03:41:07 -04:00
|
|
|
static uint8_t sonar_alt_health; // true if we can trust the altitude from the sonar
|
2013-08-18 21:52:59 -03:00
|
|
|
static float target_sonar_alt; // desired altitude in cm above the ground
|
2014-10-22 04:07:10 -03:00
|
|
|
static int32_t baro_alt; // barometer altitude in cm above home
|
|
|
|
static float baro_climbrate; // barometer climbrate in cm/s
|
2012-11-10 01:39:41 -04:00
|
|
|
|
2012-01-29 02:00:05 -04:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// 3D Location vectors
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2015-02-10 08:33:07 -04:00
|
|
|
// Current location of the copter (altitude is relative to home)
|
2012-08-21 23:19:50 -03:00
|
|
|
static struct Location current_loc;
|
2012-01-04 02:54:29 -04:00
|
|
|
|
|
|
|
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Navigation Yaw control
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2014-01-23 01:16:06 -04:00
|
|
|
// auto flight mode's yaw mode
|
|
|
|
static uint8_t auto_yaw_mode = AUTO_YAW_LOOK_AT_NEXT_WP;
|
2014-02-18 08:35:29 -04:00
|
|
|
// Yaw will point at this location if auto_yaw_mode is set to AUTO_YAW_ROI
|
|
|
|
static Vector3f roi_WP;
|
2012-12-08 01:23:32 -04:00
|
|
|
// bearing from current location to the yaw_look_at_WP
|
2014-01-23 01:16:06 -04:00
|
|
|
static float yaw_look_at_WP_bearing;
|
2012-12-08 01:23:32 -04:00
|
|
|
// yaw used for YAW_LOOK_AT_HEADING yaw_mode
|
|
|
|
static int32_t yaw_look_at_heading;
|
2012-01-04 02:54:29 -04:00
|
|
|
// Deg/s we should turn
|
2012-12-08 01:23:32 -04:00
|
|
|
static int16_t yaw_look_at_heading_slew;
|
2014-01-23 01:16:06 -04:00
|
|
|
// heading when in yaw_look_ahead_bearing
|
|
|
|
static float yaw_look_ahead_bearing;
|
2011-07-17 07:31:46 -03:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Delay Mission Scripting Command
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2012-08-21 23:19:50 -03:00
|
|
|
static int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
|
2012-01-10 00:23:37 -04:00
|
|
|
static uint32_t condition_start;
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-04-20 02:37:05 -03:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2010-12-19 12:40:33 -04:00
|
|
|
// IMU variables
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-08-08 10:09:27 -03:00
|
|
|
// Integration time (in seconds) for the gyros (DCM algorithm)
|
2012-05-17 14:55:13 -03:00
|
|
|
// Updated with the fast loop
|
2012-11-10 01:39:41 -04:00
|
|
|
static float G_Dt = 0.02;
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2012-06-14 02:27:03 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Inertial Navigation
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2014-01-03 07:58:08 -04:00
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
2014-07-28 05:38:32 -03:00
|
|
|
static AP_InertialNav_NavEKF inertial_nav(ahrs, barometer, gps_glitch, baro_glitch);
|
2014-01-03 07:58:08 -04:00
|
|
|
#else
|
2014-07-28 05:38:32 -03:00
|
|
|
static AP_InertialNav inertial_nav(ahrs, barometer, gps_glitch, baro_glitch);
|
2014-01-03 07:58:08 -04:00
|
|
|
#endif
|
2012-06-14 02:27:03 -03:00
|
|
|
|
2013-03-20 10:29:08 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-12-29 02:42:58 -04:00
|
|
|
// Attitude, Position and Waypoint navigation objects
|
2013-03-20 10:29:08 -03:00
|
|
|
// To-Do: move inertial nav up or other navigation variables down here
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2014-01-29 09:51:08 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2014-07-13 04:50:47 -03:00
|
|
|
AC_AttitudeControl_Heli attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
|
2014-08-20 10:16:25 -03:00
|
|
|
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
2014-01-29 09:51:08 -04:00
|
|
|
#else
|
2014-07-13 04:50:47 -03:00
|
|
|
AC_AttitudeControl attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
|
2014-02-10 00:25:11 -04:00
|
|
|
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
2014-01-29 09:51:08 -04:00
|
|
|
#endif
|
2013-12-29 02:42:58 -04:00
|
|
|
AC_PosControl pos_control(ahrs, inertial_nav, motors, attitude_control,
|
2014-02-15 11:00:05 -04:00
|
|
|
g.p_alt_hold, g.p_throttle_rate, g.pid_throttle_accel,
|
2014-02-14 03:08:59 -04:00
|
|
|
g.p_loiter_pos, g.pid_loiter_rate_lat, g.pid_loiter_rate_lon);
|
2014-10-30 01:59:28 -03:00
|
|
|
static AC_WPNav wp_nav(inertial_nav, ahrs, pos_control, attitude_control);
|
2014-01-27 01:10:12 -04:00
|
|
|
static AC_Circle circle_nav(inertial_nav, ahrs, pos_control);
|
2013-03-20 10:29:08 -03:00
|
|
|
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2010-12-19 12:40:33 -04:00
|
|
|
// Performance monitoring
|
2012-01-04 02:54:29 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-04-29 09:30:22 -03:00
|
|
|
static int16_t pmTest1;
|
2010-12-19 12:40:33 -04:00
|
|
|
|
|
|
|
// System Timers
|
|
|
|
// --------------
|
2012-01-04 02:54:29 -04:00
|
|
|
// Time in microseconds of main control loop
|
2012-08-21 23:19:50 -03:00
|
|
|
static uint32_t fast_loopTimer;
|
2012-10-09 00:30:17 -03:00
|
|
|
// Counter of main loop executions. Used for performance monitoring and failsafe processing
|
|
|
|
static uint16_t mainLoop_count;
|
2012-04-16 12:07:57 -03:00
|
|
|
// Loiter timer - Records how long we have been in loiter
|
2012-11-29 08:08:19 -04:00
|
|
|
static uint32_t rtl_loiter_start_time;
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2012-12-19 11:06:20 -04:00
|
|
|
// Used to exit the roll and pitch auto trim function
|
|
|
|
static uint8_t auto_trim_counter;
|
2011-03-09 02:37:09 -04:00
|
|
|
|
2012-12-22 04:26:27 -04:00
|
|
|
// Reference to the relay object (APM1 -> PORTL 2) (APM2 -> PORTB 7)
|
2013-04-17 08:35:11 -03:00
|
|
|
static AP_Relay relay;
|
2011-10-02 09:52:02 -03:00
|
|
|
|
2014-01-20 01:05:31 -04:00
|
|
|
// handle repeated servo and relay events
|
|
|
|
static AP_ServoRelayEvents ServoRelayEvents(relay);
|
|
|
|
|
2012-12-22 04:26:27 -04:00
|
|
|
//Reference to the camera object (it uses the relay object inside it)
|
|
|
|
#if CAMERA == ENABLED
|
2013-04-17 08:35:11 -03:00
|
|
|
static AP_Camera camera(&relay);
|
2012-12-22 04:26:27 -04:00
|
|
|
#endif
|
|
|
|
|
2013-05-13 02:18:32 -03:00
|
|
|
// a pin for reading the receiver RSSI voltage.
|
2013-04-17 08:35:11 -03:00
|
|
|
static AP_HAL::AnalogSource* rssi_analog_source;
|
2012-11-22 05:59:33 -04:00
|
|
|
|
2012-09-11 00:52:10 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
|
|
|
static int8_t setup_show (uint8_t argc, const Menu::arg *argv);
|
2012-09-11 01:25:53 -03:00
|
|
|
#endif
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2012-07-10 19:39:13 -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.
|
2015-01-11 02:37:26 -04:00
|
|
|
static AP_Mount camera_mount(ahrs, current_loc);
|
2012-07-10 19:39:13 -03:00
|
|
|
#endif
|
|
|
|
|
2012-07-14 23:26:17 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-04-26 06:51:07 -03:00
|
|
|
// AC_Fence library to reduce fly-aways
|
2012-07-14 23:26:17 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2013-04-26 06:51:07 -03:00
|
|
|
#if AC_FENCE == ENABLED
|
2013-05-01 05:06:58 -03:00
|
|
|
AC_Fence fence(&inertial_nav);
|
2012-07-14 23:26:17 -03:00
|
|
|
#endif
|
|
|
|
|
2014-04-06 22:18:43 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Rally library
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
#if AC_RALLY == ENABLED
|
2014-08-13 01:44:31 -03:00
|
|
|
AP_Rally rally(ahrs);
|
2014-04-06 22:18:43 -03:00
|
|
|
#endif
|
|
|
|
|
2013-08-04 11:20:21 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Crop Sprayer
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
#if SPRAYER == ENABLED
|
|
|
|
static AC_Sprayer sprayer(&inertial_nav);
|
|
|
|
#endif
|
|
|
|
|
2013-12-17 00:58:11 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// EPM Cargo Griper
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
#if EPM_ENABLED == ENABLED
|
|
|
|
static AP_EPM epm;
|
|
|
|
#endif
|
|
|
|
|
2014-04-02 12:19:54 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Parachute release
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
#if PARACHUTE == ENABLED
|
|
|
|
static AP_Parachute parachute(relay);
|
|
|
|
#endif
|
|
|
|
|
2015-01-06 00:24:50 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Landing Gear Controller
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2015-01-06 11:26:22 -04:00
|
|
|
static AP_LandingGear landinggear;
|
2015-01-06 00:24:50 -04:00
|
|
|
|
2014-07-22 05:22:36 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// terrain handling
|
2014-07-24 18:58:58 -03:00
|
|
|
#if AP_TERRAIN_AVAILABLE
|
2014-08-06 03:17:52 -03:00
|
|
|
AP_Terrain terrain(ahrs, mission, rally);
|
2014-07-22 05:22:36 -03:00
|
|
|
#endif
|
|
|
|
|
2012-11-23 02:57:49 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// function definitions to keep compiler from complaining about undeclared functions
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2015-01-21 08:43:06 -04:00
|
|
|
static bool pre_arm_checks(bool display_failure);
|
2012-11-23 02:57:49 -04:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Top-level logic
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
2010-12-23 10:05:59 -04:00
|
|
|
|
2012-12-14 17:19:35 -04:00
|
|
|
// setup the var_info table
|
2014-08-13 01:44:31 -03:00
|
|
|
AP_Param param_loader(var_info);
|
2012-12-14 17:19:35 -04:00
|
|
|
|
2013-12-16 23:25:33 -04:00
|
|
|
#if MAIN_LOOP_RATE == 400
|
|
|
|
/*
|
|
|
|
scheduler table for fast CPUs - all regular tasks apart from the fast_loop()
|
|
|
|
should be listed here, along with how often they should be called
|
|
|
|
(in 2.5ms units) and the maximum time they are expected to take (in
|
|
|
|
microseconds)
|
|
|
|
1 = 400hz
|
|
|
|
2 = 200hz
|
|
|
|
4 = 100hz
|
|
|
|
8 = 50hz
|
|
|
|
20 = 20hz
|
|
|
|
40 = 10hz
|
|
|
|
133 = 3hz
|
|
|
|
400 = 1hz
|
|
|
|
4000 = 0.1hz
|
|
|
|
|
|
|
|
*/
|
|
|
|
static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|
|
|
{ rc_loop, 4, 10 },
|
|
|
|
{ throttle_loop, 8, 45 },
|
|
|
|
{ update_GPS, 8, 90 },
|
2014-07-11 23:33:49 -03:00
|
|
|
#if OPTFLOW == ENABLED
|
2014-11-07 06:54:32 -04:00
|
|
|
{ update_optical_flow, 2, 20 },
|
2014-07-11 23:33:49 -03:00
|
|
|
#endif
|
2013-12-16 23:25:33 -04:00
|
|
|
{ update_batt_compass, 40, 72 },
|
|
|
|
{ read_aux_switches, 40, 5 },
|
|
|
|
{ arm_motors_check, 40, 1 },
|
|
|
|
{ auto_trim, 40, 14 },
|
|
|
|
{ update_altitude, 40, 100 },
|
2014-12-05 00:59:29 -04:00
|
|
|
{ run_nav_updates, 8, 80 },
|
2014-02-03 01:06:08 -04:00
|
|
|
{ update_thr_cruise, 40, 10 },
|
2013-12-16 23:25:33 -04:00
|
|
|
{ three_hz_loop, 133, 9 },
|
|
|
|
{ compass_accumulate, 8, 42 },
|
|
|
|
{ barometer_accumulate, 8, 25 },
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
{ check_dynamic_flight, 8, 10 },
|
|
|
|
#endif
|
|
|
|
{ update_notify, 8, 10 },
|
|
|
|
{ one_hz_loop, 400, 42 },
|
2014-10-16 04:18:37 -03:00
|
|
|
{ ekf_dcm_check, 40, 2 },
|
2013-12-16 23:25:33 -04:00
|
|
|
{ crash_check, 40, 2 },
|
2015-01-06 00:24:50 -04:00
|
|
|
{ landinggear_update, 40, 1 },
|
2013-12-16 23:25:33 -04:00
|
|
|
{ gcs_check_input, 8, 550 },
|
|
|
|
{ gcs_send_heartbeat, 400, 150 },
|
|
|
|
{ gcs_send_deferred, 8, 720 },
|
|
|
|
{ gcs_data_stream_send, 8, 950 },
|
|
|
|
#if COPTER_LEDS == ENABLED
|
|
|
|
{ update_copter_leds, 40, 5 },
|
|
|
|
#endif
|
|
|
|
{ update_mount, 8, 45 },
|
|
|
|
{ ten_hz_logging_loop, 40, 30 },
|
2014-02-17 09:25:02 -04:00
|
|
|
{ fifty_hz_logging_loop, 8, 22 },
|
2013-12-16 23:25:33 -04:00
|
|
|
{ perf_update, 4000, 20 },
|
|
|
|
{ read_receiver_rssi, 40, 5 },
|
2014-07-28 19:25:40 -03:00
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
2015-01-27 03:32:05 -04:00
|
|
|
{ frsky_telemetry_send, 80, 10 },
|
2014-07-28 19:25:40 -03:00
|
|
|
#endif
|
2014-09-15 03:52:21 -03:00
|
|
|
#if EPM_ENABLED == ENABLED
|
|
|
|
{ epm_update, 40, 10 },
|
|
|
|
#endif
|
2013-12-16 23:25:33 -04:00
|
|
|
#ifdef USERHOOK_FASTLOOP
|
|
|
|
{ userhook_FastLoop, 4, 10 },
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_50HZLOOP
|
|
|
|
{ userhook_50Hz, 8, 10 },
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_MEDIUMLOOP
|
|
|
|
{ userhook_MediumLoop, 40, 10 },
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_SLOWLOOP
|
|
|
|
{ userhook_SlowLoop, 120, 10 },
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_SUPERSLOWLOOP
|
|
|
|
{ userhook_SuperSlowLoop,400, 10 },
|
|
|
|
#endif
|
|
|
|
};
|
|
|
|
#else
|
2013-01-11 21:01:10 -04:00
|
|
|
/*
|
|
|
|
scheduler table - all regular tasks apart from the fast_loop()
|
|
|
|
should be listed here, along with how often they should be called
|
|
|
|
(in 10ms units) and the maximum time they are expected to take (in
|
|
|
|
microseconds)
|
2014-05-05 22:42:34 -03:00
|
|
|
1 = 100hz
|
|
|
|
2 = 50hz
|
|
|
|
4 = 25hz
|
|
|
|
10 = 10hz
|
|
|
|
20 = 5hz
|
|
|
|
33 = 3hz
|
|
|
|
50 = 2hz
|
|
|
|
100 = 1hz
|
|
|
|
1000 = 0.1hz
|
2013-01-11 21:01:10 -04:00
|
|
|
*/
|
|
|
|
static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
2013-12-16 23:25:33 -04:00
|
|
|
{ rc_loop, 1, 100 },
|
2013-10-11 05:03:26 -03:00
|
|
|
{ throttle_loop, 2, 450 },
|
2013-01-11 21:01:10 -04:00
|
|
|
{ update_GPS, 2, 900 },
|
2014-07-11 23:33:49 -03:00
|
|
|
#if OPTFLOW == ENABLED
|
2014-08-06 21:30:42 -03:00
|
|
|
{ update_optical_flow, 1, 100 },
|
2014-07-11 23:33:49 -03:00
|
|
|
#endif
|
2013-10-11 11:49:40 -03:00
|
|
|
{ update_batt_compass, 10, 720 },
|
|
|
|
{ read_aux_switches, 10, 50 },
|
|
|
|
{ arm_motors_check, 10, 10 },
|
|
|
|
{ auto_trim, 10, 140 },
|
2013-04-28 05:15:13 -03:00
|
|
|
{ update_altitude, 10, 1000 },
|
2014-12-05 00:59:29 -04:00
|
|
|
{ run_nav_updates, 4, 800 },
|
2014-02-03 01:06:08 -04:00
|
|
|
{ update_thr_cruise, 1, 50 },
|
2013-10-11 11:49:40 -03:00
|
|
|
{ three_hz_loop, 33, 90 },
|
|
|
|
{ compass_accumulate, 2, 420 },
|
|
|
|
{ barometer_accumulate, 2, 250 },
|
2013-11-06 01:51:28 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
{ check_dynamic_flight, 2, 100 },
|
|
|
|
#endif
|
2013-08-29 00:14:07 -03:00
|
|
|
{ update_notify, 2, 100 },
|
2013-10-11 11:49:40 -03:00
|
|
|
{ one_hz_loop, 100, 420 },
|
2014-10-16 04:18:37 -03:00
|
|
|
{ ekf_dcm_check, 10, 20 },
|
2013-10-29 10:11:48 -03:00
|
|
|
{ crash_check, 10, 20 },
|
2015-01-06 00:24:50 -04:00
|
|
|
{ landinggear_update, 10, 10 },
|
2013-10-13 08:53:51 -03:00
|
|
|
{ gcs_check_input, 2, 550 },
|
|
|
|
{ gcs_send_heartbeat, 100, 150 },
|
|
|
|
{ gcs_send_deferred, 2, 720 },
|
|
|
|
{ gcs_data_stream_send, 2, 950 },
|
2013-10-13 02:13:59 -03:00
|
|
|
{ update_mount, 2, 450 },
|
2013-11-27 03:46:25 -04:00
|
|
|
{ ten_hz_logging_loop, 10, 300 },
|
2013-10-11 05:03:26 -03:00
|
|
|
{ fifty_hz_logging_loop, 2, 220 },
|
2013-10-11 11:49:40 -03:00
|
|
|
{ perf_update, 1000, 200 },
|
|
|
|
{ read_receiver_rssi, 10, 50 },
|
2014-07-28 19:25:40 -03:00
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
2015-01-27 03:32:05 -04:00
|
|
|
{ frsky_telemetry_send, 20, 100 },
|
2014-07-28 19:25:40 -03:00
|
|
|
#endif
|
2014-09-15 03:52:21 -03:00
|
|
|
#if EPM_ENABLED == ENABLED
|
|
|
|
{ epm_update, 10, 20 },
|
|
|
|
#endif
|
2013-10-11 08:40:20 -03:00
|
|
|
#ifdef USERHOOK_FASTLOOP
|
2013-10-14 23:18:00 -03:00
|
|
|
{ userhook_FastLoop, 1, 100 },
|
2013-10-11 08:40:20 -03:00
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_50HZLOOP
|
|
|
|
{ userhook_50Hz, 2, 100 },
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_MEDIUMLOOP
|
|
|
|
{ userhook_MediumLoop, 10, 100 },
|
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_SLOWLOOP
|
2013-10-14 23:18:00 -03:00
|
|
|
{ userhook_SlowLoop, 30, 100 },
|
2013-10-11 08:40:20 -03:00
|
|
|
#endif
|
|
|
|
#ifdef USERHOOK_SUPERSLOWLOOP
|
2013-10-14 23:18:00 -03:00
|
|
|
{ userhook_SuperSlowLoop,100, 100 },
|
2013-10-11 08:40:20 -03:00
|
|
|
#endif
|
2013-01-11 21:01:10 -04:00
|
|
|
};
|
2013-12-16 23:25:33 -04:00
|
|
|
#endif
|
2013-01-11 21:01:10 -04:00
|
|
|
|
|
|
|
|
2013-12-28 01:02:32 -04:00
|
|
|
void setup()
|
|
|
|
{
|
2012-12-13 22:16:32 -04:00
|
|
|
cliSerial = hal.console;
|
|
|
|
|
|
|
|
// Load the default values of variables listed in var_info[]s
|
2012-12-14 17:19:35 -04:00
|
|
|
AP_Param::setup_sketch_defaults();
|
2012-12-12 19:53:48 -04:00
|
|
|
|
2014-08-13 01:44:31 -03:00
|
|
|
// setup storage layout for copter
|
|
|
|
StorageManager::set_layout_copter();
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
init_ardupilot();
|
2013-01-11 21:01:10 -04:00
|
|
|
|
|
|
|
// initialise the main loop scheduler
|
|
|
|
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
|
2015-02-15 19:02:53 -04:00
|
|
|
|
|
|
|
// setup initial performance counters
|
|
|
|
perf_info_reset();
|
|
|
|
fast_loopTimer = hal.scheduler->micros();
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2013-01-06 20:02:50 -04:00
|
|
|
/*
|
2013-01-08 01:45:12 -04:00
|
|
|
if the compass is enabled then try to accumulate a reading
|
2013-01-06 20:02:50 -04:00
|
|
|
*/
|
2013-01-08 01:45:12 -04:00
|
|
|
static void compass_accumulate(void)
|
|
|
|
{
|
|
|
|
if (g.compass_enabled) {
|
|
|
|
compass.accumulate();
|
2013-10-29 01:28:27 -03:00
|
|
|
}
|
2013-01-08 01:45:12 -04:00
|
|
|
}
|
|
|
|
|
2013-01-09 08:08:19 -04:00
|
|
|
/*
|
|
|
|
try to accumulate a baro reading
|
|
|
|
*/
|
|
|
|
static void barometer_accumulate(void)
|
|
|
|
{
|
|
|
|
barometer.accumulate();
|
|
|
|
}
|
|
|
|
|
2013-01-08 01:45:12 -04:00
|
|
|
static void perf_update(void)
|
2013-01-06 20:02:50 -04:00
|
|
|
{
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_PM))
|
2013-01-08 01:45:12 -04:00
|
|
|
Log_Write_Performance();
|
2013-01-11 21:06:40 -04:00
|
|
|
if (scheduler.debug()) {
|
2015-02-15 19:02:53 -04:00
|
|
|
gcs_send_text_fmt(PSTR("PERF: %u/%u %lu %lu\n"),
|
|
|
|
(unsigned)perf_info_get_num_long_running(),
|
|
|
|
(unsigned)perf_info_get_num_loops(),
|
|
|
|
(unsigned long)perf_info_get_max_time(),
|
|
|
|
(unsigned long)perf_info_get_min_time());
|
2013-01-11 21:06:40 -04:00
|
|
|
}
|
2013-01-08 01:45:12 -04:00
|
|
|
perf_info_reset();
|
2013-04-29 09:30:22 -03:00
|
|
|
pmTest1 = 0;
|
2013-01-06 20:02:50 -04:00
|
|
|
}
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
void loop()
|
|
|
|
{
|
2013-10-08 03:30:43 -03:00
|
|
|
// wait for an INS sample
|
2014-10-15 20:33:24 -03:00
|
|
|
ins.wait_for_sample();
|
|
|
|
|
2012-11-10 01:39:41 -04:00
|
|
|
uint32_t timer = micros();
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-10-08 03:30:43 -03:00
|
|
|
// check loop time
|
|
|
|
perf_info_check_loop_time(timer - fast_loopTimer);
|
2012-11-18 12:16:07 -04:00
|
|
|
|
2013-10-08 03:30:43 -03:00
|
|
|
// used by PI Loops
|
|
|
|
G_Dt = (float)(timer - fast_loopTimer) / 1000000.f;
|
|
|
|
fast_loopTimer = timer;
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-10-08 03:30:43 -03:00
|
|
|
// for mainloop failure monitoring
|
|
|
|
mainLoop_count++;
|
2012-10-09 00:30:17 -03:00
|
|
|
|
2013-10-08 03:30:43 -03:00
|
|
|
// Execute the fast loop
|
|
|
|
// ---------------------
|
|
|
|
fast_loop();
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-10-08 03:30:43 -03:00
|
|
|
// tell the scheduler one tick has passed
|
|
|
|
scheduler.tick();
|
2013-07-23 04:05:16 -03:00
|
|
|
|
2013-10-08 03:30:43 -03:00
|
|
|
// run all the tasks that are due to run. Note that we only
|
|
|
|
// have to call this once per loop, as the tasks are scheduled
|
|
|
|
// in multiples of the main loop tick. So if they don't run on
|
|
|
|
// the first call to the scheduler they won't run on a later
|
|
|
|
// call until scheduler.tick() is called again
|
2013-12-16 23:25:33 -04:00
|
|
|
uint32_t time_available = (timer + MAIN_LOOP_MICROS) - micros();
|
|
|
|
scheduler.run(time_available);
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2011-07-10 21:47:08 -03:00
|
|
|
|
2013-01-08 01:45:12 -04:00
|
|
|
|
2012-05-17 14:55:13 -03:00
|
|
|
// Main loop - 100hz
|
2011-07-17 07:31:46 -03:00
|
|
|
static void fast_loop()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2013-12-17 00:58:11 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// IMU DCM Algorithm
|
|
|
|
// --------------------
|
|
|
|
read_AHRS();
|
2011-09-19 18:02:42 -03:00
|
|
|
|
2013-01-11 01:32:40 -04:00
|
|
|
// run low level rate controllers that only require IMU data
|
2013-12-06 02:08:11 -04:00
|
|
|
attitude_control.rate_controller_run();
|
2014-05-09 18:07:52 -03:00
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
update_heli_control_dynamics();
|
|
|
|
#endif //HELI_FRAME
|
2013-01-11 01:32:40 -04:00
|
|
|
|
2015-01-21 07:20:05 -04:00
|
|
|
// send outputs to the motors library
|
|
|
|
motors_output();
|
2013-01-11 01:32:40 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// Inertial Nav
|
|
|
|
// --------------------
|
2012-11-07 06:03:30 -04:00
|
|
|
read_inertia();
|
2012-06-14 02:27:03 -03:00
|
|
|
|
2014-01-11 04:03:05 -04:00
|
|
|
// run the attitude controllers
|
|
|
|
update_flight_mode();
|
2013-12-16 23:25:33 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// rc_loops - reads user input from transmitter/receiver
|
|
|
|
// called at 100hz
|
|
|
|
static void rc_loop()
|
|
|
|
{
|
2012-11-12 23:50:51 -04:00
|
|
|
// Read radio and 3-position switch on radio
|
|
|
|
// -----------------------------------------
|
|
|
|
read_radio();
|
|
|
|
read_control_switch();
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2013-10-11 05:03:26 -03:00
|
|
|
// throttle_loop - should be run at 50 hz
|
2013-05-19 23:05:14 -03:00
|
|
|
// ---------------------------
|
2013-10-11 05:03:26 -03:00
|
|
|
static void throttle_loop()
|
2013-05-19 23:05:14 -03:00
|
|
|
{
|
|
|
|
// get altitude and climb rate from inertial lib
|
|
|
|
read_inertial_altitude();
|
|
|
|
|
2013-07-26 02:15:27 -03:00
|
|
|
// check if we've landed
|
|
|
|
update_land_detector();
|
|
|
|
|
2013-05-19 23:05:14 -03:00
|
|
|
// check auto_armed status
|
|
|
|
update_auto_armed();
|
2013-11-06 08:39:39 -04:00
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2013-11-08 04:29:54 -04:00
|
|
|
// update rotor speed
|
|
|
|
heli_update_rotor_speed_targets();
|
|
|
|
|
2013-11-06 08:39:39 -04:00
|
|
|
// update trad heli swash plate movement
|
|
|
|
heli_update_landing_swash();
|
|
|
|
#endif
|
2013-10-11 05:03:26 -03:00
|
|
|
}
|
2013-05-19 23:05:14 -03:00
|
|
|
|
2013-10-11 08:40:20 -03:00
|
|
|
// update_mount - update camera mount position
|
2013-10-11 05:03:26 -03:00
|
|
|
// should be run at 50hz
|
2013-10-11 08:40:20 -03:00
|
|
|
static void update_mount()
|
2013-10-11 05:03:26 -03:00
|
|
|
{
|
2013-05-19 23:05:14 -03:00
|
|
|
#if MOUNT == ENABLED
|
|
|
|
// update camera mount's position
|
2015-01-11 02:37:26 -04:00
|
|
|
camera_mount.update();
|
2013-05-19 23:05:14 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if CAMERA == ENABLED
|
|
|
|
camera.trigger_pic_cleanup();
|
|
|
|
#endif
|
2013-10-11 05:03:26 -03:00
|
|
|
}
|
|
|
|
|
2013-10-11 08:40:20 -03:00
|
|
|
// update_batt_compass - read battery and compass
|
|
|
|
// should be called at 10hz
|
|
|
|
static void update_batt_compass(void)
|
|
|
|
{
|
|
|
|
// read battery before compass because it may be used for motor interference compensation
|
|
|
|
read_battery();
|
|
|
|
|
|
|
|
if(g.compass_enabled) {
|
2014-02-03 01:06:08 -04:00
|
|
|
// update compass with throttle value - used for compassmot
|
|
|
|
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
|
2014-08-15 22:45:11 -03:00
|
|
|
compass.read();
|
2013-10-11 08:40:20 -03:00
|
|
|
// log compass information
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_COMPASS)) {
|
2015-01-16 18:27:37 -04:00
|
|
|
DataFlash.Log_Write_Compass(compass);
|
2013-10-11 08:40:20 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// ten_hz_logging_loop
|
|
|
|
// should be run at 10hz
|
|
|
|
static void ten_hz_logging_loop()
|
|
|
|
{
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_ATTITUDE_MED)) {
|
2014-01-07 09:41:56 -04:00
|
|
|
Log_Write_Attitude();
|
|
|
|
}
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_RCIN)) {
|
2014-01-07 09:41:56 -04:00
|
|
|
DataFlash.Log_Write_RCIN();
|
|
|
|
}
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_RCOUT)) {
|
2014-01-07 09:41:56 -04:00
|
|
|
DataFlash.Log_Write_RCOUT();
|
2013-10-11 08:40:20 -03:00
|
|
|
}
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_NTUN) && (mode_requires_GPS(control_mode) || landing_with_GPS())) {
|
2014-01-21 23:56:07 -04:00
|
|
|
Log_Write_Nav_Tuning();
|
|
|
|
}
|
2013-10-11 08:40:20 -03:00
|
|
|
}
|
|
|
|
|
2013-10-11 05:03:26 -03:00
|
|
|
// fifty_hz_logging_loop
|
|
|
|
// should be run at 50hz
|
|
|
|
static void fifty_hz_logging_loop()
|
|
|
|
{
|
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
|
|
|
// HIL for a copter needs very fast update of the servo values
|
|
|
|
gcs_send_message(MSG_RADIO_OUT);
|
|
|
|
#endif
|
2013-05-19 23:05:14 -03:00
|
|
|
|
2014-01-07 09:41:56 -04:00
|
|
|
#if HIL_MODE == HIL_MODE_DISABLED
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
2013-05-19 23:05:14 -03:00
|
|
|
Log_Write_Attitude();
|
|
|
|
}
|
|
|
|
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_IMU)) {
|
2013-11-03 23:37:46 -04:00
|
|
|
DataFlash.Log_Write_IMU(ins);
|
2014-01-07 09:41:56 -04:00
|
|
|
}
|
2013-05-19 23:05:14 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2013-10-11 08:40:20 -03:00
|
|
|
// three_hz_loop - 3.3hz loop
|
|
|
|
static void three_hz_loop()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2013-10-11 08:40:20 -03:00
|
|
|
// check if we've lost contact with the ground station
|
|
|
|
failsafe_gcs_check();
|
2012-04-04 10:50:43 -03:00
|
|
|
|
2013-04-26 06:51:07 -03:00
|
|
|
#if AC_FENCE == ENABLED
|
2013-10-11 08:40:20 -03:00
|
|
|
// check if we have breached a fence
|
|
|
|
fence_check();
|
2013-04-26 06:51:07 -03:00
|
|
|
#endif // AC_FENCE_ENABLED
|
|
|
|
|
2013-08-04 11:20:21 -03:00
|
|
|
#if SPRAYER == ENABLED
|
2013-10-11 08:40:20 -03:00
|
|
|
sprayer.update();
|
2012-08-21 23:19:50 -03:00
|
|
|
#endif
|
2011-06-01 02:50:17 -03:00
|
|
|
|
2013-10-11 08:40:20 -03:00
|
|
|
update_events();
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2015-01-16 02:12:58 -04:00
|
|
|
// update ch6 in flight tuning
|
|
|
|
tuning();
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
2013-10-11 08:40:20 -03:00
|
|
|
// one_hz_loop - runs at 1Hz
|
|
|
|
static void one_hz_loop()
|
2011-02-25 01:33:39 -04:00
|
|
|
{
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_ANY)) {
|
2013-01-12 11:17:44 -04:00
|
|
|
Log_Write_Data(DATA_AP_STATE, ap.value);
|
|
|
|
}
|
2012-11-11 21:59:53 -04:00
|
|
|
|
2013-11-18 04:20:39 -04:00
|
|
|
// perform pre-arm checks & display failures every 30 seconds
|
|
|
|
static uint8_t pre_arm_display_counter = 15;
|
|
|
|
pre_arm_display_counter++;
|
|
|
|
if (pre_arm_display_counter >= 30) {
|
|
|
|
pre_arm_checks(true);
|
|
|
|
pre_arm_display_counter = 0;
|
|
|
|
}else{
|
|
|
|
pre_arm_checks(false);
|
|
|
|
}
|
2013-04-22 12:01:20 -03:00
|
|
|
|
2013-05-20 02:05:50 -03:00
|
|
|
// auto disarm checks
|
|
|
|
auto_disarm_check();
|
2012-03-07 02:22:14 -04:00
|
|
|
|
2013-06-03 03:52:52 -03:00
|
|
|
if (!motors.armed()) {
|
2013-10-11 08:40:20 -03:00
|
|
|
// make it possible to change ahrs orientation at runtime during initial config
|
2013-06-03 03:52:52 -03:00
|
|
|
ahrs.set_orientation();
|
2013-10-11 08:40:20 -03:00
|
|
|
|
|
|
|
// check the user hasn't updated the frame orientation
|
|
|
|
motors.set_frame_orientation(g.frame_orientation);
|
2013-06-03 03:52:52 -03:00
|
|
|
}
|
|
|
|
|
2013-10-31 03:22:34 -03:00
|
|
|
// update assigned functions and enable auxiliar servos
|
2014-02-05 19:12:31 -04:00
|
|
|
RC_Channel_aux::enable_aux_servos();
|
2013-10-11 08:40:20 -03:00
|
|
|
|
|
|
|
check_usb_mux();
|
2014-07-22 05:22:36 -03:00
|
|
|
|
2014-07-24 18:58:58 -03:00
|
|
|
#if AP_TERRAIN_AVAILABLE
|
2014-07-22 05:22:36 -03:00
|
|
|
terrain.update();
|
|
|
|
#endif
|
2015-01-30 00:35:23 -04:00
|
|
|
|
|
|
|
#if AC_FENCE == ENABLED
|
|
|
|
// set fence altitude limit in position controller
|
|
|
|
if ((fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) {
|
2015-02-10 08:33:07 -04:00
|
|
|
pos_control.set_alt_max(pv_alt_above_origin(fence.get_safe_alt()*100.0f));
|
2015-01-30 00:35:23 -04:00
|
|
|
}
|
|
|
|
#endif
|
2011-02-25 01:33:39 -04:00
|
|
|
}
|
|
|
|
|
2012-05-21 13:58:14 -03:00
|
|
|
// called at 50hz
|
2011-07-17 07:31:46 -03:00
|
|
|
static void update_GPS(void)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2014-04-09 21:30:10 -03:00
|
|
|
static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; // time of last gps message
|
2014-02-10 22:43:24 -04:00
|
|
|
bool report_gps_glitch;
|
2014-04-09 21:30:10 -03:00
|
|
|
bool gps_updated = false;
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2014-03-31 04:07:46 -03:00
|
|
|
gps.update();
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-11-21 22:51:48 -04:00
|
|
|
// logging and glitch protection run after every gps message
|
2014-04-09 21:30:10 -03:00
|
|
|
for (uint8_t i=0; i<gps.num_sensors(); i++) {
|
|
|
|
if (gps.last_message_time_ms(i) != last_gps_reading[i]) {
|
|
|
|
last_gps_reading[i] = gps.last_message_time_ms(i);
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2014-04-09 21:30:10 -03:00
|
|
|
// log GPS message
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_GPS)) {
|
2014-04-09 21:30:10 -03:00
|
|
|
DataFlash.Log_Write_GPS(gps, i, current_loc.alt);
|
|
|
|
}
|
|
|
|
|
|
|
|
gps_updated = true;
|
2013-03-25 04:25:13 -03:00
|
|
|
}
|
2014-04-09 21:30:10 -03:00
|
|
|
}
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2014-04-09 21:30:10 -03:00
|
|
|
if (gps_updated) {
|
2013-11-21 22:51:48 -04:00
|
|
|
// run glitch protection and update AP_Notify if home has been initialised
|
2015-02-09 07:23:49 -04:00
|
|
|
if (home_is_set()) {
|
2013-11-21 22:51:48 -04:00
|
|
|
gps_glitch.check_position();
|
2014-03-31 04:54:49 -03:00
|
|
|
report_gps_glitch = (gps_glitch.glitching() && !ap.usb_connected && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
2014-02-10 22:43:24 -04:00
|
|
|
if (AP_Notify::flags.gps_glitching != report_gps_glitch) {
|
2013-11-21 22:51:48 -04:00
|
|
|
if (gps_glitch.glitching()) {
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_GPS, ERROR_CODE_GPS_GLITCH);
|
|
|
|
}else{
|
|
|
|
Log_Write_Error(ERROR_SUBSYSTEM_GPS, ERROR_CODE_ERROR_RESOLVED);
|
|
|
|
}
|
2014-02-10 22:43:24 -04:00
|
|
|
AP_Notify::flags.gps_glitching = report_gps_glitch;
|
2013-09-23 00:20:57 -03:00
|
|
|
}
|
|
|
|
}
|
2013-11-21 22:51:48 -04:00
|
|
|
|
2015-02-09 07:23:49 -04:00
|
|
|
// set system time if necessary
|
|
|
|
set_system_time_from_GPS();
|
2014-03-31 04:07:46 -03:00
|
|
|
|
2015-02-09 07:23:49 -04:00
|
|
|
// update home from GPS location if necessary
|
|
|
|
update_home_from_GPS();
|
2013-06-24 23:52:44 -03:00
|
|
|
|
2015-02-09 07:23:49 -04:00
|
|
|
// check gps base position (used for RTK only)
|
|
|
|
check_gps_base_pos();
|
2014-06-06 19:17:38 -03:00
|
|
|
|
2015-02-09 07:23:49 -04:00
|
|
|
// checks to initialise home and take location based pictures
|
|
|
|
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
2014-06-06 19:17:38 -03:00
|
|
|
|
2013-06-24 23:52:44 -03:00
|
|
|
#if CAMERA == ENABLED
|
2014-03-31 04:07:46 -03:00
|
|
|
if (camera.update_location(current_loc) == true) {
|
|
|
|
do_take_picture();
|
|
|
|
}
|
2013-10-29 01:28:27 -03:00
|
|
|
#endif
|
2014-03-31 04:07:46 -03:00
|
|
|
}
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2013-03-16 05:27:46 -03:00
|
|
|
|
|
|
|
// check for loss of gps
|
|
|
|
failsafe_gps_check();
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2011-02-17 05:36:33 -04:00
|
|
|
|
2013-10-05 06:25:03 -03:00
|
|
|
static void
|
|
|
|
init_simple_bearing()
|
2012-01-04 02:54:29 -04:00
|
|
|
{
|
2013-10-05 06:25:03 -03:00
|
|
|
// capture current cos_yaw and sin_yaw values
|
2014-02-08 03:40:45 -04:00
|
|
|
simple_cos_yaw = ahrs.cos_yaw();
|
|
|
|
simple_sin_yaw = ahrs.sin_yaw();
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2013-10-05 06:25:03 -03:00
|
|
|
// initialise super simple heading (i.e. heading towards home) to be 180 deg from simple mode heading
|
|
|
|
super_simple_last_bearing = wrap_360_cd(ahrs.yaw_sensor+18000);
|
|
|
|
super_simple_cos_yaw = simple_cos_yaw;
|
|
|
|
super_simple_sin_yaw = simple_sin_yaw;
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2013-10-05 06:25:03 -03:00
|
|
|
// log the simple bearing to dataflash
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_ANY)) {
|
2013-10-05 06:25:03 -03:00
|
|
|
Log_Write_Data(DATA_INIT_SIMPLE_BEARING, ahrs.yaw_sensor);
|
|
|
|
}
|
|
|
|
}
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2013-10-05 06:25:03 -03:00
|
|
|
// update_simple_mode - rotates pilot input if we are in simple mode
|
|
|
|
void update_simple_mode(void)
|
|
|
|
{
|
|
|
|
float rollx, pitchx;
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2013-10-05 06:25:03 -03:00
|
|
|
// exit immediately if no new radio frame or not in simple mode
|
2013-10-08 03:25:14 -03:00
|
|
|
if (ap.simple_mode == 0 || !ap.new_radio_frame) {
|
2013-10-05 06:25:03 -03:00
|
|
|
return;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2014-03-28 05:03:31 -03:00
|
|
|
// mark radio frame as consumed
|
|
|
|
ap.new_radio_frame = false;
|
|
|
|
|
2013-10-05 06:25:03 -03:00
|
|
|
if (ap.simple_mode == 1) {
|
|
|
|
// rotate roll, pitch input by -initial simple heading (i.e. north facing)
|
|
|
|
rollx = g.rc_1.control_in*simple_cos_yaw - g.rc_2.control_in*simple_sin_yaw;
|
|
|
|
pitchx = g.rc_1.control_in*simple_sin_yaw + g.rc_2.control_in*simple_cos_yaw;
|
|
|
|
}else{
|
|
|
|
// rotate roll, pitch input by -super simple heading (reverse of heading to home)
|
|
|
|
rollx = g.rc_1.control_in*super_simple_cos_yaw - g.rc_2.control_in*super_simple_sin_yaw;
|
|
|
|
pitchx = g.rc_1.control_in*super_simple_sin_yaw + g.rc_2.control_in*super_simple_cos_yaw;
|
|
|
|
}
|
2012-01-04 02:54:29 -04:00
|
|
|
|
2013-10-05 06:25:03 -03:00
|
|
|
// rotate roll, pitch input from north facing to vehicle's perspective
|
2014-02-08 03:40:45 -04:00
|
|
|
g.rc_1.control_in = rollx*ahrs.cos_yaw() + pitchx*ahrs.sin_yaw();
|
|
|
|
g.rc_2.control_in = -rollx*ahrs.sin_yaw() + pitchx*ahrs.cos_yaw();
|
2011-09-04 21:15:36 -03:00
|
|
|
}
|
2011-07-10 21:47:08 -03:00
|
|
|
|
2013-01-27 10:48:07 -04:00
|
|
|
// update_super_simple_bearing - adjusts simple bearing based on location
|
2013-01-24 00:36:55 -04:00
|
|
|
// should be called after home_bearing has been updated
|
2013-10-05 06:25:03 -03:00
|
|
|
void update_super_simple_bearing(bool force_update)
|
2013-01-24 00:36:55 -04:00
|
|
|
{
|
2013-10-05 06:25:03 -03:00
|
|
|
// check if we are in super simple mode and at least 10m from home
|
|
|
|
if(force_update || (ap.simple_mode == 2 && home_distance > SUPER_SIMPLE_RADIUS)) {
|
|
|
|
// check the bearing to home has changed by at least 5 degrees
|
|
|
|
if (labs(super_simple_last_bearing - home_bearing) > 500) {
|
|
|
|
super_simple_last_bearing = home_bearing;
|
|
|
|
float angle_rad = radians((super_simple_last_bearing+18000)/100);
|
|
|
|
super_simple_cos_yaw = cosf(angle_rad);
|
|
|
|
super_simple_sin_yaw = sinf(angle_rad);
|
2013-01-24 00:36:55 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2011-07-17 07:31:46 -03:00
|
|
|
static void read_AHRS(void)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
// Perform IMU calculations and get attitude info
|
|
|
|
//-----------------------------------------------
|
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
|
|
|
// update hil before ahrs update
|
2013-01-08 01:45:12 -04:00
|
|
|
gcs_check_input();
|
2012-08-21 23:19:50 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
ahrs.update();
|
2011-01-23 12:40:03 -04:00
|
|
|
}
|
2011-02-13 18:32:34 -04:00
|
|
|
|
2014-07-28 05:38:32 -03:00
|
|
|
// read baro and sonar altitude at 10hz
|
2011-09-04 21:15:36 -03:00
|
|
|
static void update_altitude()
|
2011-02-21 00:30:56 -04:00
|
|
|
{
|
2013-02-01 23:00:09 -04:00
|
|
|
// read in baro altitude
|
2014-10-22 04:07:10 -03:00
|
|
|
read_barometer();
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-02-01 23:00:09 -04:00
|
|
|
// read in sonar altitude
|
2013-01-31 04:00:28 -04:00
|
|
|
sonar_alt = read_sonar();
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-02-01 23:00:09 -04:00
|
|
|
// write altitude info to dataflash logs
|
2014-10-16 21:37:49 -03:00
|
|
|
if (should_log(MASK_LOG_CTUN)) {
|
2013-02-01 23:00:09 -04:00
|
|
|
Log_Write_Control_Tuning();
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2011-03-26 03:35:52 -03:00
|
|
|
}
|
|
|
|
|
2012-12-13 16:02:27 -04:00
|
|
|
AP_HAL_MAIN();
|
|
|
|
|