|
|
|
@ -8,12 +8,13 @@ static int8_t setup_show (uint8_t argc, const Menu::arg *argv);
@@ -8,12 +8,13 @@ static int8_t setup_show (uint8_t argc, const Menu::arg *argv);
|
|
|
|
|
static int8_t setup_factory (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_flightmodes (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
#if !defined( __AVR_ATmega1280__ ) |
|
|
|
|
static int8_t setup_accel_scale (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_accel_scale (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
#endif |
|
|
|
|
static int8_t setup_level (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_erase (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_compass (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_batt_monitor (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_compass (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
static int8_t setup_batt_monitor (uint8_t argc, const Menu::arg *argv); |
|
|
|
|
|
|
|
|
|
// Command/function table for the setup menu |
|
|
|
|
static const struct Menu::command setup_menu_commands[] PROGMEM = { |
|
|
|
@ -22,6 +23,7 @@ static const struct Menu::command setup_menu_commands[] PROGMEM = {
@@ -22,6 +23,7 @@ static const struct Menu::command setup_menu_commands[] PROGMEM = {
|
|
|
|
|
{"reset", setup_factory}, |
|
|
|
|
{"radio", setup_radio}, |
|
|
|
|
{"modes", setup_flightmodes}, |
|
|
|
|
{"level", setup_level}, |
|
|
|
|
#if !defined( __AVR_ATmega1280__ ) |
|
|
|
|
{"accel", setup_accel_scale}, |
|
|
|
|
#endif |
|
|
|
@ -311,6 +313,19 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv)
@@ -311,6 +313,19 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
static int8_t |
|
|
|
|
setup_level(uint8_t argc, const Menu::arg *argv) |
|
|
|
|
{ |
|
|
|
|
cliSerial->println_P(PSTR("Initialising gyros")); |
|
|
|
|
ahrs.init(); |
|
|
|
|
ins.init(AP_InertialSensor::COLD_START, |
|
|
|
|
ins_sample_rate, |
|
|
|
|
flash_leds); |
|
|
|
|
ins.init_accel(flash_leds); |
|
|
|
|
ahrs.set_trim(Vector3f(0, 0, 0)); |
|
|
|
|
return(0); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static int8_t |
|
|
|
|
setup_compass(uint8_t argc, const Menu::arg *argv) |
|
|
|
|
{ |
|
|
|
|