2011-09-08 22:29:39 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/*****************************************************************************
|
2012-08-21 23:19:51 -03:00
|
|
|
* The init_ardupilot function processes everything we need for an in - air restart
|
|
|
|
* We will determine later if we are actually on the ground and process a
|
|
|
|
* ground start in that case.
|
|
|
|
*
|
2011-09-08 22:29:39 -03:00
|
|
|
*****************************************************************************/
|
|
|
|
|
|
|
|
#if CLI_ENABLED == ENABLED
|
|
|
|
|
|
|
|
// Functions called from the top-level menu
|
2012-08-21 23:19:51 -03:00
|
|
|
static int8_t process_logs(uint8_t argc, const Menu::arg *argv); // in Log.pde
|
|
|
|
static int8_t setup_mode(uint8_t argc, const Menu::arg *argv); // in setup.pde
|
|
|
|
static int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in test.cpp
|
2012-11-24 03:14:26 -04:00
|
|
|
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
|
|
|
// This is the help function
|
|
|
|
// PSTR is an AVR macro to read strings from flash memory
|
|
|
|
// printf_P is a version of print_f that reads from flash memory
|
2012-08-21 23:19:51 -03:00
|
|
|
static int8_t main_menu_help(uint8_t argc, const Menu::arg *argv)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2012-11-21 01:19:16 -04:00
|
|
|
cliSerial->printf_P(PSTR("Commands:\n"
|
2012-08-21 23:19:51 -03:00
|
|
|
" logs log readback/setup mode\n"
|
|
|
|
" setup setup mode\n"
|
|
|
|
" test test mode\n"
|
2012-11-24 03:14:26 -04:00
|
|
|
" reboot reboot to flight mode\n"
|
2012-08-21 23:19:51 -03:00
|
|
|
"\n"));
|
|
|
|
return(0);
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// Command/function table for the top-level menu.
|
|
|
|
static const struct Menu::command main_menu_commands[] PROGMEM = {
|
|
|
|
// command function called
|
|
|
|
// ======= ===============
|
2012-08-21 23:19:51 -03:00
|
|
|
{"logs", process_logs},
|
|
|
|
{"setup", setup_mode},
|
|
|
|
{"test", test_mode},
|
2012-11-24 03:14:26 -04:00
|
|
|
{"reboot", reboot_board},
|
2012-08-21 23:19:51 -03:00
|
|
|
{"help", main_menu_help},
|
2011-09-08 22:29:39 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// Create the top-level menu object.
|
2011-09-17 15:25:31 -03:00
|
|
|
MENU(main_menu, THISFIRMWARE, main_menu_commands);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-11-24 03:14:26 -04:00
|
|
|
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv)
|
|
|
|
{
|
2013-09-03 22:59:16 -03:00
|
|
|
hal.scheduler->reboot(false);
|
2012-11-24 03:14:26 -04:00
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2011-10-27 04:35:25 -03:00
|
|
|
// the user wants the CLI. It never exits
|
2012-12-04 18:22:21 -04:00
|
|
|
static void run_cli(AP_HAL::UARTDriver *port)
|
2011-10-27 04:35:25 -03:00
|
|
|
{
|
2011-12-21 08:25:51 -04:00
|
|
|
// disable the failsafe code in the CLI
|
2012-12-04 18:22:21 -04:00
|
|
|
hal.scheduler->register_timer_failsafe(NULL,1);
|
2011-12-21 08:25:51 -04:00
|
|
|
|
2012-12-23 17:51:33 -04:00
|
|
|
// disable the mavlink delay callback
|
|
|
|
hal.scheduler->register_delay_callback(NULL, 5);
|
|
|
|
|
2012-11-21 01:19:16 -04:00
|
|
|
cliSerial = port;
|
|
|
|
Menu::set_port(port);
|
|
|
|
port->set_blocking_writes(true);
|
|
|
|
|
2011-10-27 04:35:25 -03:00
|
|
|
while (1) {
|
|
|
|
main_menu.run();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
#endif // CLI_ENABLED
|
|
|
|
|
|
|
|
static void init_ardupilot()
|
|
|
|
{
|
2015-01-23 09:45:24 -04:00
|
|
|
// initialise serial port
|
|
|
|
serial_manager.init_console();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-11-08 07:27:22 -04:00
|
|
|
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
2012-08-21 23:19:51 -03:00
|
|
|
"\n\nFree RAM: %u\n"),
|
2013-12-27 23:51:37 -04:00
|
|
|
hal.util->available_memory());
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2011-11-13 00:10:30 -04:00
|
|
|
|
|
|
|
//
|
2012-12-04 18:22:21 -04:00
|
|
|
// Check the EEPROM format version before loading any parameters from EEPROM
|
2012-08-21 23:19:51 -03:00
|
|
|
//
|
2012-02-12 04:20:56 -04:00
|
|
|
load_parameters();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2015-03-13 08:33:48 -03:00
|
|
|
if (g.hil_mode == 1) {
|
|
|
|
// set sensors to HIL mode
|
|
|
|
ins.set_hil_mode();
|
|
|
|
compass.set_hil_mode();
|
|
|
|
barometer.set_hil_mode();
|
|
|
|
}
|
|
|
|
|
2014-11-05 06:18:04 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
// this must be before BoardConfig.init() so if
|
|
|
|
// BRD_SAFETYENABLE==0 then we don't have safety off yet
|
|
|
|
setup_failsafe_mixing();
|
|
|
|
#endif
|
|
|
|
|
2014-01-19 21:58:49 -04:00
|
|
|
BoardConfig.init();
|
|
|
|
|
2015-01-23 09:45:24 -04:00
|
|
|
// initialise serial ports
|
|
|
|
serial_manager.init();
|
|
|
|
|
2014-01-20 00:36:31 -04:00
|
|
|
// allow servo set on all channels except first 4
|
|
|
|
ServoRelayEvents.set_channel_mask(0xFFF0);
|
|
|
|
|
2013-06-03 03:42:38 -03:00
|
|
|
set_control_channels();
|
2013-06-03 02:32:08 -03:00
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
// keep a record of how many resets have happened. This can be
|
|
|
|
// used to detect in-flight resets
|
|
|
|
g.num_resets.set_and_save(g.num_resets+1);
|
|
|
|
|
2013-05-05 21:57:57 -03:00
|
|
|
// init baro before we start the GCS, so that the CLI baro test works
|
|
|
|
barometer.init();
|
|
|
|
|
2014-08-26 08:17:47 -03:00
|
|
|
// initialise rangefinder
|
|
|
|
init_rangefinder();
|
2013-10-30 19:23:21 -03:00
|
|
|
|
2014-08-08 23:29:20 -03:00
|
|
|
// initialise battery monitoring
|
|
|
|
battery.init();
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// init the GCS
|
2015-03-27 22:50:57 -03:00
|
|
|
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console, 0);
|
2011-11-20 05:31:45 -04:00
|
|
|
|
2013-09-20 20:16:17 -03:00
|
|
|
// we start by assuming USB connected, as we initialed the serial
|
|
|
|
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
|
|
|
|
usb_connected = true;
|
|
|
|
check_usb_mux();
|
2013-09-19 03:23:58 -03:00
|
|
|
|
2015-01-23 09:45:24 -04:00
|
|
|
// setup serial port for telem1
|
2015-03-27 22:50:57 -03:00
|
|
|
gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
2013-11-22 04:18:19 -04:00
|
|
|
|
2013-11-25 19:58:11 -04:00
|
|
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
2015-01-23 09:45:24 -04:00
|
|
|
// setup serial port for telem2
|
2015-03-27 22:50:57 -03:00
|
|
|
gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1);
|
2015-01-23 09:45:24 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// setup frsky
|
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
|
|
|
frsky_telemetry.init(serial_manager);
|
2013-11-25 19:58:11 -04:00
|
|
|
#endif
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
mavlink_system.sysid = g.sysid_this_mav;
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2011-12-21 08:29:22 -04:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2013-12-16 20:15:17 -04:00
|
|
|
DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0]));
|
2012-12-08 00:35:49 -04:00
|
|
|
if (!DataFlash.CardInserted()) {
|
2011-12-28 00:53:14 -04:00
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("No dataflash card inserted"));
|
|
|
|
g.log_bitmask.set(0);
|
2012-12-08 00:35:49 -04:00
|
|
|
} else if (DataFlash.NeedErase()) {
|
2011-12-17 19:19:52 -04:00
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS"));
|
2012-08-21 23:19:51 -03:00
|
|
|
do_erase_logs();
|
2013-11-22 04:18:19 -04:00
|
|
|
for (uint8_t i=0; i<num_gcs; i++) {
|
|
|
|
gcs[i].reset_cli_timeout();
|
|
|
|
}
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
2015-02-06 03:40:16 -04:00
|
|
|
arming.set_logging_available(DataFlash.CardInserted());
|
2011-12-21 08:29:22 -04:00
|
|
|
#endif
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2014-10-15 01:13:13 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
2013-06-02 22:40:44 -03:00
|
|
|
apm1_adc.Init(); // APM ADC library initialization
|
2013-09-28 11:52:51 -03:00
|
|
|
#endif
|
2011-11-12 22:47:54 -04:00
|
|
|
|
2013-06-02 22:40:44 -03:00
|
|
|
// initialise airspeed sensor
|
|
|
|
airspeed.init();
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
if (g.compass_enabled==true) {
|
|
|
|
if (!compass.init() || !compass.read()) {
|
2012-11-21 01:19:16 -04:00
|
|
|
cliSerial->println_P(PSTR("Compass initialisation failed!"));
|
2011-09-08 22:29:39 -03:00
|
|
|
g.compass_enabled = false;
|
|
|
|
} else {
|
2012-03-11 05:13:31 -03:00
|
|
|
ahrs.set_compass(&compass);
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
2015-01-02 20:09:02 -04:00
|
|
|
|
|
|
|
// make optflow available to libraries
|
|
|
|
ahrs.set_optflow(&optflow);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2014-11-08 00:29:25 -04:00
|
|
|
// Register mavlink_delay_cb, which will run anytime you have
|
|
|
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
|
|
|
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
|
|
|
|
|
2012-08-10 19:57:44 -03:00
|
|
|
// give AHRS the airspeed sensor
|
|
|
|
ahrs.set_airspeed(&airspeed);
|
|
|
|
|
2012-06-10 03:36:18 -03:00
|
|
|
// GPS Initialization
|
2015-01-23 09:45:24 -04:00
|
|
|
gps.init(&DataFlash, serial_manager);
|
2013-12-21 07:27:15 -04:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
init_rc_in(); // sets up rc channels from radio
|
|
|
|
init_rc_out(); // sets up the timer libs
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-12-04 18:22:21 -04:00
|
|
|
relay.init();
|
2011-12-16 15:28:25 -04:00
|
|
|
|
2015-01-27 09:12:12 -04:00
|
|
|
#if MOUNT == ENABLED
|
2015-01-08 16:12:08 -04:00
|
|
|
// initialise camera mount
|
2015-01-23 09:45:24 -04:00
|
|
|
camera_mount.init(serial_manager);
|
2015-01-27 09:12:12 -04:00
|
|
|
#endif
|
2015-01-08 16:12:08 -04:00
|
|
|
|
2011-12-16 15:28:25 -04:00
|
|
|
#if FENCE_TRIGGERED_PIN > 0
|
2014-06-01 20:28:27 -03:00
|
|
|
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
|
|
|
|
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
|
2011-12-16 15:28:25 -04:00
|
|
|
#endif
|
|
|
|
|
2011-12-22 20:11:59 -04:00
|
|
|
/*
|
2012-08-21 23:19:51 -03:00
|
|
|
* setup the 'main loop is dead' check. Note that this relies on
|
|
|
|
* the RC library being initialised.
|
2011-12-22 20:11:59 -04:00
|
|
|
*/
|
2012-12-04 18:22:21 -04:00
|
|
|
hal.scheduler->register_timer_failsafe(failsafe_check, 1000);
|
2011-12-22 20:11:59 -04:00
|
|
|
|
2015-01-23 09:45:24 -04:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2015-03-09 00:14:59 -03:00
|
|
|
if (g.cli_enabled == 1) {
|
|
|
|
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
|
|
|
cliSerial->println_P(msg);
|
|
|
|
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
|
|
|
gcs[1].get_uart()->println_P(msg);
|
|
|
|
}
|
|
|
|
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) {
|
|
|
|
gcs[2].get_uart()->println_P(msg);
|
|
|
|
}
|
2013-11-22 04:18:19 -04:00
|
|
|
}
|
2015-01-23 09:45:24 -04:00
|
|
|
#endif // CLI_ENABLED
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-07-19 22:15:48 -03:00
|
|
|
startup_ground();
|
2014-01-13 22:07:43 -04:00
|
|
|
if (should_log(MASK_LOG_CMD))
|
2013-07-19 22:15:48 -03:00
|
|
|
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-04-11 21:25:46 -03:00
|
|
|
// choose the nav controller
|
|
|
|
set_nav_controller();
|
|
|
|
|
2015-02-26 17:07:59 -04:00
|
|
|
set_mode((FlightMode)g.initial_mode.get());
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// set the correct flight mode
|
|
|
|
// ---------------------------
|
|
|
|
reset_control_switch();
|
2014-10-13 04:51:10 -03:00
|
|
|
|
|
|
|
// initialise sensor
|
2014-11-03 03:33:56 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2014-10-13 04:51:10 -03:00
|
|
|
optflow.init();
|
2014-11-03 03:33:56 -04:00
|
|
|
#endif
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
//********************************************************************************
|
|
|
|
//This function does all the calibrations, etc. that we need during a ground start
|
|
|
|
//********************************************************************************
|
|
|
|
static void startup_ground(void)
|
|
|
|
{
|
|
|
|
set_mode(INITIALISING);
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> GROUND START"));
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
#if (GROUND_START_DELAY > 0)
|
|
|
|
gcs_send_text_P(SEVERITY_LOW,PSTR("<startup_ground> With Delay"));
|
|
|
|
delay(GROUND_START_DELAY * 1000);
|
|
|
|
#endif
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Makes the servos wiggle
|
|
|
|
// step 1 = 1 wiggle
|
|
|
|
// -----------------------
|
2013-07-19 22:33:09 -03:00
|
|
|
if (!g.skip_gyro_cal) {
|
|
|
|
demo_servos(1);
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-11-05 00:32:13 -04:00
|
|
|
//INS ground start
|
2012-08-21 23:19:51 -03:00
|
|
|
//------------------------
|
2011-09-08 22:29:39 -03:00
|
|
|
//
|
2015-03-10 20:16:59 -03:00
|
|
|
startup_INS_ground();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// read the radio to set trims
|
|
|
|
// ---------------------------
|
2015-03-06 17:20:55 -04:00
|
|
|
if (g.trim_rc_at_start != 0) {
|
|
|
|
trim_radio();
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Save the settings for in-air restart
|
|
|
|
// ------------------------------------
|
|
|
|
//save_EEPROM_groundstart();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2014-03-11 01:06:45 -03:00
|
|
|
// initialise mission library
|
|
|
|
mission.init();
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Makes the servos wiggle - 3 times signals ready to fly
|
|
|
|
// -----------------------
|
2013-07-19 22:33:09 -03:00
|
|
|
if (!g.skip_gyro_cal) {
|
|
|
|
demo_servos(3);
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-12-25 17:46:36 -04:00
|
|
|
// reset last heartbeat time, so we don't trigger failsafe on slow
|
|
|
|
// startup
|
2013-07-19 01:11:16 -03:00
|
|
|
failsafe.last_heartbeat_ms = millis();
|
2012-12-25 17:46:36 -04:00
|
|
|
|
2012-03-30 03:06:03 -03:00
|
|
|
// we don't want writes to the serial port to cause us to pause
|
|
|
|
// mid-flight, so set the serial ports non-blocking once we are
|
|
|
|
// ready to fly
|
2015-01-23 09:45:24 -04:00
|
|
|
serial_manager.set_blocking_writes_all(false);
|
2012-03-30 03:06:03 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2014-02-13 18:49:42 -04:00
|
|
|
static enum FlightMode get_previous_mode() {
|
|
|
|
return previous_mode;
|
|
|
|
}
|
|
|
|
|
2012-11-30 17:15:48 -04:00
|
|
|
static void set_mode(enum FlightMode mode)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2012-08-21 23:19:51 -03:00
|
|
|
if(control_mode == mode) {
|
|
|
|
// don't switch modes if we are already in the correct mode.
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if(g.auto_trim > 0 && control_mode == MANUAL)
|
|
|
|
trim_control_surfaces();
|
|
|
|
|
2014-03-14 09:40:47 -03:00
|
|
|
// perform any cleanup required for prev flight mode
|
|
|
|
exit_mode(control_mode);
|
|
|
|
|
2014-06-05 03:12:10 -03:00
|
|
|
// cancel inverted flight
|
|
|
|
auto_state.inverted_flight = false;
|
|
|
|
|
2014-08-04 07:39:15 -03:00
|
|
|
// don't cross-track when starting a mission
|
|
|
|
auto_state.next_wp_no_crosstrack = true;
|
|
|
|
|
2014-10-17 22:46:20 -03:00
|
|
|
// reset landing check
|
|
|
|
auto_state.checked_for_autoland = false;
|
|
|
|
|
2014-10-21 12:26:33 -03:00
|
|
|
// reset go around command
|
|
|
|
auto_state.commanded_go_around = false;
|
|
|
|
|
2014-10-06 17:17:33 -03:00
|
|
|
// zero locked course
|
|
|
|
steer_state.locked_course_err = 0;
|
|
|
|
|
2014-03-14 09:40:47 -03:00
|
|
|
// set mode
|
2014-02-13 18:49:42 -04:00
|
|
|
previous_mode = control_mode;
|
2012-08-21 23:19:51 -03:00
|
|
|
control_mode = mode;
|
|
|
|
|
2014-04-12 01:12:14 -03:00
|
|
|
if (previous_mode == AUTOTUNE && control_mode != AUTOTUNE) {
|
|
|
|
// restore last gains
|
|
|
|
autotune_restore();
|
|
|
|
}
|
|
|
|
|
2014-08-23 04:34:07 -03:00
|
|
|
// zero initial pitch and highest airspeed on mode change
|
|
|
|
auto_state.highest_airspeed = 0;
|
|
|
|
auto_state.initial_pitch_cd = ahrs.pitch_sensor;
|
|
|
|
|
|
|
|
// disable taildrag takeoff on mode change
|
|
|
|
auto_state.fbwa_tdrag_takeoff_mode = false;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
switch(control_mode)
|
|
|
|
{
|
|
|
|
case INITIALISING:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
case MANUAL:
|
|
|
|
case STABILIZE:
|
2012-12-04 02:32:37 -04:00
|
|
|
case TRAINING:
|
2012-08-21 23:19:51 -03:00
|
|
|
case FLY_BY_WIRE_A:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = false;
|
|
|
|
break;
|
|
|
|
|
|
|
|
case AUTOTUNE:
|
|
|
|
auto_throttle_mode = false;
|
|
|
|
autotune_start();
|
2013-03-27 20:27:25 -03:00
|
|
|
break;
|
|
|
|
|
2013-07-12 08:34:32 -03:00
|
|
|
case ACRO:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = false;
|
2013-07-12 08:34:32 -03:00
|
|
|
acro_state.locked_roll = false;
|
|
|
|
acro_state.locked_pitch = false;
|
|
|
|
break;
|
|
|
|
|
2013-07-13 07:05:53 -03:00
|
|
|
case CRUISE:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
2013-07-13 07:05:53 -03:00
|
|
|
cruise_state.locked_heading = false;
|
|
|
|
cruise_state.lock_timer_ms = 0;
|
2014-07-24 03:21:30 -03:00
|
|
|
set_target_altitude_current();
|
2013-07-13 07:05:53 -03:00
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
case FLY_BY_WIRE_B:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
2014-07-24 03:21:30 -03:00
|
|
|
set_target_altitude_current();
|
2012-08-21 23:19:51 -03:00
|
|
|
break;
|
|
|
|
|
2013-02-10 22:52:25 -04:00
|
|
|
case CIRCLE:
|
|
|
|
// the altitude to circle at is taken from the current altitude
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
2014-03-16 01:53:10 -03:00
|
|
|
next_WP_loc.alt = current_loc.alt;
|
2013-02-10 22:52:25 -04:00
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
case AUTO:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
2014-05-18 03:14:11 -03:00
|
|
|
next_WP_loc = prev_WP_loc = current_loc;
|
2014-04-28 18:50:51 -03:00
|
|
|
// start or resume the mission, based on MIS_AUTORESET
|
|
|
|
mission.start_or_resume();
|
2012-08-21 23:19:51 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case RTL:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
2014-03-16 01:53:10 -03:00
|
|
|
prev_WP_loc = current_loc;
|
2012-08-21 23:19:51 -03:00
|
|
|
do_RTL();
|
|
|
|
break;
|
|
|
|
|
|
|
|
case LOITER:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
2012-08-21 23:19:51 -03:00
|
|
|
do_loiter_at_location();
|
|
|
|
break;
|
|
|
|
|
|
|
|
case GUIDED:
|
2014-04-12 01:12:14 -03:00
|
|
|
auto_throttle_mode = true;
|
2013-09-07 18:31:10 -03:00
|
|
|
guided_throttle_passthru = false;
|
2012-08-21 23:19:51 -03:00
|
|
|
set_guided_WP();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2014-04-12 01:12:14 -03:00
|
|
|
// start with throttle suppressed in auto_throttle modes
|
|
|
|
throttle_suppressed = auto_throttle_mode;
|
2012-08-27 03:26:53 -03:00
|
|
|
|
2014-01-13 22:07:43 -04:00
|
|
|
if (should_log(MASK_LOG_MODE))
|
2015-01-16 12:30:49 -04:00
|
|
|
DataFlash.Log_Write_Mode(control_mode);
|
2013-06-01 09:29:28 -03:00
|
|
|
|
|
|
|
// reset attitude integrators on mode change
|
2013-08-14 01:57:41 -03:00
|
|
|
rollController.reset_I();
|
|
|
|
pitchController.reset_I();
|
|
|
|
yawController.reset_I();
|
2014-08-24 19:20:37 -03:00
|
|
|
steerController.reset_I();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2014-10-01 01:19:20 -03:00
|
|
|
/*
|
|
|
|
set_mode() wrapper for MAVLink SET_MODE
|
|
|
|
*/
|
|
|
|
static bool mavlink_set_mode(uint8_t mode)
|
|
|
|
{
|
|
|
|
switch (mode) {
|
|
|
|
case MANUAL:
|
|
|
|
case CIRCLE:
|
|
|
|
case STABILIZE:
|
|
|
|
case TRAINING:
|
|
|
|
case ACRO:
|
|
|
|
case FLY_BY_WIRE_A:
|
|
|
|
case AUTOTUNE:
|
|
|
|
case FLY_BY_WIRE_B:
|
|
|
|
case CRUISE:
|
|
|
|
case AUTO:
|
|
|
|
case RTL:
|
|
|
|
case LOITER:
|
|
|
|
set_mode((enum FlightMode)mode);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2014-03-14 09:40:47 -03:00
|
|
|
// exit_mode - perform any cleanup required when leaving a flight mode
|
|
|
|
static void exit_mode(enum FlightMode mode)
|
|
|
|
{
|
|
|
|
// stop mission when we leave auto
|
|
|
|
if (mode == AUTO) {
|
|
|
|
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
|
|
|
mission.stop();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
static void check_long_failsafe()
|
|
|
|
{
|
2012-12-25 17:46:36 -04:00
|
|
|
uint32_t tnow = millis();
|
2012-08-21 23:19:51 -03:00
|
|
|
// only act on changes
|
|
|
|
// -------------------
|
2013-07-19 01:11:16 -03:00
|
|
|
if(failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS) {
|
ArduPlane failsafes: remove rc_override_active
- rc_override_active is never set anywhere in the ArduPlane code; it's only used for Copter and Rover. Removing it significantly simplifies the failsafe code.
- modified code has been tested in SITL. Heartbeat and RC failures in AUTO, CRUISE, and RTL modes (covering the three cases in the failsafe check functions) have been simulated with FS_LONG_ACTN = 0, 1, and 2, FS_SHORT_ACTN = 0, 1, and 2, and FS_GCS_ENABL = 0, 1, and 2. In all cases the results are identical to those with the original code.
2014-09-16 00:14:40 -03:00
|
|
|
if (failsafe.state == FAILSAFE_SHORT &&
|
2013-12-19 20:39:00 -04:00
|
|
|
(tnow - failsafe.ch3_timer_ms) > g.long_fs_timeout*1000) {
|
2012-08-21 23:19:51 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_LONG);
|
2013-12-19 20:39:00 -04:00
|
|
|
} else if (g.gcs_heartbeat_fs_enabled != GCS_FAILSAFE_OFF &&
|
|
|
|
failsafe.last_heartbeat_ms != 0 &&
|
|
|
|
(tnow - failsafe.last_heartbeat_ms) > g.long_fs_timeout*1000) {
|
|
|
|
failsafe_long_on_event(FAILSAFE_GCS);
|
|
|
|
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
|
2014-03-18 18:34:35 -03:00
|
|
|
gcs[0].last_radio_status_remrssi_ms != 0 &&
|
|
|
|
(tnow - gcs[0].last_radio_status_remrssi_ms) > g.long_fs_timeout*1000) {
|
2012-08-21 23:19:51 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_GCS);
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// We do not change state but allow for user to change mode
|
2013-07-19 01:11:16 -03:00
|
|
|
if (failsafe.state == FAILSAFE_GCS &&
|
|
|
|
(tnow - failsafe.last_heartbeat_ms) < g.short_fs_timeout*1000) {
|
|
|
|
failsafe.state = FAILSAFE_NONE;
|
|
|
|
} else if (failsafe.state == FAILSAFE_LONG &&
|
|
|
|
!failsafe.ch3_failsafe) {
|
|
|
|
failsafe.state = FAILSAFE_NONE;
|
2013-07-11 22:56:04 -03:00
|
|
|
}
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
static void check_short_failsafe()
|
|
|
|
{
|
2012-08-21 23:19:51 -03:00
|
|
|
// only act on changes
|
|
|
|
// -------------------
|
2013-07-19 01:11:16 -03:00
|
|
|
if(failsafe.state == FAILSAFE_NONE) {
|
|
|
|
if(failsafe.ch3_failsafe) { // The condition is checked and the flag ch3_failsafe is set in radio.pde
|
2012-08-21 23:19:51 -03:00
|
|
|
failsafe_short_on_event(FAILSAFE_SHORT);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-07-19 01:11:16 -03:00
|
|
|
if(failsafe.state == FAILSAFE_SHORT) {
|
|
|
|
if(!failsafe.ch3_failsafe) {
|
2012-08-21 23:19:51 -03:00
|
|
|
failsafe_short_off_event();
|
|
|
|
}
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-03-10 20:16:59 -03:00
|
|
|
static void startup_INS_ground(void)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2015-03-13 08:33:48 -03:00
|
|
|
if (g.hil_mode == 1) {
|
|
|
|
while (barometer.get_last_update() == 0) {
|
|
|
|
// the barometer begins updating when we get the first
|
|
|
|
// HIL_STATE message
|
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Waiting for first HIL_STATE message"));
|
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
}
|
2013-01-03 20:29:19 -04:00
|
|
|
}
|
|
|
|
|
2013-07-19 22:33:09 -03:00
|
|
|
AP_InertialSensor::Start_style style;
|
2015-03-10 20:16:59 -03:00
|
|
|
if (g.skip_gyro_cal) {
|
2013-07-19 22:33:09 -03:00
|
|
|
style = AP_InertialSensor::WARM_START;
|
2015-01-20 04:47:59 -04:00
|
|
|
arming.set_skip_gyro_cal(true);
|
2013-07-19 22:33:09 -03:00
|
|
|
} else {
|
|
|
|
style = AP_InertialSensor::COLD_START;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (style == AP_InertialSensor::COLD_START) {
|
|
|
|
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move plane"));
|
2013-10-30 19:00:56 -03:00
|
|
|
mavlink_delay(100);
|
2013-07-19 22:33:09 -03:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-01-13 01:04:18 -04:00
|
|
|
ahrs.init();
|
|
|
|
ahrs.set_fly_forward(true);
|
2014-04-21 04:12:24 -03:00
|
|
|
ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING);
|
2013-05-23 22:21:32 -03:00
|
|
|
ahrs.set_wind_estimation(true);
|
2013-01-13 01:04:18 -04:00
|
|
|
|
2013-09-19 05:33:42 -03:00
|
|
|
ins.init(style, ins_sample_rate);
|
2012-03-11 05:13:31 -03:00
|
|
|
ahrs.reset();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// read Baro pressure at ground
|
|
|
|
//-----------------------------
|
|
|
|
init_barometer();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-07-15 22:21:50 -03:00
|
|
|
if (airspeed.enabled()) {
|
2011-11-20 21:05:43 -04:00
|
|
|
// initialize airspeed sensor
|
|
|
|
// --------------------------
|
2014-11-13 06:12:59 -04:00
|
|
|
zero_airspeed(true);
|
2011-11-20 21:05:43 -04:00
|
|
|
} else {
|
2012-07-15 22:21:50 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW,PSTR("NO airspeed"));
|
2011-11-20 21:05:43 -04:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2013-08-29 00:13:58 -03:00
|
|
|
// updates the status of the notify objects
|
2013-08-24 05:58:32 -03:00
|
|
|
// should be called at 50hz
|
2013-08-29 00:13:58 -03:00
|
|
|
static void update_notify()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2013-08-29 00:13:58 -03:00
|
|
|
notify.update();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2014-10-22 02:14:51 -03:00
|
|
|
static void resetPerfData(void)
|
|
|
|
{
|
2012-08-21 23:19:51 -03:00
|
|
|
mainLoop_count = 0;
|
2013-10-11 23:30:27 -03:00
|
|
|
G_Dt_max = 0;
|
2014-10-22 02:14:51 -03:00
|
|
|
G_Dt_min = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
perf_mon_timer = millis();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2011-11-20 05:31:45 -04:00
|
|
|
static void check_usb_mux(void)
|
|
|
|
{
|
2013-09-19 03:23:58 -03:00
|
|
|
bool usb_check = hal.gpio->usb_connected();
|
2011-11-20 05:31:45 -04:00
|
|
|
if (usb_check == usb_connected) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// the user has switched to/from the telemetry port
|
|
|
|
usb_connected = usb_check;
|
2013-09-20 20:16:17 -03:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
|
|
// the APM2 has a MUX setup where the first serial port switches
|
|
|
|
// between USB and a TTL serial connection. When on USB we use
|
|
|
|
// SERIAL0_BAUD, but when connected as a TTL serial port we run it
|
2013-11-25 19:58:11 -04:00
|
|
|
// at SERIAL1_BAUD.
|
2011-11-20 05:31:45 -04:00
|
|
|
if (usb_connected) {
|
2015-04-01 19:13:20 -03:00
|
|
|
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_Console, 0);
|
2011-11-20 05:31:45 -04:00
|
|
|
} else {
|
2015-03-27 22:50:57 -03:00
|
|
|
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_MAVLink, 0);
|
2011-11-20 05:31:45 -04:00
|
|
|
}
|
2013-09-20 20:16:17 -03:00
|
|
|
#endif
|
2012-12-20 07:46:48 -04:00
|
|
|
}
|
2011-12-13 03:19:41 -04:00
|
|
|
|
|
|
|
|
2012-09-18 00:38:56 -03:00
|
|
|
static void
|
2013-04-20 02:18:10 -03:00
|
|
|
print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
2012-09-18 00:38:56 -03:00
|
|
|
{
|
|
|
|
switch (mode) {
|
|
|
|
case MANUAL:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("Manual"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
|
|
|
case CIRCLE:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("Circle"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
|
|
|
case STABILIZE:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("Stabilize"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
2012-12-04 02:32:37 -04:00
|
|
|
case TRAINING:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("Training"));
|
2012-12-04 02:32:37 -04:00
|
|
|
break;
|
2013-07-10 10:25:38 -03:00
|
|
|
case ACRO:
|
|
|
|
port->print_P(PSTR("ACRO"));
|
|
|
|
break;
|
2012-09-18 00:38:56 -03:00
|
|
|
case FLY_BY_WIRE_A:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("FBW_A"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
2014-04-12 01:12:14 -03:00
|
|
|
case AUTOTUNE:
|
|
|
|
port->print_P(PSTR("AUTOTUNE"));
|
|
|
|
break;
|
2012-09-18 00:38:56 -03:00
|
|
|
case FLY_BY_WIRE_B:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("FBW_B"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
2013-07-13 07:05:53 -03:00
|
|
|
case CRUISE:
|
|
|
|
port->print_P(PSTR("CRUISE"));
|
|
|
|
break;
|
2012-09-18 00:38:56 -03:00
|
|
|
case AUTO:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("AUTO"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
|
|
|
case RTL:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("RTL"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
|
|
|
case LOITER:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->print_P(PSTR("Loiter"));
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
2014-02-01 23:04:36 -04:00
|
|
|
case GUIDED:
|
|
|
|
port->print_P(PSTR("Guided"));
|
|
|
|
break;
|
2012-09-18 00:38:56 -03:00
|
|
|
default:
|
2013-04-20 02:18:10 -03:00
|
|
|
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
|
2012-09-18 00:38:56 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2012-09-18 00:48:08 -03:00
|
|
|
|
2015-04-24 02:08:06 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2012-09-18 00:48:08 -03:00
|
|
|
static void print_comma(void)
|
|
|
|
{
|
2012-11-21 01:19:16 -04:00
|
|
|
cliSerial->print_P(PSTR(","));
|
2012-09-18 00:48:08 -03:00
|
|
|
}
|
2015-04-24 02:08:06 -03:00
|
|
|
#endif
|
2012-12-04 18:22:21 -04:00
|
|
|
|
2013-03-30 00:38:43 -03:00
|
|
|
/*
|
|
|
|
write to a servo
|
|
|
|
*/
|
|
|
|
static void servo_write(uint8_t ch, uint16_t pwm)
|
|
|
|
{
|
2015-03-13 08:33:48 -03:00
|
|
|
if (g.hil_mode==1 && !g.hil_servos) {
|
2013-03-30 00:38:43 -03:00
|
|
|
if (ch < 8) {
|
2013-06-03 02:11:55 -03:00
|
|
|
RC_Channel::rc_channel(ch)->radio_out = pwm;
|
2013-03-30 00:38:43 -03:00
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
hal.rcout->enable_ch(ch);
|
|
|
|
hal.rcout->write(ch, pwm);
|
|
|
|
}
|
2014-01-13 22:07:43 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
should we log a message type now?
|
|
|
|
*/
|
|
|
|
static bool should_log(uint32_t mask)
|
|
|
|
{
|
2014-01-13 23:29:14 -04:00
|
|
|
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
2014-01-13 22:07:43 -04:00
|
|
|
return false;
|
|
|
|
}
|
2015-01-28 19:30:00 -04:00
|
|
|
bool ret = hal.util->get_soft_armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0;
|
2014-01-13 22:51:49 -04:00
|
|
|
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
2014-01-13 23:29:14 -04:00
|
|
|
// we have to set in_mavlink_delay to prevent logging while
|
|
|
|
// writing headers
|
|
|
|
in_mavlink_delay = true;
|
2015-01-15 13:22:09 -04:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2014-01-13 22:51:49 -04:00
|
|
|
start_logging();
|
2015-01-15 13:22:09 -04:00
|
|
|
#endif
|
2014-01-13 23:29:14 -04:00
|
|
|
in_mavlink_delay = false;
|
2014-01-13 22:51:49 -04:00
|
|
|
}
|
|
|
|
return ret;
|
2014-01-13 22:07:43 -04:00
|
|
|
}
|
2014-07-29 08:38:15 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
send FrSky telemetry. Should be called at 5Hz by scheduler
|
|
|
|
*/
|
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
2015-04-24 02:08:06 -03:00
|
|
|
static void frsky_telemetry_send(void)
|
|
|
|
{
|
2015-01-20 12:36:46 -04:00
|
|
|
frsky_telemetry.send_frames((uint8_t)control_mode);
|
2014-07-29 08:38:15 -03:00
|
|
|
}
|
2015-04-24 02:08:06 -03:00
|
|
|
#endif
|
2014-08-03 04:16:51 -03:00
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
return throttle percentage from 0 to 100
|
|
|
|
*/
|
|
|
|
static uint8_t throttle_percentage(void)
|
|
|
|
{
|
|
|
|
// to get the real throttle we need to use norm_output() which
|
|
|
|
// returns a number from -1 to 1.
|
|
|
|
return constrain_int16(50*(channel_throttle->norm_output()+1), 0, 100);
|
|
|
|
}
|
2015-02-22 04:39:58 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
update AHRS soft arm state and log as needed
|
|
|
|
*/
|
|
|
|
static void change_arm_state(void)
|
|
|
|
{
|
|
|
|
Log_Arm_Disarm();
|
|
|
|
hal.util->set_soft_armed(arming.is_armed() &&
|
|
|
|
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
|
|
|
|
|
|
|
// log the mode, so the following log is recorded as the correct mode
|
|
|
|
if (should_log(MASK_LOG_MODE)) {
|
|
|
|
DataFlash.Log_Write_Mode(control_mode);
|
|
|
|
}
|
|
|
|
}
|
2015-03-16 20:09:37 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
arm motors
|
|
|
|
*/
|
|
|
|
static bool arm_motors(AP_Arming::ArmingMethod method)
|
|
|
|
{
|
|
|
|
if (!arming.arm(method)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
//only log if arming was successful
|
|
|
|
channel_throttle->enable_out();
|
|
|
|
change_arm_state();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
disarm motors
|
|
|
|
*/
|
|
|
|
static bool disarm_motors(void)
|
|
|
|
{
|
|
|
|
if (!arming.disarm()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) {
|
|
|
|
channel_throttle->disable_out();
|
|
|
|
}
|
|
|
|
if (control_mode != AUTO) {
|
|
|
|
// reset the mission on disarm if we are not in auto
|
|
|
|
mission.reset();
|
|
|
|
}
|
|
|
|
|
|
|
|
// suppress the throttle in auto-throttle modes
|
|
|
|
throttle_suppressed = auto_throttle_mode;
|
|
|
|
|
|
|
|
//only log if disarming was successful
|
|
|
|
change_arm_state();
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|