Copter: alphabetise order of cli setup menu

This commit is contained in:
Randy Mackay 2013-05-31 14:56:08 +09:00
parent a0c8bf238e
commit e2495b7a49
1 changed files with 376 additions and 385 deletions

View File

@ -3,54 +3,54 @@
#if CLI_ENABLED == ENABLED
// Functions called from the setup menu
static int8_t setup_radio (uint8_t argc, const Menu::arg *argv);
static int8_t setup_accel (uint8_t argc, const Menu::arg *argv);
static int8_t setup_accel_scale (uint8_t argc, const Menu::arg *argv);
static int8_t setup_frame (uint8_t argc, const Menu::arg *argv);
static int8_t setup_factory (uint8_t argc, const Menu::arg *argv);
static int8_t setup_erase (uint8_t argc, const Menu::arg *argv);
static int8_t setup_flightmodes (uint8_t argc, const Menu::arg *argv);
static int8_t setup_batt_monitor (uint8_t argc, const Menu::arg *argv);
static int8_t setup_sonar (uint8_t argc, const Menu::arg *argv);
static int8_t setup_compass (uint8_t argc, const Menu::arg *argv);
static int8_t setup_compassmot (uint8_t argc, const Menu::arg *argv);
static int8_t setup_tune (uint8_t argc, const Menu::arg *argv);
static int8_t setup_range (uint8_t argc, const Menu::arg *argv);
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv);
static int8_t setup_optflow (uint8_t argc, const Menu::arg *argv);
static int8_t setup_erase (uint8_t argc, const Menu::arg *argv);
static int8_t setup_frame (uint8_t argc, const Menu::arg *argv);
#if FRAME_CONFIG == HELI_FRAME
static int8_t setup_heli (uint8_t argc, const Menu::arg *argv);
static int8_t setup_gyro (uint8_t argc, const Menu::arg *argv);
static int8_t setup_heli (uint8_t argc, const Menu::arg *argv);
#endif
static int8_t setup_accel (uint8_t argc, const Menu::arg *argv);
static int8_t setup_flightmodes (uint8_t argc, const Menu::arg *argv);
static int8_t setup_optflow (uint8_t argc, const Menu::arg *argv);
static int8_t setup_radio (uint8_t argc, const Menu::arg *argv);
static int8_t setup_range (uint8_t argc, const Menu::arg *argv);
static int8_t setup_factory (uint8_t argc, const Menu::arg *argv);
static int8_t setup_set (uint8_t argc, const Menu::arg *argv);
static int8_t setup_show (uint8_t argc, const Menu::arg *argv);
static int8_t setup_sonar (uint8_t argc, const Menu::arg *argv);
static int8_t setup_tune (uint8_t argc, const Menu::arg *argv);
// Command/function table for the setup menu
const struct Menu::command setup_menu_commands[] PROGMEM = {
// command function called
// ======= ===============
{"erase", setup_erase},
{"reset", setup_factory},
{"radio", setup_radio},
{"frame", setup_frame},
{"level", setup_accel},
{"accel", setup_accel_scale},
{"modes", setup_flightmodes},
{"battery", setup_batt_monitor},
{"sonar", setup_sonar},
{"compass", setup_compass},
{"compassmot", setup_compassmot},
{"tune", setup_tune},
{"range", setup_range},
{"declination", setup_declination},
{"optflow", setup_optflow},
{"declination", setup_declination},
{"erase", setup_erase},
{"frame", setup_frame},
#if FRAME_CONFIG == HELI_FRAME
{"heli", setup_heli},
{"gyro", setup_gyro},
{"heli", setup_heli},
#endif
{"level", setup_accel},
{"modes", setup_flightmodes},
{"optflow", setup_optflow},
{"radio", setup_radio},
{"range", setup_range},
{"reset", setup_factory},
{"set", setup_set},
{"show", setup_show},
{"set", setup_set}
{"sonar", setup_sonar},
{"tune", setup_tune}
};
// Create the setup menu object.
@ -75,179 +75,6 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
return 0;
}
// Print the current configuration.
// Called by the setup menu 'show' command.
static int8_t
setup_show(uint8_t argc, const Menu::arg *argv)
{
AP_Param *param;
ap_var_type type;
//If a parameter name is given as an argument to show, print only that parameter
if(argc>=2)
{
param=AP_Param::find(argv[1].str, &type);
if(!param)
{
cliSerial->printf_P(PSTR("Parameter not found: '%s'\n"), argv[1]);
return 0;
}
AP_Param::show(param, argv[1].str, type, cliSerial);
return 0;
}
// clear the area
print_blanks(8);
report_version();
report_radio();
report_frame();
report_batt_monitor();
report_sonar();
report_flight_modes();
report_ins();
report_compass();
report_optflow();
#if FRAME_CONFIG == HELI_FRAME
report_heli();
report_gyro();
#endif
AP_Param::show_all(cliSerial);
return(0);
}
// Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults).
// Called by the setup menu 'factoryreset' command.
static int8_t
setup_factory(uint8_t argc, const Menu::arg *argv)
{
int16_t c;
cliSerial->printf_P(PSTR("\n'Y' = factory reset, any other key to abort:\n"));
do {
c = cliSerial->read();
} while (-1 == c);
if (('y' != c) && ('Y' != c))
return(-1);
AP_Param::erase_all();
cliSerial->printf_P(PSTR("\nReboot APM"));
delay(1000);
for (;; ) {
}
// note, cannot actually return here
return(0);
}
// Perform radio setup.
// Called by the setup menu 'radio' command.
static int8_t
setup_radio(uint8_t argc, const Menu::arg *argv)
{
cliSerial->println_P(PSTR("\n\nRadio Setup:"));
uint8_t i;
for(i = 0; i < 100; i++) {
delay(20);
read_radio();
}
if(g.rc_1.radio_in < 500) {
while(1) {
//cliSerial->printf_P(PSTR("\nNo radio; Check connectors."));
delay(1000);
// stop here
}
}
g.rc_1.radio_min = g.rc_1.radio_in;
g.rc_2.radio_min = g.rc_2.radio_in;
g.rc_3.radio_min = g.rc_3.radio_in;
g.rc_4.radio_min = g.rc_4.radio_in;
g.rc_5.radio_min = g.rc_5.radio_in;
g.rc_6.radio_min = g.rc_6.radio_in;
g.rc_7.radio_min = g.rc_7.radio_in;
g.rc_8.radio_min = g.rc_8.radio_in;
g.rc_1.radio_max = g.rc_1.radio_in;
g.rc_2.radio_max = g.rc_2.radio_in;
g.rc_3.radio_max = g.rc_3.radio_in;
g.rc_4.radio_max = g.rc_4.radio_in;
g.rc_5.radio_max = g.rc_5.radio_in;
g.rc_6.radio_max = g.rc_6.radio_in;
g.rc_7.radio_max = g.rc_7.radio_in;
g.rc_8.radio_max = g.rc_8.radio_in;
g.rc_1.radio_trim = g.rc_1.radio_in;
g.rc_2.radio_trim = g.rc_2.radio_in;
g.rc_4.radio_trim = g.rc_4.radio_in;
// 3 is not trimed
g.rc_5.radio_trim = 1500;
g.rc_6.radio_trim = 1500;
g.rc_7.radio_trim = 1500;
g.rc_8.radio_trim = 1500;
cliSerial->printf_P(PSTR("\nMove all controls to extremes. Enter to save: "));
while(1) {
delay(20);
// Filters radio input - adjust filters in the radio.pde file
// ----------------------------------------------------------
read_radio();
g.rc_1.update_min_max();
g.rc_2.update_min_max();
g.rc_3.update_min_max();
g.rc_4.update_min_max();
g.rc_5.update_min_max();
g.rc_6.update_min_max();
g.rc_7.update_min_max();
g.rc_8.update_min_max();
if(cliSerial->available() > 0) {
delay(20);
while (cliSerial->read() != -1); /* flush */
g.rc_1.save_eeprom();
g.rc_2.save_eeprom();
g.rc_3.save_eeprom();
g.rc_4.save_eeprom();
g.rc_5.save_eeprom();
g.rc_6.save_eeprom();
g.rc_7.save_eeprom();
g.rc_8.save_eeprom();
print_done();
break;
}
}
report_radio();
return(0);
}
static int8_t
setup_accel(uint8_t argc, const Menu::arg *argv)
{
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)); // clear out saved trim
report_ins();
return(0);
}
static int8_t
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
{
@ -268,131 +95,19 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv)
}
static int8_t
setup_frame(uint8_t argc, const Menu::arg *argv)
setup_batt_monitor(uint8_t argc, const Menu::arg *argv)
{
if (!strcmp_P(argv[1].str, PSTR("x"))) {
g.frame_orientation.set_and_save(X_FRAME);
} else if (!strcmp_P(argv[1].str, PSTR("p"))) {
g.frame_orientation.set_and_save(PLUS_FRAME);
} else if (!strcmp_P(argv[1].str, PSTR("+"))) {
g.frame_orientation.set_and_save(PLUS_FRAME);
} else if (!strcmp_P(argv[1].str, PSTR("v"))) {
g.frame_orientation.set_and_save(V_FRAME);
}else{
cliSerial->printf_P(PSTR("\nOp:[x,+,v]\n"));
report_frame();
return 0;
if (!strcmp_P(argv[1].str, PSTR("off"))) {
g.battery_monitoring.set_and_save(0);
} else if(argv[1].i > 0 && argv[1].i <= 4) {
g.battery_monitoring.set_and_save(argv[1].i);
} else {
cliSerial->printf_P(PSTR("\nOp: off, 3-4"));
}
report_frame();
return 0;
}
static int8_t
setup_flightmodes(uint8_t argc, const Menu::arg *argv)
{
uint8_t _switchPosition = 0;
uint8_t _oldSwitchPosition = 0;
int8_t mode = 0;
cliSerial->printf_P(PSTR("\nMode switch to edit, aileron: select modes, rudder: Simple on/off\n"));
print_hit_enter();
while(1) {
delay(20);
read_radio();
_switchPosition = readSwitch();
// look for control switch change
if (_oldSwitchPosition != _switchPosition) {
mode = flight_modes[_switchPosition];
mode = constrain_int16(mode, 0, NUM_MODES-1);
// update the user
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
// Remember switch position
_oldSwitchPosition = _switchPosition;
}
// look for stick input
if (abs(g.rc_1.control_in) > 3000) {
mode++;
if(mode >= NUM_MODES)
mode = 0;
// save new mode
flight_modes[_switchPosition] = mode;
// print new mode
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
delay(500);
}
// look for stick input
if (g.rc_4.control_in > 3000) {
g.simple_modes |= (1<<_switchPosition);
// print new mode
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
delay(500);
}
// look for stick input
if (g.rc_4.control_in < -3000) {
g.simple_modes &= ~(1<<_switchPosition);
// print new mode
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
delay(500);
}
// escape hatch
if(cliSerial->available() > 0) {
for (mode = 0; mode < 6; mode++)
flight_modes[mode].save();
g.simple_modes.save();
print_done();
report_flight_modes();
return (0);
}
}
}
static int8_t
setup_declination(uint8_t argc, const Menu::arg *argv)
{
compass.set_declination(radians(argv[1].f));
report_compass();
return 0;
}
static int8_t
setup_tune(uint8_t argc, const Menu::arg *argv)
{
g.radio_tuning.set_and_save(argv[1].i);
report_tuning();
return 0;
}
static int8_t
setup_range(uint8_t argc, const Menu::arg *argv)
{
cliSerial->printf_P(PSTR("\nCH 6 Ranges are divided by 1000: [low, high]\n"));
g.radio_tuning_low.set_and_save(argv[1].i);
g.radio_tuning_high.set_and_save(argv[2].i);
report_tuning();
return 0;
}
static int8_t
setup_erase(uint8_t argc, const Menu::arg *argv)
{
zero_eeprom();
report_batt_monitor();
return 0;
}
@ -404,7 +119,9 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
init_compass();
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
clear_offsets();
Vector3f mag_offsets(0,0,0);
compass.set_offsets(mag_offsets);
compass.save_offsets();
g.compass_enabled.set_and_save(false);
}else{
@ -656,46 +373,71 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv)
}
static int8_t
setup_batt_monitor(uint8_t argc, const Menu::arg *argv)
setup_declination(uint8_t argc, const Menu::arg *argv)
{
if (!strcmp_P(argv[1].str, PSTR("off"))) {
g.battery_monitoring.set_and_save(0);
} else if(argv[1].i > 0 && argv[1].i <= 4) {
g.battery_monitoring.set_and_save(argv[1].i);
} else {
cliSerial->printf_P(PSTR("\nOp: off, 3-4"));
}
report_batt_monitor();
compass.set_declination(radians(argv[1].f));
report_compass();
return 0;
}
static int8_t
setup_sonar(uint8_t argc, const Menu::arg *argv)
setup_erase(uint8_t argc, const Menu::arg *argv)
{
if (!strcmp_P(argv[1].str, PSTR("on"))) {
g.sonar_enabled.set_and_save(true);
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
g.sonar_enabled.set_and_save(false);
} else if (argc > 1 && (argv[1].i >= 0 && argv[1].i <= 3)) {
g.sonar_enabled.set_and_save(true); // if you set the sonar type, surely you want it on
g.sonar_type.set_and_save(argv[1].i);
}else{
cliSerial->printf_P(PSTR("\nOp:[on, off, 0-3]\n"));
report_sonar();
return 0;
}
report_sonar();
zero_eeprom();
return 0;
}
#if FRAME_CONFIG == HELI_FRAME
static int8_t
setup_frame(uint8_t argc, const Menu::arg *argv)
{
if (!strcmp_P(argv[1].str, PSTR("x"))) {
g.frame_orientation.set_and_save(X_FRAME);
} else if (!strcmp_P(argv[1].str, PSTR("p"))) {
g.frame_orientation.set_and_save(PLUS_FRAME);
} else if (!strcmp_P(argv[1].str, PSTR("+"))) {
g.frame_orientation.set_and_save(PLUS_FRAME);
} else if (!strcmp_P(argv[1].str, PSTR("v"))) {
g.frame_orientation.set_and_save(V_FRAME);
}else{
cliSerial->printf_P(PSTR("\nOp:[x,+,v]\n"));
report_frame();
return 0;
}
report_frame();
return 0;
}
#if FRAME_CONFIG == HELI_FRAME
// setup for external tail gyro (for heli only)
static int8_t
setup_gyro(uint8_t argc, const Menu::arg *argv)
{
if (!strcmp_P(argv[1].str, PSTR("on"))) {
motors.ext_gyro_enabled.set_and_save(true);
// optionally capture the gain
if( argc >= 2 && argv[2].i >= 1000 && argv[2].i <= 2000 ) {
motors.ext_gyro_gain = argv[2].i;
motors.ext_gyro_gain.save();
}
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
motors.ext_gyro_enabled.set_and_save(false);
// capture gain if user simply provides a number
} else if( argv[1].i >= 1000 && argv[1].i <= 2000 ) {
motors.ext_gyro_enabled.set_and_save(true);
motors.ext_gyro_gain = argv[1].i;
motors.ext_gyro_gain.save();
}else{
cliSerial->printf_P(PSTR("\nOp:[on, off] gain\n"));
}
report_gyro();
return 0;
}
// Perform heli setup.
// Called by the setup menu 'radio' command.
@ -911,44 +653,91 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
return(0);
}
#endif // FRAME_CONFIG == HELI
// setup for external tail gyro (for heli only)
static int8_t
setup_gyro(uint8_t argc, const Menu::arg *argv)
setup_accel(uint8_t argc, const Menu::arg *argv)
{
if (!strcmp_P(argv[1].str, PSTR("on"))) {
motors.ext_gyro_enabled.set_and_save(true);
// optionally capture the gain
if( argc >= 2 && argv[2].i >= 1000 && argv[2].i <= 2000 ) {
motors.ext_gyro_gain = argv[2].i;
motors.ext_gyro_gain.save();
}
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
motors.ext_gyro_enabled.set_and_save(false);
// capture gain if user simply provides a number
} else if( argv[1].i >= 1000 && argv[1].i <= 2000 ) {
motors.ext_gyro_enabled.set_and_save(true);
motors.ext_gyro_gain = argv[1].i;
motors.ext_gyro_gain.save();
}else{
cliSerial->printf_P(PSTR("\nOp:[on, off] gain\n"));
}
report_gyro();
return 0;
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)); // clear out saved trim
report_ins();
return(0);
}
#endif // FRAME_CONFIG == HELI
static void clear_offsets()
static int8_t
setup_flightmodes(uint8_t argc, const Menu::arg *argv)
{
Vector3f _offsets(0.0,0.0,0.0);
compass.set_offsets(_offsets);
compass.save_offsets();
uint8_t _switchPosition = 0;
uint8_t _oldSwitchPosition = 0;
int8_t mode = 0;
cliSerial->printf_P(PSTR("\nMode switch to edit, aileron: select modes, rudder: Simple on/off\n"));
print_hit_enter();
while(1) {
delay(20);
read_radio();
_switchPosition = readSwitch();
// look for control switch change
if (_oldSwitchPosition != _switchPosition) {
mode = flight_modes[_switchPosition];
mode = constrain_int16(mode, 0, NUM_MODES-1);
// update the user
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
// Remember switch position
_oldSwitchPosition = _switchPosition;
}
// look for stick input
if (abs(g.rc_1.control_in) > 3000) {
mode++;
if(mode >= NUM_MODES)
mode = 0;
// save new mode
flight_modes[_switchPosition] = mode;
// print new mode
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
delay(500);
}
// look for stick input
if (g.rc_4.control_in > 3000) {
g.simple_modes |= (1<<_switchPosition);
// print new mode
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
delay(500);
}
// look for stick input
if (g.rc_4.control_in < -3000) {
g.simple_modes &= ~(1<<_switchPosition);
// print new mode
print_switch(_switchPosition, mode, BIT_IS_SET(g.simple_modes, _switchPosition));
delay(500);
}
// escape hatch
if(cliSerial->available() > 0) {
for (mode = 0; mode < 6; mode++)
flight_modes[mode].save();
g.simple_modes.save();
print_done();
report_flight_modes();
return (0);
}
}
}
static int8_t
@ -974,6 +763,131 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
return 0;
}
// Perform radio setup.
// Called by the setup menu 'radio' command.
static int8_t
setup_radio(uint8_t argc, const Menu::arg *argv)
{
cliSerial->println_P(PSTR("\n\nRadio Setup:"));
uint8_t i;
for(i = 0; i < 100; i++) {
delay(20);
read_radio();
}
if(g.rc_1.radio_in < 500) {
while(1) {
//cliSerial->printf_P(PSTR("\nNo radio; Check connectors."));
delay(1000);
// stop here
}
}
g.rc_1.radio_min = g.rc_1.radio_in;
g.rc_2.radio_min = g.rc_2.radio_in;
g.rc_3.radio_min = g.rc_3.radio_in;
g.rc_4.radio_min = g.rc_4.radio_in;
g.rc_5.radio_min = g.rc_5.radio_in;
g.rc_6.radio_min = g.rc_6.radio_in;
g.rc_7.radio_min = g.rc_7.radio_in;
g.rc_8.radio_min = g.rc_8.radio_in;
g.rc_1.radio_max = g.rc_1.radio_in;
g.rc_2.radio_max = g.rc_2.radio_in;
g.rc_3.radio_max = g.rc_3.radio_in;
g.rc_4.radio_max = g.rc_4.radio_in;
g.rc_5.radio_max = g.rc_5.radio_in;
g.rc_6.radio_max = g.rc_6.radio_in;
g.rc_7.radio_max = g.rc_7.radio_in;
g.rc_8.radio_max = g.rc_8.radio_in;
g.rc_1.radio_trim = g.rc_1.radio_in;
g.rc_2.radio_trim = g.rc_2.radio_in;
g.rc_4.radio_trim = g.rc_4.radio_in;
// 3 is not trimed
g.rc_5.radio_trim = 1500;
g.rc_6.radio_trim = 1500;
g.rc_7.radio_trim = 1500;
g.rc_8.radio_trim = 1500;
cliSerial->printf_P(PSTR("\nMove all controls to extremes. Enter to save: "));
while(1) {
delay(20);
// Filters radio input - adjust filters in the radio.pde file
// ----------------------------------------------------------
read_radio();
g.rc_1.update_min_max();
g.rc_2.update_min_max();
g.rc_3.update_min_max();
g.rc_4.update_min_max();
g.rc_5.update_min_max();
g.rc_6.update_min_max();
g.rc_7.update_min_max();
g.rc_8.update_min_max();
if(cliSerial->available() > 0) {
delay(20);
while (cliSerial->read() != -1); /* flush */
g.rc_1.save_eeprom();
g.rc_2.save_eeprom();
g.rc_3.save_eeprom();
g.rc_4.save_eeprom();
g.rc_5.save_eeprom();
g.rc_6.save_eeprom();
g.rc_7.save_eeprom();
g.rc_8.save_eeprom();
print_done();
break;
}
}
report_radio();
return(0);
}
static int8_t
setup_range(uint8_t argc, const Menu::arg *argv)
{
cliSerial->printf_P(PSTR("\nCH 6 Ranges are divided by 1000: [low, high]\n"));
g.radio_tuning_low.set_and_save(argv[1].i);
g.radio_tuning_high.set_and_save(argv[2].i);
report_tuning();
return 0;
}
// Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults).
// Called by the setup menu 'factoryreset' command.
static int8_t
setup_factory(uint8_t argc, const Menu::arg *argv)
{
int16_t c;
cliSerial->printf_P(PSTR("\n'Y' = factory reset, any other key to abort:\n"));
do {
c = cliSerial->read();
} while (-1 == c);
if (('y' != c) && ('Y' != c))
return(-1);
AP_Param::erase_all();
cliSerial->printf_P(PSTR("\nReboot APM"));
delay(1000);
for (;; ) {
}
// note, cannot actually return here
return(0);
}
//Set a parameter to a specified value. It will cast the value to the current type of the
//parameter and make sure it fits in case of INT8 and INT16
static int8_t setup_set(uint8_t argc, const Menu::arg *argv)
@ -1033,6 +947,83 @@ static int8_t setup_set(uint8_t argc, const Menu::arg *argv)
return 0;
}
// Print the current configuration.
// Called by the setup menu 'show' command.
static int8_t
setup_show(uint8_t argc, const Menu::arg *argv)
{
AP_Param *param;
ap_var_type type;
//If a parameter name is given as an argument to show, print only that parameter
if(argc>=2)
{
param=AP_Param::find(argv[1].str, &type);
if(!param)
{
cliSerial->printf_P(PSTR("Parameter not found: '%s'\n"), argv[1]);
return 0;
}
AP_Param::show(param, argv[1].str, type, cliSerial);
return 0;
}
// clear the area
print_blanks(8);
report_version();
report_radio();
report_frame();
report_batt_monitor();
report_sonar();
report_flight_modes();
report_ins();
report_compass();
report_optflow();
#if FRAME_CONFIG == HELI_FRAME
report_heli();
report_gyro();
#endif
AP_Param::show_all(cliSerial);
return(0);
}
static int8_t
setup_sonar(uint8_t argc, const Menu::arg *argv)
{
if (!strcmp_P(argv[1].str, PSTR("on"))) {
g.sonar_enabled.set_and_save(true);
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
g.sonar_enabled.set_and_save(false);
} else if (argc > 1 && (argv[1].i >= 0 && argv[1].i <= 3)) {
g.sonar_enabled.set_and_save(true); // if you set the sonar type, surely you want it on
g.sonar_type.set_and_save(argv[1].i);
}else{
cliSerial->printf_P(PSTR("\nOp:[on, off, 0-3]\n"));
report_sonar();
return 0;
}
report_sonar();
return 0;
}
static int8_t
setup_tune(uint8_t argc, const Menu::arg *argv)
{
g.radio_tuning.set_and_save(argv[1].i);
report_tuning();
return 0;
}
/***************************************************************************/
// CLI reports
/***************************************************************************/