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()
|
|
|
|
{
|
2012-08-21 23:19:51 -03:00
|
|
|
// Console serial port
|
|
|
|
//
|
|
|
|
// The console port buffers are defined to be sufficiently large to support
|
|
|
|
// the MAVLink protocol efficiently
|
|
|
|
//
|
2012-12-04 18:22:21 -04:00
|
|
|
hal.uartA->begin(SERIAL0_BAUD, 128, SERIAL_BUFSIZE);
|
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
|
|
|
|
2014-01-19 21:58:49 -04:00
|
|
|
BoardConfig.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
|
|
|
|
2013-01-12 16:39:40 -04:00
|
|
|
// reset the uartA baud rate after parameter load
|
|
|
|
hal.uartA->begin(map_baudrate(g.serial0_baud, SERIAL0_BAUD));
|
|
|
|
|
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();
|
|
|
|
|
2013-10-30 19:23:21 -03:00
|
|
|
// initialise sonar
|
|
|
|
init_sonar();
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// init the GCS
|
2013-11-22 04:18:19 -04:00
|
|
|
gcs[0].init(hal.uartA);
|
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
|
|
|
|
2011-11-20 05:31:45 -04:00
|
|
|
// we have a 2nd serial port for telemetry
|
2013-11-25 19:58:11 -04:00
|
|
|
hal.uartC->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD),
|
|
|
|
128, SERIAL1_BUFSIZE);
|
2013-11-22 04:18:19 -04:00
|
|
|
gcs[1].init(hal.uartC);
|
|
|
|
|
2013-11-25 19:58:11 -04:00
|
|
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
2013-11-23 06:44:45 -04:00
|
|
|
if (hal.uartD != NULL) {
|
2013-11-25 19:58:11 -04:00
|
|
|
hal.uartD->begin(map_baudrate(g.serial2_baud, SERIAL2_BAUD),
|
2013-11-22 04:18:19 -04:00
|
|
|
128, SERIAL2_BUFSIZE);
|
|
|
|
gcs[2].init(hal.uartD);
|
|
|
|
}
|
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
|
|
|
}
|
2011-12-21 08:29:22 -04:00
|
|
|
#endif
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-12-27 04:24:15 -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);
|
|
|
|
|
2013-09-28 11:52:51 -03:00
|
|
|
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN || 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
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
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
|
2014-03-28 16:52:48 -03:00
|
|
|
gps.init(&DataFlash);
|
2013-12-21 07:27:15 -04:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
//mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav
|
|
|
|
mavlink_system.compid = 1; //MAV_COMP_ID_IMU; // We do not check for comp id
|
|
|
|
mavlink_system.type = MAV_TYPE_FIXED_WING;
|
2011-09-08 22:29:39 -03: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
|
|
|
|
|
|
|
#if FENCE_TRIGGERED_PIN > 0
|
2013-09-30 07:45:50 -03:00
|
|
|
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, OUTPUT);
|
2011-12-16 15:28:25 -04:00
|
|
|
digitalWrite(FENCE_TRIGGERED_PIN, LOW);
|
|
|
|
#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
|
|
|
|
2012-11-21 01:19:16 -04:00
|
|
|
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
|
|
|
cliSerial->println_P(msg);
|
2013-11-22 04:18:19 -04:00
|
|
|
if (gcs[1].initialised) {
|
2013-09-19 03:23:58 -03:00
|
|
|
hal.uartC->println_P(msg);
|
|
|
|
}
|
2013-11-22 04:18:19 -04:00
|
|
|
if (num_gcs > 2 && gcs[2].initialised) {
|
|
|
|
hal.uartD->println_P(msg);
|
|
|
|
}
|
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();
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
set_mode(MANUAL);
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// set the correct flight mode
|
|
|
|
// ---------------------------
|
|
|
|
reset_control_switch();
|
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
|
|
|
//
|
2013-05-02 00:38:28 -03:00
|
|
|
startup_INS_ground(false);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// read the radio to set trims
|
|
|
|
// ---------------------------
|
|
|
|
trim_radio(); // This was commented out as a HACK. Why? I don't find a problem.
|
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
|
2013-06-04 00:34:58 -03:00
|
|
|
hal.uartA->set_blocking_writes(false);
|
2012-12-04 18:22:21 -04:00
|
|
|
hal.uartC->set_blocking_writes(false);
|
2013-11-23 06:44:45 -04:00
|
|
|
if (hal.uartD != NULL) {
|
|
|
|
hal.uartD->set_blocking_writes(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);
|
|
|
|
|
|
|
|
// 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;
|
|
|
|
|
|
|
|
switch(control_mode)
|
|
|
|
{
|
|
|
|
case INITIALISING:
|
|
|
|
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:
|
2013-03-27 20:27:25 -03:00
|
|
|
break;
|
|
|
|
|
2013-07-12 08:34:32 -03:00
|
|
|
case ACRO:
|
|
|
|
acro_state.locked_roll = false;
|
|
|
|
acro_state.locked_pitch = false;
|
|
|
|
break;
|
|
|
|
|
2013-07-13 07:05:53 -03:00
|
|
|
case CRUISE:
|
|
|
|
cruise_state.locked_heading = false;
|
|
|
|
cruise_state.lock_timer_ms = 0;
|
|
|
|
target_altitude_cm = current_loc.alt;
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
case FLY_BY_WIRE_B:
|
2013-03-27 20:27:25 -03:00
|
|
|
target_altitude_cm = current_loc.alt;
|
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-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-03-16 01:53:10 -03:00
|
|
|
prev_WP_loc = current_loc;
|
2014-03-13 22:01:42 -03:00
|
|
|
// start the mission. Note that we use resume(), not start(),
|
|
|
|
// as the correct behaviour for plane when entering auto is to
|
|
|
|
// continue the mission. If the pilot wants to restart the
|
|
|
|
// mission they need to either use RST_MISSION_CH or change
|
|
|
|
// waypoint number to 0
|
|
|
|
mission.resume();
|
2012-08-21 23:19:51 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case RTL:
|
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:
|
|
|
|
do_loiter_at_location();
|
|
|
|
break;
|
|
|
|
|
|
|
|
case GUIDED:
|
2013-09-07 18:31:10 -03:00
|
|
|
guided_throttle_passthru = false;
|
2012-08-21 23:19:51 -03:00
|
|
|
set_guided_WP();
|
|
|
|
break;
|
|
|
|
|
|
|
|
default:
|
2014-03-16 01:53:10 -03:00
|
|
|
prev_WP_loc = current_loc;
|
2012-08-21 23:19:51 -03:00
|
|
|
do_RTL();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2012-08-27 03:26:53 -03:00
|
|
|
// if in an auto-throttle mode, start with throttle suppressed for
|
|
|
|
// safety. suppress_throttle() will unsupress it when appropriate
|
|
|
|
if (control_mode == CIRCLE || control_mode >= FLY_BY_WIRE_B) {
|
2013-07-05 01:55:22 -03:00
|
|
|
auto_throttle_mode = true;
|
2012-08-27 03:26:53 -03:00
|
|
|
throttle_suppressed = true;
|
2013-07-05 01:55:22 -03:00
|
|
|
} else {
|
|
|
|
auto_throttle_mode = false;
|
|
|
|
throttle_suppressed = false;
|
2012-08-27 03:26:53 -03:00
|
|
|
}
|
|
|
|
|
2014-01-13 22:07:43 -04:00
|
|
|
if (should_log(MASK_LOG_MODE))
|
2012-08-21 23:19:51 -03:00
|
|
|
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();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
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) {
|
|
|
|
if (failsafe.rc_override_active && (tnow - failsafe.last_heartbeat_ms) > g.long_fs_timeout*1000) {
|
2012-08-21 23:19:51 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_LONG);
|
2013-07-19 01:11:16 -03:00
|
|
|
} else if (!failsafe.rc_override_active &&
|
|
|
|
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.rc_override_active &&
|
|
|
|
(tnow - failsafe.last_heartbeat_ms) < g.short_fs_timeout*1000) {
|
|
|
|
failsafe.state = FAILSAFE_NONE;
|
|
|
|
} else if (failsafe.state == FAILSAFE_LONG &&
|
|
|
|
!failsafe.rc_override_active &&
|
|
|
|
!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
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-05-02 00:38:28 -03:00
|
|
|
static void startup_INS_ground(bool do_accel_init)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2013-01-03 20:29:19 -04:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
|
|
|
while (!barometer.healthy) {
|
|
|
|
// the barometer becomes healthy when we get the first
|
|
|
|
// HIL_STATE message
|
|
|
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Waiting for first HIL_STATE message"));
|
|
|
|
delay(1000);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2013-07-19 22:33:09 -03:00
|
|
|
AP_InertialSensor::Start_style style;
|
|
|
|
if (g.skip_gyro_cal && !do_accel_init) {
|
|
|
|
style = AP_InertialSensor::WARM_START;
|
|
|
|
} 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);
|
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);
|
2013-05-02 00:38:28 -03:00
|
|
|
if (do_accel_init) {
|
2013-09-19 05:33:42 -03:00
|
|
|
ins.init_accel();
|
2013-05-02 00:38:28 -03:00
|
|
|
ahrs.set_trim(Vector3f(0, 0, 0));
|
|
|
|
}
|
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
|
|
|
|
// --------------------------
|
|
|
|
zero_airspeed();
|
|
|
|
} 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
|
|
|
}
|
|
|
|
|
|
|
|
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;
|
2012-08-21 23:19:51 -03:00
|
|
|
perf_mon_timer = millis();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
2012-08-21 23:19:51 -03:00
|
|
|
* map from a 8 bit EEPROM baud rate to a real baud rate
|
2011-09-08 22:29:39 -03:00
|
|
|
*/
|
|
|
|
static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
|
|
|
{
|
|
|
|
switch (rate) {
|
2012-02-04 04:06:22 -04:00
|
|
|
case 1: return 1200;
|
|
|
|
case 2: return 2400;
|
|
|
|
case 4: return 4800;
|
2011-09-08 22:29:39 -03:00
|
|
|
case 9: return 9600;
|
|
|
|
case 19: return 19200;
|
|
|
|
case 38: return 38400;
|
|
|
|
case 57: return 57600;
|
|
|
|
case 111: return 111100;
|
|
|
|
case 115: return 115200;
|
|
|
|
}
|
2013-11-25 19:58:11 -04:00
|
|
|
cliSerial->println_P(PSTR("Invalid baudrate"));
|
2011-09-08 22:29:39 -03:00
|
|
|
return default_baud;
|
|
|
|
}
|
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) {
|
2012-12-04 18:22:21 -04:00
|
|
|
hal.uartA->begin(SERIAL0_BAUD);
|
2011-11-20 05:31:45 -04:00
|
|
|
} else {
|
2013-11-25 19:58:11 -04:00
|
|
|
hal.uartA->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD));
|
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;
|
|
|
|
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
|
|
|
|
|
|
|
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
|
|
|
}
|
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)
|
|
|
|
{
|
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
|
|
|
if (!g.hil_servos) {
|
|
|
|
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;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
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;
|
|
|
|
}
|
2014-02-18 19:53:26 -04:00
|
|
|
bool ret = ahrs.get_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;
|
2014-01-13 22:51:49 -04:00
|
|
|
start_logging();
|
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
|
|
|
}
|