CLI: make it possible to completely disable the CLI

set CLI_ENABLED to DISABLED for no CLI. This saves a lot of memory

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2895 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-07-17 10:34:05 +00:00
parent e6d9a6921a
commit 6b0c938176
4 changed files with 105 additions and 81 deletions

View File

@ -585,3 +585,12 @@
#ifndef ALLOW_RC_OVERRIDE
# define ALLOW_RC_OVERRIDE DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//
// use this to completely disable the CLI
#ifndef CLI_ENABLED
# define CLI_ENABLED ENABLED
#endif

View File

@ -1,5 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#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_motors (uint8_t argc, const Menu::arg *argv);
@ -233,29 +235,6 @@ setup_esc(uint8_t argc, const Menu::arg *argv)
}
}
static void
init_esc()
{
g.esc_calibrate.set_and_save(0);
while(1){
read_radio();
delay(100);
dancing_light();
APM_RC.OutputCh(CH_1, g.rc_3.radio_in);
APM_RC.OutputCh(CH_2, g.rc_3.radio_in);
APM_RC.OutputCh(CH_3, g.rc_3.radio_in);
APM_RC.OutputCh(CH_4, g.rc_3.radio_in);
APM_RC.OutputCh(CH_7, g.rc_3.radio_in);
APM_RC.OutputCh(CH_8, g.rc_3.radio_in);
#if FRAME_CONFIG == OCTA_FRAME
APM_RC.OutputCh(CH_10, g.rc_3.radio_in);
APM_RC.OutputCh(CH_11, g.rc_3.radio_in);
#endif
}
}
static int8_t
setup_motors(uint8_t argc, const Menu::arg *argv)
{
@ -755,26 +734,6 @@ static void report_wp(byte index = 255)
}
}
static void print_wp(struct Location *cmd, byte index)
{
Serial.printf_P(PSTR("command #: %d id:%d op:%d p1:%d p2:%ld p3:%ld p4:%ld \n"),
(int)index,
(int)cmd->id,
(int)cmd->options,
(int)cmd->p1,
cmd->alt,
cmd->lat,
cmd->lng);
}
static void report_gps()
{
Serial.printf_P(PSTR("\nGPS\n"));
print_divider();
print_enabled(GPS_enabled);
print_blanks(2);
}
static void report_sonar()
{
g.sonar_enabled.load();
@ -784,13 +743,6 @@ static void report_sonar()
print_blanks(2);
}
static void report_version()
{
Serial.printf_P(PSTR("FW Version %d\n"),(int)g.format_version.get());
print_divider();
print_blanks(2);
}
static void report_frame()
{
Serial.printf_P(PSTR("Frame\n"));
@ -1018,24 +970,6 @@ print_done()
Serial.printf_P(PSTR("\nSaved Settings\n\n"));
}
static void
print_blanks(int num)
{
while(num > 0){
num--;
Serial.println("");
}
}
static void
print_divider(void)
{
for (int i = 0; i < 40; i++) {
Serial.print("-");
}
Serial.println("");
}
// read at 50Hz
static bool
radio_input_switch(void)
@ -1076,15 +1010,6 @@ static void zero_eeprom(void)
Serial.printf_P(PSTR("done\n"));
}
static void print_enabled(boolean b)
{
if(b)
Serial.printf_P(PSTR("en"));
else
Serial.printf_P(PSTR("dis"));
Serial.printf_P(PSTR("abled\n"));
}
static void
print_accel_offsets(void)
{
@ -1138,3 +1063,84 @@ static int read_num_from_serial() {
return atoi(data);
}
#endif
#endif // CLI_ENABLED
static void
print_blanks(int num)
{
while(num > 0){
num--;
Serial.println("");
}
}
static void
print_divider(void)
{
for (int i = 0; i < 40; i++) {
Serial.print("-");
}
Serial.println("");
}
static void print_enabled(boolean b)
{
if(b)
Serial.printf_P(PSTR("en"));
else
Serial.printf_P(PSTR("dis"));
Serial.printf_P(PSTR("abled\n"));
}
static void
init_esc()
{
g.esc_calibrate.set_and_save(0);
while(1){
read_radio();
delay(100);
dancing_light();
APM_RC.OutputCh(CH_1, g.rc_3.radio_in);
APM_RC.OutputCh(CH_2, g.rc_3.radio_in);
APM_RC.OutputCh(CH_3, g.rc_3.radio_in);
APM_RC.OutputCh(CH_4, g.rc_3.radio_in);
APM_RC.OutputCh(CH_7, g.rc_3.radio_in);
APM_RC.OutputCh(CH_8, g.rc_3.radio_in);
#if FRAME_CONFIG == OCTA_FRAME
APM_RC.OutputCh(CH_10, g.rc_3.radio_in);
APM_RC.OutputCh(CH_11, g.rc_3.radio_in);
#endif
}
}
static void print_wp(struct Location *cmd, byte index)
{
Serial.printf_P(PSTR("command #: %d id:%d op:%d p1:%d p2:%ld p3:%ld p4:%ld \n"),
(int)index,
(int)cmd->id,
(int)cmd->options,
(int)cmd->p1,
cmd->alt,
cmd->lat,
cmd->lng);
}
static void report_gps()
{
Serial.printf_P(PSTR("\nGPS\n"));
print_divider();
print_enabled(GPS_enabled);
print_blanks(2);
}
static void report_version()
{
Serial.printf_P(PSTR("FW Version %d\n"),(int)g.format_version.get());
print_divider();
print_blanks(2);
}

View File

@ -6,6 +6,7 @@ The init_ardupilot function processes everything we need for an in - air restart
*****************************************************************************/
#if CLI_ENABLED == ENABLED
// Functions called from the top-level menu
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
@ -42,6 +43,8 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
// Create the top-level menu object.
MENU(main_menu, "AC 2.0.36 Beta", main_menu_commands);
#endif // CLI_ENABLED
static void init_ardupilot()
{
// Console serial port
@ -217,6 +220,7 @@ static void init_ardupilot()
// DataFlash log initialization
DataFlash.Init();
#if CLI_ENABLED == ENABLED
// 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
@ -234,11 +238,12 @@ static void init_ardupilot()
//Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
main_menu.run();
}
}else{
}
#endif // CLI_ENABLED
if(g.esc_calibrate == 1){
init_esc();
}
}
// Logging:
// --------

View File

@ -1,5 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#if CLI_ENABLED == ENABLED
// These are function definitions so the Menu can be constructed before the functions
// are defined below. Order matters to the compiler.
static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv);
@ -1061,3 +1063,5 @@ static void print_motor_out(){
(motor_out[CH_3] - g.rc_3.radio_min),
(motor_out[CH_4] - g.rc_3.radio_min));
}
#endif // CLI_ENABLED