CLI: enable "hit enter 3 times" support for CLI

if you hit enter 3 times before you send any mavlink packets, we will
enter CLI mode
This commit is contained in:
Andrew Tridgell 2011-10-27 18:35:25 +11:00
parent 5770be6dc6
commit 5a44298d57
8 changed files with 88 additions and 17 deletions

View File

@ -135,10 +135,14 @@ private:
uint16_t _parameter_count; ///< cache of reportable parameters uint16_t _parameter_count; ///< cache of reportable parameters
AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index
mavlink_channel_t chan; mavlink_channel_t chan;
uint16_t packet_drops; uint16_t packet_drops;
#if CLI_ENABLED == ENABLED
// this allows us to detect the user wanting the CLI to start
uint8_t crlf_count;
#endif
// waypoints // waypoints
uint16_t waypoint_request_i; // request index uint16_t waypoint_request_i; // request index
uint16_t waypoint_dest_sysid; // where to send requests uint16_t waypoint_dest_sysid; // where to send requests
@ -150,7 +154,6 @@ private:
uint32_t waypoint_timelast_receive; // milliseconds uint32_t waypoint_timelast_receive; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds uint16_t waypoint_receive_timeout; // milliseconds
float junk; //used to return a junk value for interface
// data stream rates // data stream rates
AP_Var_group _group; AP_Var_group _group;

View File

@ -8,6 +8,9 @@ static bool in_mavlink_delay;
// messages don't block the CPU // messages don't block the CPU
static mavlink_statustext_t pending_status; static mavlink_statustext_t pending_status;
// true when we have received at least 1 MAVLink packet
static bool mavlink_active;
// check if a message will fit in the payload space available // check if a message will fit in the payload space available
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false #define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
@ -539,8 +542,26 @@ GCS_MAVLINK::update(void)
{ {
uint8_t c = comm_receive_ch(chan); uint8_t c = comm_receive_ch(chan);
#if CLI_ENABLED == ENABLED
/* allow CLI to be started by hitting enter 3 times, if no
heartbeat packets have been received */
if (mavlink_active == false) {
if (c == '\n' || c == '\r') {
crlf_count++;
} else {
crlf_count = 0;
}
if (crlf_count == 3) {
run_cli();
}
}
#endif
// Try to get a new message // Try to get a new message
if(mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg); if (mavlink_parse_char(chan, c, &msg, &status)) {
mavlink_active = true;
handleMessage(&msg);
}
} }
// Update packet drops counter // Update packet drops counter

View File

@ -692,6 +692,11 @@
# define CLI_ENABLED ENABLED # define CLI_ENABLED ENABLED
#endif #endif
// use this to disable the CLI slider switch
#ifndef CLI_SLIDER_ENABLED
# define CLI_SLIDER_ENABLED ENABLED
#endif
// delay to prevent Xbee bricking, in milliseconds // delay to prevent Xbee bricking, in milliseconds
#ifndef MAVLINK_TELEMETRY_PORT_DELAY #ifndef MAVLINK_TELEMETRY_PORT_DELAY
# define MAVLINK_TELEMETRY_PORT_DELAY 2000 # define MAVLINK_TELEMETRY_PORT_DELAY 2000

View File

@ -43,6 +43,14 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
// Create the top-level menu object. // Create the top-level menu object.
MENU(main_menu, THISFIRMWARE, main_menu_commands); MENU(main_menu, THISFIRMWARE, main_menu_commands);
// the user wants the CLI. It never exits
static void run_cli(void)
{
while (1) {
main_menu.run();
}
}
#endif // CLI_ENABLED #endif // CLI_ENABLED
static void init_ardupilot() static void init_ardupilot()
@ -210,7 +218,7 @@ static void init_ardupilot()
DataFlash.Init(); DataFlash.Init();
#endif #endif
#if CLI_ENABLED == ENABLED #if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
// If the switch is in 'menu' mode, run the main menu. // If the switch is in 'menu' mode, run the main menu.
// //
// Since we can't be sure that the setup or test mode won't leave // Since we can't be sure that the setup or test mode won't leave
@ -220,11 +228,10 @@ static void init_ardupilot()
if (check_startup_for_CLI()) { if (check_startup_for_CLI()) {
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
Serial.printf_P(PSTR("\nCLI:\n\n")); Serial.printf_P(PSTR("\nCLI:\n\n"));
for (;;) { run_cli();
//Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
main_menu.run();
}
} }
#else
Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n"));
#endif // CLI_ENABLED #endif // CLI_ENABLED
if(g.esc_calibrate == 1){ if(g.esc_calibrate == 1){

View File

@ -135,10 +135,14 @@ private:
uint16_t _parameter_count; ///< cache of reportable parameters uint16_t _parameter_count; ///< cache of reportable parameters
AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index
mavlink_channel_t chan; mavlink_channel_t chan;
uint16_t packet_drops; uint16_t packet_drops;
#if CLI_ENABLED == ENABLED
// this allows us to detect the user wanting the CLI to start
uint8_t crlf_count;
#endif
// waypoints // waypoints
uint16_t waypoint_request_i; // request index uint16_t waypoint_request_i; // request index
uint16_t waypoint_dest_sysid; // where to send requests uint16_t waypoint_dest_sysid; // where to send requests
@ -150,7 +154,6 @@ private:
uint32_t waypoint_timelast_receive; // milliseconds uint32_t waypoint_timelast_receive; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds uint16_t waypoint_receive_timeout; // milliseconds
float junk; //used to return a junk value for interface
// data stream rates // data stream rates
AP_Var_group _group; AP_Var_group _group;

View File

@ -9,6 +9,8 @@ static bool in_mavlink_delay;
// messages don't block the CPU // messages don't block the CPU
static mavlink_statustext_t pending_status; static mavlink_statustext_t pending_status;
// true when we have received at least 1 MAVLink packet
static bool mavlink_active;
// check if a message will fit in the payload space available // check if a message will fit in the payload space available
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false #define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
@ -805,8 +807,26 @@ GCS_MAVLINK::update(void)
{ {
uint8_t c = comm_receive_ch(chan); uint8_t c = comm_receive_ch(chan);
#if CLI_ENABLED == ENABLED
/* allow CLI to be started by hitting enter 3 times, if no
heartbeat packets have been received */
if (mavlink_active == 0) {
if (c == '\n' || c == '\r') {
crlf_count++;
} else {
crlf_count = 0;
}
if (crlf_count == 3) {
run_cli();
}
}
#endif
// Try to get a new message // Try to get a new message
if (mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg); if (mavlink_parse_char(chan, c, &msg, &status)) {
mavlink_active = 1;
handleMessage(&msg);
}
} }
// Update packet drops counter // Update packet drops counter

View File

@ -662,6 +662,11 @@
# define CLI_ENABLED ENABLED # define CLI_ENABLED ENABLED
#endif #endif
// use this to disable the CLI slider switch
#ifndef CLI_SLIDER_ENABLED
# define CLI_SLIDER_ENABLED ENABLED
#endif
// delay to prevent Xbee bricking, in milliseconds // delay to prevent Xbee bricking, in milliseconds
#ifndef MAVLINK_TELEMETRY_PORT_DELAY #ifndef MAVLINK_TELEMETRY_PORT_DELAY
# define MAVLINK_TELEMETRY_PORT_DELAY 2000 # define MAVLINK_TELEMETRY_PORT_DELAY 2000

View File

@ -43,6 +43,14 @@ static const struct Menu::command main_menu_commands[] PROGMEM = {
// Create the top-level menu object. // Create the top-level menu object.
MENU(main_menu, THISFIRMWARE, main_menu_commands); MENU(main_menu, THISFIRMWARE, main_menu_commands);
// the user wants the CLI. It never exits
static void run_cli(void)
{
while (1) {
main_menu.run();
}
}
#endif // CLI_ENABLED #endif // CLI_ENABLED
static void init_ardupilot() static void init_ardupilot()
@ -185,7 +193,7 @@ static void init_ardupilot()
// the system in an odd state, we don't let the user exit the top // the system in an odd state, we don't let the user exit the top
// menu; they must reset in order to fly. // menu; they must reset in order to fly.
// //
#if CLI_ENABLED == ENABLED #if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
if (digitalRead(SLIDE_SWITCH_PIN) == 0) { if (digitalRead(SLIDE_SWITCH_PIN) == 0) {
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
Serial.printf_P(PSTR("\n" Serial.printf_P(PSTR("\n"
@ -194,14 +202,13 @@ static void init_ardupilot()
"If using the Arduino Serial Monitor, ensure Line Ending is set to Carriage Return.\n" "If using the Arduino Serial Monitor, ensure Line Ending is set to Carriage Return.\n"
"Type 'help' to list commands, 'exit' to leave a submenu.\n" "Type 'help' to list commands, 'exit' to leave a submenu.\n"
"Visit the 'setup' menu for first-time configuration.\n")); "Visit the 'setup' menu for first-time configuration.\n"));
for (;;) { Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n")); run_cli();
main_menu.run();
}
} }
#else
Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n"));
#endif // CLI_ENABLED #endif // CLI_ENABLED
if(g.log_bitmask != 0){ if(g.log_bitmask != 0){
// TODO - Here we will check on the length of the last log // TODO - Here we will check on the length of the last log
// We don't want to create a bunch of little logs due to powering on and off // We don't want to create a bunch of little logs due to powering on and off