ardupilot/ArduPlane/system.pde

593 lines
16 KiB
Plaintext
Raw Normal View History

// -*- 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.
*
*****************************************************************************/
#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
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv);
// 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)
{
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"
" reboot reboot to flight mode\n"
2012-08-21 23:19:51 -03:00
"\n"));
return(0);
}
// 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},
{"reboot", reboot_board},
2012-08-21 23:19:51 -03:00
{"help", main_menu_help},
};
// Create the top-level menu object.
MENU(main_menu, THISFIRMWARE, main_menu_commands);
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv)
{
2013-09-03 22:59:16 -03:00
hal.scheduler->reboot(false);
return 0;
}
// the user wants the CLI. It never exits
2012-12-04 18:22:21 -04:00
static void run_cli(AP_HAL::UARTDriver *port)
{
// disable the failsafe code in the CLI
2012-12-04 18:22:21 -04:00
hal.scheduler->register_timer_failsafe(NULL,1);
// disable the mavlink delay callback
hal.scheduler->register_delay_callback(NULL, 5);
cliSerial = port;
Menu::set_port(port);
port->set_blocking_writes(true);
while (1) {
main_menu.run();
}
}
#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);
2012-08-21 23:19:51 -03:00
// GPS serial port.
//
// standard gps running
2012-12-04 18:22:21 -04:00
hal.uartB->begin(38400, 256, 16);
cliSerial->printf_P(PSTR("\n\nInit " THISFIRMWARE
2012-08-21 23:19:51 -03:00
"\n\nFree RAM: %u\n"),
memcheck_available_memory());
//
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();
set_control_channels();
// reset the uartA baud rate after parameter load
hal.uartA->begin(map_baudrate(g.serial0_baud, SERIAL0_BAUD));
// 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);
// init baro before we start the GCS, so that the CLI baro test works
barometer.init();
2012-08-21 23:19:51 -03:00
// init the GCS
2012-12-04 18:22:21 -04:00
gcs0.init(hal.uartA);
// 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-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();
// we have a 2nd serial port for telemetry
2012-12-04 18:22:21 -04:00
hal.uartC->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD),
128, SERIAL2_BUFSIZE);
2012-12-04 18:22:21 -04:00
gcs3.init(hal.uartC);
2012-08-21 23:19:51 -03:00
mavlink_system.sysid = g.sysid_this_mav;
2011-12-21 08:29:22 -04:00
#if LOGGING_ENABLED == ENABLED
2012-12-08 00:46:10 -04:00
DataFlash.Init();
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);
} else if (DataFlash.NeedErase()) {
gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS"));
2012-08-21 23:19:51 -03:00
do_erase_logs();
2012-12-04 18:22:21 -04:00
gcs0.reset_cli_timeout();
2012-08-21 23:19:51 -03:00
}
if (g.log_bitmask != 0) {
2013-04-19 10:37:21 -03:00
start_logging();
}
2011-12-21 08:29:22 -04:00
#endif
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
apm1_adc.Init(); // APM ADC library initialization
#endif
2011-11-12 22:47:54 -04:00
// initialise airspeed sensor
airspeed.init();
2012-08-21 23:19:51 -03:00
if (g.compass_enabled==true) {
if (!compass.init() || !compass.read()) {
cliSerial->println_P(PSTR("Compass initialisation failed!"));
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
}
2012-08-21 23:19:51 -03:00
}
2012-08-10 19:57:44 -03:00
// give AHRS the airspeed sensor
ahrs.set_airspeed(&airspeed);
// Do GPS init
g_gps = &g_gps_driver;
// GPS Initialization
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
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;
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
2012-12-04 18:22:21 -04:00
relay.init();
#if FENCE_TRIGGERED_PIN > 0
pinMode(FENCE_TRIGGERED_PIN, OUTPUT);
digitalWrite(FENCE_TRIGGERED_PIN, LOW);
#endif
/*
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.
*/
2012-12-04 18:22:21 -04:00
hal.scheduler->register_timer_failsafe(failsafe_check, 1000);
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
cliSerial->println_P(msg);
if (gcs3.initialised) {
hal.uartC->println_P(msg);
}
startup_ground();
if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
// choose the nav controller
set_nav_controller();
set_mode(MANUAL);
2012-08-21 23:19:51 -03:00
// set the correct flight mode
// ---------------------------
reset_control_switch();
}
//********************************************************************************
//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"));
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
2012-08-21 23:19:51 -03:00
// Makes the servos wiggle
// step 1 = 1 wiggle
// -----------------------
if (!g.skip_gyro_cal) {
demo_servos(1);
}
//INS ground start
2012-08-21 23:19:51 -03:00
//------------------------
//
startup_INS_ground(false);
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.
2012-08-21 23:19:51 -03:00
// Save the settings for in-air restart
// ------------------------------------
//save_EEPROM_groundstart();
2012-08-21 23:19:51 -03:00
// initialize commands
// -------------------
init_commands();
2012-08-21 23:19:51 -03:00
// Makes the servos wiggle - 3 times signals ready to fly
// -----------------------
if (!g.skip_gyro_cal) {
demo_servos(3);
}
// reset last heartbeat time, so we don't trigger failsafe on slow
// startup
failsafe.last_heartbeat_ms = millis();
// 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
hal.uartA->set_blocking_writes(false);
2012-12-04 18:22:21 -04:00
hal.uartC->set_blocking_writes(false);
2013-06-11 05:49:03 -03:00
#if 0
// leave GPS blocking until we have support for correct handling
// of GPS config in uBlox when non-blocking
hal.uartB->set_blocking_writes(false);
#endif
2012-08-21 23:19:51 -03:00
gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
}
static void set_mode(enum FlightMode mode)
{
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();
control_mode = mode;
switch(control_mode)
{
case INITIALISING:
case MANUAL:
case STABILIZE:
case TRAINING:
2012-08-21 23:19:51 -03:00
case FLY_BY_WIRE_A:
break;
case ACRO:
acro_state.locked_roll = false;
acro_state.locked_pitch = false;
break;
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:
target_altitude_cm = current_loc.alt;
2012-08-21 23:19:51 -03:00
break;
case CIRCLE:
// the altitude to circle at is taken from the current altitude
next_WP.alt = current_loc.alt;
break;
2012-08-21 23:19:51 -03:00
case AUTO:
prev_WP = current_loc;
2012-08-21 23:19:51 -03:00
update_auto();
break;
case RTL:
prev_WP = current_loc;
2012-08-21 23:19:51 -03:00
do_RTL();
break;
case LOITER:
do_loiter_at_location();
break;
case GUIDED:
guided_throttle_passthru = false;
2012-08-21 23:19:51 -03:00
set_guided_WP();
break;
default:
prev_WP = current_loc;
2012-08-21 23:19:51 -03:00
do_RTL();
break;
}
// 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) {
auto_throttle_mode = true;
throttle_suppressed = true;
} else {
auto_throttle_mode = false;
throttle_suppressed = false;
}
2012-08-21 23:19:51 -03:00
if (g.log_bitmask & MASK_LOG_MODE)
Log_Write_Mode(control_mode);
// reset attitude integrators on mode change
2013-08-14 01:57:41 -03:00
rollController.reset_I();
pitchController.reset_I();
yawController.reset_I();
}
static void check_long_failsafe()
{
uint32_t tnow = millis();
2012-08-21 23:19:51 -03:00
// only act on changes
// -------------------
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);
} else if (!failsafe.rc_override_active &&
failsafe.state == FAILSAFE_SHORT &&
(tnow - failsafe.ch3_timer_ms) > g.long_fs_timeout*1000) {
2012-08-21 23:19:51 -03:00
failsafe_long_on_event(FAILSAFE_LONG);
} else if (g.gcs_heartbeat_fs_enabled &&
failsafe.last_heartbeat_ms != 0 &&
(tnow - failsafe.last_heartbeat_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
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;
}
2012-08-21 23:19:51 -03:00
}
}
static void check_short_failsafe()
{
2012-08-21 23:19:51 -03:00
// only act on changes
// -------------------
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);
}
}
if(failsafe.state == FAILSAFE_SHORT) {
if(!failsafe.ch3_failsafe) {
2012-08-21 23:19:51 -03:00
failsafe_short_off_event();
}
}
}
static void startup_INS_ground(bool do_accel_init)
{
#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
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("Warming up ADC..."));
mavlink_delay(500);
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
// -----------------------
demo_servos(2);
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move plane"));
mavlink_delay(1000);
}
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);
if (do_accel_init) {
2013-09-19 05:33:42 -03:00
ins.init_accel();
ahrs.set_trim(Vector3f(0, 0, 0));
}
ahrs.reset();
2012-08-21 23:19:51 -03:00
// read Baro pressure at ground
//-----------------------------
init_barometer();
if (airspeed.enabled()) {
// initialize airspeed sensor
// --------------------------
zero_airspeed();
} else {
gcs_send_text_P(SEVERITY_LOW,PSTR("NO airspeed"));
}
}
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()
{
2013-08-29 00:13:58 -03:00
notify.update();
}
static void resetPerfData(void) {
2012-08-21 23:19:51 -03:00
mainLoop_count = 0;
G_Dt_max = 0;
ahrs.renorm_range_count = 0;
ahrs.renorm_blowup_count = 0;
gps_fix_count = 0;
perf_mon_timer = millis();
}
/*
2012-08-21 23:19:51 -03:00
* map from a 8 bit EEPROM baud rate to a real baud rate
*/
static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
{
switch (rate) {
case 1: return 1200;
case 2: return 2400;
case 4: return 4800;
case 9: return 9600;
case 19: return 19200;
case 38: return 38400;
case 57: return 57600;
case 111: return 111100;
case 115: return 115200;
}
cliSerial->println_P(PSTR("Invalid SERIAL3_BAUD"));
return default_baud;
}
static void check_usb_mux(void)
{
bool usb_check = hal.gpio->usb_connected();
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
// at SERIAL3_BAUD.
if (usb_connected) {
2012-12-04 18:22:21 -04:00
hal.uartA->begin(SERIAL0_BAUD);
} else {
2012-12-04 18:22:21 -04:00
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD));
}
2013-09-20 20:16:17 -03:00
#endif
}
2012-03-01 00:21:32 -04:00
/*
* Read Vcc vs 1.1v internal reference
*/
uint16_t board_voltage(void)
{
2013-09-12 00:26:27 -03:00
return vcc_pin->voltage_latest() * 1000;
2012-03-01 00:21:32 -04:00
}
static void
print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
{
switch (mode) {
case MANUAL:
port->print_P(PSTR("Manual"));
break;
case CIRCLE:
port->print_P(PSTR("Circle"));
break;
case STABILIZE:
port->print_P(PSTR("Stabilize"));
break;
case TRAINING:
port->print_P(PSTR("Training"));
break;
case ACRO:
port->print_P(PSTR("ACRO"));
break;
case FLY_BY_WIRE_A:
port->print_P(PSTR("FBW_A"));
break;
case FLY_BY_WIRE_B:
port->print_P(PSTR("FBW_B"));
break;
case CRUISE:
port->print_P(PSTR("CRUISE"));
break;
case AUTO:
port->print_P(PSTR("AUTO"));
break;
case RTL:
port->print_P(PSTR("RTL"));
break;
case LOITER:
port->print_P(PSTR("Loiter"));
break;
default:
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
break;
}
}
2012-09-18 00:48:08 -03:00
static void print_comma(void)
{
cliSerial->print_P(PSTR(","));
2012-09-18 00:48:08 -03:00
}
2012-12-04 18:22:21 -04: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) {
RC_Channel::rc_channel(ch)->radio_out = pwm;
}
return;
}
#endif
hal.rcout->enable_ch(ch);
hal.rcout->write(ch, pwm);
}