Copter: added CLI_ENABLED option

This commit is contained in:
Andrew Tridgell 2015-03-09 14:18:16 +11:00
parent 16cdf64d63
commit 3f906f6bd1
4 changed files with 23 additions and 8 deletions

View File

@ -1655,7 +1655,7 @@ static void gcs_check_input(void)
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
#if CLI_ENABLED == ENABLED
gcs[i].update(run_cli);
gcs[i].update(g.cli_enabled==1?run_cli:NULL);
#else
gcs[i].update(NULL);
#endif

View File

@ -127,6 +127,7 @@ public:
k_param_optflow,
k_param_dcmcheck_thresh, // 59
k_param_log_bitmask,
k_param_cli_enabled,
// 65: AP_Limits Library
k_param_limits = 65, // deprecated - remove
@ -330,6 +331,9 @@ public:
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
AP_Int8 telem_delay;
#if CLI_ENABLED == ENABLED
AP_Int8 cli_enabled;
#endif
AP_Int16 rtl_altitude;
AP_Float sonar_gain;

View File

@ -53,6 +53,15 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
#if CLI_ENABLED == ENABLED
// @Param: CLI_ENABLED
// @DisplayName: CLI Enable
// @Description: This enables/disables the checking for three carriage returns on telemetry links on startup to enter the diagnostics command line interface
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(cli_enabled, "CLI_ENABLED", 0),
#endif
// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),

View File

@ -219,13 +219,15 @@ static void init_ardupilot()
#endif
#if CLI_ENABLED == 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);
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);
}
}
#endif // CLI_ENABLED