2011-04-16 17:44:44 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2015-05-29 23:12:49 -03:00
|
|
|
|
|
|
|
#include "Copter.h"
|
|
|
|
|
2011-04-16 17:44:44 -03:00
|
|
|
/*****************************************************************************
|
2012-08-21 23:19:50 -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-04-16 17:44:44 -03:00
|
|
|
*****************************************************************************/
|
|
|
|
|
2011-07-17 07:34:05 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2011-04-16 17:44:44 -03:00
|
|
|
|
|
|
|
// This is the help function
|
2015-05-29 23:12:49 -03:00
|
|
|
int8_t Copter::main_menu_help(uint8_t argc, const Menu::arg *argv)
|
2011-04-16 17:44:44 -03:00
|
|
|
{
|
2012-11-21 02:08:03 -04:00
|
|
|
cliSerial->printf_P(PSTR("Commands:\n"
|
2012-08-21 23:19:50 -03:00
|
|
|
" logs\n"
|
|
|
|
" setup\n"
|
|
|
|
" test\n"
|
2012-11-24 03:20:03 -04:00
|
|
|
" reboot\n"
|
2012-08-21 23:19:50 -03:00
|
|
|
"\n"));
|
|
|
|
return(0);
|
2011-04-16 17:44:44 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// Command/function table for the top-level menu.
|
|
|
|
const struct Menu::command main_menu_commands[] PROGMEM = {
|
|
|
|
// command function called
|
|
|
|
// ======= ===============
|
2015-05-29 23:12:49 -03:00
|
|
|
{"logs", MENU_FUNC(process_logs)},
|
|
|
|
{"setup", MENU_FUNC(setup_mode)},
|
|
|
|
{"test", MENU_FUNC(test_mode)},
|
|
|
|
{"reboot", MENU_FUNC(reboot_board)},
|
|
|
|
{"help", MENU_FUNC(main_menu_help)},
|
2011-04-16 17:44:44 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// Create the top-level menu object.
|
2011-09-17 15:25:31 -03:00
|
|
|
MENU(main_menu, THISFIRMWARE, main_menu_commands);
|
2011-04-16 17:44:44 -03:00
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
int8_t Copter::reboot_board(uint8_t argc, const Menu::arg *argv)
|
2012-11-24 03:20:03 -04:00
|
|
|
{
|
2013-09-03 22:59:02 -03:00
|
|
|
hal.scheduler->reboot(false);
|
2012-11-24 03:20:03 -04:00
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2011-10-27 04:35:25 -03:00
|
|
|
// the user wants the CLI. It never exits
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::run_cli(AP_HAL::UARTDriver *port)
|
2011-10-27 04:35:25 -03:00
|
|
|
{
|
2012-11-21 02:08:03 -04:00
|
|
|
cliSerial = port;
|
|
|
|
Menu::set_port(port);
|
|
|
|
port->set_blocking_writes(true);
|
|
|
|
|
2012-12-23 17:51:33 -04:00
|
|
|
// disable the mavlink delay callback
|
|
|
|
hal.scheduler->register_delay_callback(NULL, 5);
|
|
|
|
|
2013-03-02 04:54:18 -04:00
|
|
|
// disable main_loop failsafe
|
|
|
|
failsafe_disable();
|
|
|
|
|
2013-03-21 00:07:00 -03:00
|
|
|
// cut the engines
|
|
|
|
if(motors.armed()) {
|
|
|
|
motors.armed(false);
|
|
|
|
motors.output();
|
|
|
|
}
|
2013-10-29 01:28:27 -03:00
|
|
|
|
2011-10-27 04:35:25 -03:00
|
|
|
while (1) {
|
|
|
|
main_menu.run();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2011-07-17 07:34:05 -03:00
|
|
|
#endif // CLI_ENABLED
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
static void mavlink_delay_cb_static()
|
|
|
|
{
|
|
|
|
copter.mavlink_delay_cb();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
static void failsafe_check_static()
|
|
|
|
{
|
|
|
|
copter.failsafe_check();
|
|
|
|
}
|
|
|
|
|
|
|
|
void Copter::init_ardupilot()
|
2011-04-16 17:44:44 -03:00
|
|
|
{
|
2013-09-20 20:21:17 -03:00
|
|
|
if (!hal.gpio->usb_connected()) {
|
2011-11-20 05:42:51 -04:00
|
|
|
// USB is not connected, this means UART0 may be a Xbee, with
|
|
|
|
// its darned bricking problem. We can't write to it for at
|
|
|
|
// least one second after powering up. Simplest solution for
|
|
|
|
// now is to delay for 1 second. Something more elegant may be
|
|
|
|
// added later
|
|
|
|
delay(1000);
|
|
|
|
}
|
|
|
|
|
2015-01-19 09:52:54 -04:00
|
|
|
// initialise serial port
|
|
|
|
serial_manager.init_console();
|
2014-02-25 18:40:29 -04:00
|
|
|
|
2013-11-08 07:29:29 -04:00
|
|
|
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
2012-08-21 23:19:50 -03:00
|
|
|
"\n\nFree RAM: %u\n"),
|
2013-12-28 01:02:32 -04:00
|
|
|
hal.util->available_memory());
|
2011-04-16 17:44:44 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
//
|
2012-09-13 09:49:11 -03:00
|
|
|
// Report firmware version code expect on console (check of actual EEPROM format version is done in load_parameters function)
|
2012-08-21 23:19:50 -03:00
|
|
|
//
|
|
|
|
report_version();
|
2011-04-16 17:44:44 -03:00
|
|
|
|
2012-02-12 07:27:51 -04:00
|
|
|
// load parameters from EEPROM
|
|
|
|
load_parameters();
|
2011-04-16 17:44:44 -03:00
|
|
|
|
2014-01-19 21:58:12 -04:00
|
|
|
BoardConfig.init();
|
|
|
|
|
2015-01-19 09:52:54 -04:00
|
|
|
// initialise serial port
|
|
|
|
serial_manager.init();
|
|
|
|
|
2013-12-19 01:12:19 -04:00
|
|
|
// init EPM cargo gripper
|
|
|
|
#if EPM_ENABLED == ENABLED
|
|
|
|
epm.init();
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// initialise notify system
|
|
|
|
// disable external leds if epm is enabled because of pin conflict on the APM
|
2014-09-15 03:52:21 -03:00
|
|
|
notify.init(true);
|
2013-12-19 01:12:19 -04:00
|
|
|
|
|
|
|
// initialise battery monitor
|
|
|
|
battery.init();
|
|
|
|
|
|
|
|
rssi_analog_source = hal.analogin->channel(g.rssi_pin);
|
|
|
|
|
2013-05-25 00:21:29 -03:00
|
|
|
barometer.init();
|
|
|
|
|
2012-12-13 19:27:42 -04:00
|
|
|
// Register the mavlink service callback. This will run
|
|
|
|
// anytime there are more than 5ms remaining in a call to
|
|
|
|
// hal.scheduler->delay.
|
2015-05-29 23:12:49 -03:00
|
|
|
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
2012-12-13 19:27:42 -04:00
|
|
|
|
2013-09-20 20:21:17 -03:00
|
|
|
// we start by assuming USB connected, as we initialed the serial
|
2013-10-29 01:28:27 -03:00
|
|
|
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
|
2013-10-08 03:25:14 -03:00
|
|
|
ap.usb_connected = true;
|
2013-09-20 20:21:17 -03:00
|
|
|
check_usb_mux();
|
2013-09-19 03:24:23 -03:00
|
|
|
|
2015-01-27 23:38:55 -04:00
|
|
|
// init the GCS connected to the console
|
2015-03-27 22:50:08 -03:00
|
|
|
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console, 0);
|
2015-01-27 23:38:55 -04:00
|
|
|
|
2015-03-13 03:25:08 -03:00
|
|
|
// init telemetry port
|
2015-03-27 22:50:08 -03:00
|
|
|
gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
2014-07-28 19:25:40 -03:00
|
|
|
|
2013-11-25 19:58:50 -04:00
|
|
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
2015-01-19 09:52:54 -04:00
|
|
|
// setup serial port for telem2
|
2015-03-27 22:50:08 -03:00
|
|
|
gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1);
|
2015-01-19 09:52:54 -04:00
|
|
|
#endif
|
|
|
|
|
2015-05-15 01:24:18 -03:00
|
|
|
#if MAVLINK_COMM_NUM_BUFFERS > 3
|
|
|
|
// setup serial port for fourth telemetry port (not used by default)
|
|
|
|
gcs[3].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 2);
|
|
|
|
#endif
|
|
|
|
|
2015-01-19 09:52:54 -04:00
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
|
|
|
// setup frsky
|
|
|
|
frsky_telemetry.init(serial_manager);
|
2013-11-25 19:58:50 -04:00
|
|
|
#endif
|
2011-08-01 08:39:17 -03:00
|
|
|
|
2011-12-02 16:54:36 -04:00
|
|
|
// identify ourselves correctly with the ground station
|
2012-08-21 23:19:50 -03:00
|
|
|
mavlink_system.sysid = g.sysid_this_mav;
|
2012-02-11 02:25:24 -04:00
|
|
|
|
2011-12-28 00:53:05 -04:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2015-05-29 23:12:49 -03:00
|
|
|
log_init();
|
2011-12-28 00:53:05 -04:00
|
|
|
#endif
|
2011-12-17 19:19:41 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
init_rc_in(); // sets up rc channels from radio
|
2013-05-16 04:32:00 -03:00
|
|
|
init_rc_out(); // sets up motors and output to escs
|
|
|
|
|
2014-07-26 04:30:31 -03:00
|
|
|
// initialise which outputs Servo and Relay events can use
|
|
|
|
ServoRelayEvents.set_channel_mask(~motors.get_motor_mask());
|
|
|
|
|
|
|
|
relay.init();
|
|
|
|
|
2012-10-09 00:30:17 -03:00
|
|
|
/*
|
|
|
|
* setup the 'main loop is dead' check. Note that this relies on
|
|
|
|
* the RC library being initialised.
|
|
|
|
*/
|
2015-05-29 23:12:49 -03:00
|
|
|
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
|
2012-06-29 08:51:05 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// Do GPS init
|
2015-01-19 09:52:54 -04:00
|
|
|
gps.init(&DataFlash, serial_manager);
|
2014-02-25 18:40:29 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
if(g.compass_enabled)
|
|
|
|
init_compass();
|
2011-04-16 17:44:44 -03:00
|
|
|
|
2015-01-03 21:29:22 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2015-01-02 20:15:46 -04:00
|
|
|
// make optflow available to AHRS
|
|
|
|
ahrs.set_optflow(&optflow);
|
2015-01-03 21:29:22 -04:00
|
|
|
#endif
|
2015-01-02 20:15:46 -04:00
|
|
|
|
2013-12-29 09:09:42 -04:00
|
|
|
// initialise attitude and position controllers
|
2013-12-16 23:25:33 -04:00
|
|
|
attitude_control.set_dt(MAIN_LOOP_SECONDS);
|
2013-12-29 09:09:42 -04:00
|
|
|
pos_control.set_dt(MAIN_LOOP_SECONDS);
|
2013-12-16 23:25:33 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// init the optical flow sensor
|
2014-07-11 23:34:55 -03:00
|
|
|
init_optflow();
|
2011-12-23 18:42:05 -04:00
|
|
|
|
2015-03-21 09:02:06 -03:00
|
|
|
#if MOUNT == ENABLED
|
2015-01-11 02:37:26 -04:00
|
|
|
// initialise camera mount
|
2015-01-19 09:52:54 -04:00
|
|
|
camera_mount.init(serial_manager);
|
2015-03-21 09:02:06 -03:00
|
|
|
#endif
|
2015-01-11 02:37:26 -04:00
|
|
|
|
2011-10-18 03:51:47 -03:00
|
|
|
#ifdef USERHOOK_INIT
|
2012-08-21 23:19:50 -03:00
|
|
|
USERHOOK_INIT
|
2011-10-18 03:51:47 -03:00
|
|
|
#endif
|
2011-11-19 18:01:47 -04:00
|
|
|
|
2013-03-18 02:07:04 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2015-03-09 00:18:16 -03:00
|
|
|
if (g.cli_enabled) {
|
|
|
|
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-23 06:45:42 -04:00
|
|
|
}
|
2011-07-17 07:34:05 -03:00
|
|
|
#endif // CLI_ENABLED
|
|
|
|
|
2013-03-18 02:19:31 -03:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
2014-08-13 10:54:41 -03:00
|
|
|
while (barometer.get_last_update() == 0) {
|
|
|
|
// the barometer begins updating when we get the first
|
2013-03-18 02:19:31 -03:00
|
|
|
// HIL_STATE message
|
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Waiting for first HIL_STATE message"));
|
|
|
|
delay(1000);
|
|
|
|
}
|
2014-10-15 20:33:24 -03:00
|
|
|
|
|
|
|
// set INS to HIL mode
|
|
|
|
ins.set_hil_mode();
|
2013-03-18 02:19:31 -03:00
|
|
|
#endif
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// read Baro pressure at ground
|
|
|
|
//-----------------------------
|
2014-01-15 10:18:23 -04:00
|
|
|
init_barometer(true);
|
2012-08-21 23:19:50 -03:00
|
|
|
|
|
|
|
// initialise sonar
|
|
|
|
#if CONFIG_SONAR == ENABLED
|
|
|
|
init_sonar();
|
|
|
|
#endif
|
|
|
|
|
2014-03-11 00:54:22 -03:00
|
|
|
// initialise mission library
|
|
|
|
mission.init();
|
|
|
|
|
2013-07-16 10:05:59 -03:00
|
|
|
// initialise the flight mode and aux switch
|
2012-08-21 23:19:50 -03:00
|
|
|
// ---------------------------
|
|
|
|
reset_control_switch();
|
2013-07-16 10:05:59 -03:00
|
|
|
init_aux_switches();
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-11-10 08:05:58 -04:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
// trad heli specific initialisation
|
|
|
|
heli_init();
|
|
|
|
#endif
|
|
|
|
|
2013-11-10 08:51:54 -04:00
|
|
|
startup_ground(true);
|
2011-07-30 17:42:54 -03:00
|
|
|
|
2014-07-11 03:27:29 -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-19 09:52:54 -04:00
|
|
|
serial_manager.set_blocking_writes_all(false);
|
2014-07-11 03:27:29 -03:00
|
|
|
|
2015-04-13 03:57:44 -03:00
|
|
|
// enable CPU failsafe
|
|
|
|
failsafe_enable();
|
|
|
|
|
2015-05-06 23:09:00 -03:00
|
|
|
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
|
|
|
ins.set_dataflash(&DataFlash);
|
|
|
|
|
2015-07-30 03:44:18 -03:00
|
|
|
// init vehicle capabilties
|
|
|
|
init_capabilities();
|
|
|
|
|
2012-12-13 15:48:01 -04:00
|
|
|
cliSerial->print_P(PSTR("\nReady to FLY "));
|
2014-09-09 10:17:46 -03:00
|
|
|
|
|
|
|
// flag that initialisation has completed
|
|
|
|
ap.initialised = true;
|
2012-12-13 15:48:01 -04:00
|
|
|
}
|
|
|
|
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-12-13 15:48:01 -04:00
|
|
|
//******************************************************************************
|
2011-07-30 17:42:54 -03:00
|
|
|
//This function does all the calibrations, etc. that we need during a ground start
|
2012-12-13 15:48:01 -04:00
|
|
|
//******************************************************************************
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::startup_ground(bool force_gyro_cal)
|
2011-07-30 17:42:54 -03:00
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
gcs_send_text_P(SEVERITY_LOW,PSTR("GROUND START"));
|
2011-07-30 17:42:54 -03:00
|
|
|
|
2013-01-13 01:04:04 -04:00
|
|
|
// initialise ahrs (may push imu calibration into the mpu6000 if using that device).
|
|
|
|
ahrs.init();
|
2014-04-21 05:11:53 -03:00
|
|
|
ahrs.set_vehicle_class(AHRS_VEHICLE_COPTER);
|
2013-01-13 01:04:04 -04:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// Warm up and read Gyro offsets
|
|
|
|
// -----------------------------
|
2013-10-29 19:23:47 -03:00
|
|
|
ins.init(force_gyro_cal?AP_InertialSensor::COLD_START:AP_InertialSensor::WARM_START,
|
2013-09-19 05:33:21 -03:00
|
|
|
ins_sample_rate);
|
2012-08-21 23:19:50 -03:00
|
|
|
#if CLI_ENABLED == ENABLED
|
2012-11-05 00:32:38 -04:00
|
|
|
report_ins();
|
2012-08-21 23:19:50 -03:00
|
|
|
#endif
|
2011-07-30 17:42:54 -03:00
|
|
|
|
2014-10-28 08:23:18 -03:00
|
|
|
// reset ahrs gyro bias
|
|
|
|
if (force_gyro_cal) {
|
|
|
|
ahrs.reset_gyro_drift();
|
|
|
|
}
|
|
|
|
|
2013-07-28 04:45:39 -03:00
|
|
|
// set landed flag
|
|
|
|
set_land_complete(true);
|
2014-09-19 03:54:36 -03:00
|
|
|
set_land_complete_maybe(true);
|
2011-04-16 17:44:44 -03:00
|
|
|
}
|
|
|
|
|
2015-01-02 07:43:50 -04:00
|
|
|
// position_ok - returns true if the horizontal absolute position is ok and home position is set
|
2015-05-29 23:12:49 -03:00
|
|
|
bool Copter::position_ok()
|
2013-07-19 23:01:10 -03:00
|
|
|
{
|
2015-06-15 03:53:41 -03:00
|
|
|
// return false if ekf failsafe has triggered
|
|
|
|
if (failsafe.ekf) {
|
2015-03-19 00:36:20 -03:00
|
|
|
return false;
|
|
|
|
}
|
2015-01-05 23:15:35 -04:00
|
|
|
|
2015-06-15 03:53:41 -03:00
|
|
|
// check ekf position estimate
|
|
|
|
return ekf_position_ok();
|
|
|
|
}
|
|
|
|
|
|
|
|
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
|
|
|
|
bool Copter::ekf_position_ok()
|
|
|
|
{
|
|
|
|
if (!ahrs.have_inertial_nav()) {
|
|
|
|
// do not allow navigation with dcm position
|
2015-03-19 00:36:20 -03:00
|
|
|
return false;
|
|
|
|
}
|
2015-01-05 23:15:35 -04:00
|
|
|
|
2015-03-19 00:36:20 -03:00
|
|
|
// with EKF use filter status and ekf check
|
|
|
|
nav_filter_status filt_status = inertial_nav.get_filter_status();
|
|
|
|
|
|
|
|
// if disarmed we accept a predicted horizontal position
|
|
|
|
if (!motors.armed()) {
|
|
|
|
return ((filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs));
|
2015-01-02 07:43:50 -04:00
|
|
|
} else {
|
2015-03-19 00:36:20 -03:00
|
|
|
// once armed we require a good absolute position and EKF must not be in const_pos_mode
|
|
|
|
return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
|
2013-07-19 23:01:10 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-01-02 07:45:10 -04:00
|
|
|
// optflow_position_ok - returns true if optical flow based position estimate is ok
|
2015-05-29 23:12:49 -03:00
|
|
|
bool Copter::optflow_position_ok()
|
2015-01-02 07:45:10 -04:00
|
|
|
{
|
|
|
|
#if OPTFLOW != ENABLED
|
|
|
|
return false;
|
|
|
|
#else
|
2015-01-05 23:16:24 -04:00
|
|
|
// return immediately if optflow is not enabled or EKF not used
|
|
|
|
if (!optflow.enabled() || !ahrs.have_inertial_nav()) {
|
2015-01-02 07:45:10 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-01-05 23:16:24 -04:00
|
|
|
// get filter status from EKF
|
2015-01-05 01:14:27 -04:00
|
|
|
nav_filter_status filt_status = inertial_nav.get_filter_status();
|
|
|
|
return (filt_status.flags.horiz_pos_rel || filt_status.flags.pred_horiz_pos_rel);
|
2015-01-02 07:45:10 -04:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2013-04-17 09:25:32 -03:00
|
|
|
// update_auto_armed - update status of auto_armed flag
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::update_auto_armed()
|
2013-04-17 09:25:32 -03:00
|
|
|
{
|
|
|
|
// disarm checks
|
|
|
|
if(ap.auto_armed){
|
|
|
|
// if motors are disarmed, auto_armed should also be false
|
|
|
|
if(!motors.armed()) {
|
|
|
|
set_auto_armed(false);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
// if in stabilize or acro flight mode and throttle is zero, auto-armed should become false
|
2015-01-21 06:57:02 -04:00
|
|
|
if(mode_has_manual_throttle(control_mode) && ap.throttle_zero && !failsafe.radio) {
|
2013-04-17 09:25:32 -03:00
|
|
|
set_auto_armed(false);
|
|
|
|
}
|
2015-06-10 19:33:42 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
// if helicopters are on the ground, and the motor is switched off, auto-armed should be false
|
|
|
|
// so that rotor runup is checked again before attempting to take-off
|
|
|
|
if(ap.land_complete && !motors.rotor_runup_complete()) {
|
|
|
|
set_auto_armed(false);
|
|
|
|
}
|
|
|
|
#endif // HELI_FRAME
|
2013-04-17 09:25:32 -03:00
|
|
|
}else{
|
|
|
|
// arm checks
|
2013-07-19 17:16:37 -03:00
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
// for tradheli if motors are armed and throttle is above zero and the motor is started, auto_armed should be true
|
2015-05-28 18:28:55 -03:00
|
|
|
if(motors.armed() && !ap.throttle_zero && motors.rotor_runup_complete()) {
|
2013-11-04 07:54:47 -04:00
|
|
|
set_auto_armed(true);
|
|
|
|
}
|
2013-07-19 17:16:37 -03:00
|
|
|
#else
|
2013-04-17 09:25:32 -03:00
|
|
|
// if motors are armed and throttle is above zero auto_armed should be true
|
2014-10-07 12:29:24 -03:00
|
|
|
if(motors.armed() && !ap.throttle_zero) {
|
2013-04-17 09:25:32 -03:00
|
|
|
set_auto_armed(true);
|
|
|
|
}
|
2013-11-04 07:54:47 -04:00
|
|
|
#endif // HELI_FRAME
|
2013-04-17 09:25:32 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::check_usb_mux(void)
|
2011-11-20 05:42:51 -04:00
|
|
|
{
|
2013-09-19 03:24:23 -03:00
|
|
|
bool usb_check = hal.gpio->usb_connected();
|
2013-10-08 03:25:14 -03:00
|
|
|
if (usb_check == ap.usb_connected) {
|
2011-11-20 05:42:51 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// the user has switched to/from the telemetry port
|
2013-10-08 03:25:14 -03:00
|
|
|
ap.usb_connected = usb_check;
|
2011-11-20 05:42:51 -04:00
|
|
|
}
|
2011-12-13 03:19:41 -04:00
|
|
|
|
2015-01-27 03:32:05 -04:00
|
|
|
// frsky_telemetry_send - sends telemetry data using frsky telemetry
|
|
|
|
// should be called at 5Hz by scheduler
|
2015-04-24 02:08:30 -03:00
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::frsky_telemetry_send(void)
|
2014-07-28 19:25:40 -03:00
|
|
|
{
|
2015-01-20 12:14:39 -04:00
|
|
|
frsky_telemetry.send_frames((uint8_t)control_mode);
|
2014-07-28 19:25:40 -03:00
|
|
|
}
|
2015-04-24 02:08:30 -03:00
|
|
|
#endif
|
2014-10-16 21:37:49 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
should we log a message type now?
|
|
|
|
*/
|
2015-05-29 23:12:49 -03:00
|
|
|
bool Copter::should_log(uint32_t mask)
|
2014-10-16 21:37:49 -03:00
|
|
|
{
|
2014-10-17 04:07:47 -03:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2014-10-16 21:37:49 -03:00
|
|
|
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
bool ret = motors.armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0;
|
|
|
|
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
|
|
|
// we have to set in_mavlink_delay to prevent logging while
|
|
|
|
// writing headers
|
|
|
|
start_logging();
|
|
|
|
}
|
|
|
|
return ret;
|
2014-10-17 04:07:47 -03:00
|
|
|
#else
|
|
|
|
return false;
|
|
|
|
#endif
|
2014-10-16 21:37:49 -03:00
|
|
|
}
|