diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index b72677a7a0..ccdf5dc179 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -935,6 +935,9 @@ AP_Relay relay; static bool usb_connected; #endif +#if CLI_ENABLED == ENABLED + static int8_t setup_show (uint8_t argc, const Menu::arg *argv); +#enduf // Camera/Antenna mount tracking and stabilisation stuff // -------------------------------------- diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index d981e4be08..bfe5d84f11 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -963,6 +963,10 @@ static void Log_Read(int16_t start_page, int16_t end_page) Serial.printf_P(PSTR("APM 1\n")); #endif +#if CLI_ENABLED == ENABLED + setup_show(NULL, NULL); +#enduf + if(start_page > end_page) { packet_count = Log_Read_Process(start_page, DataFlash.df_NumPages); packet_count += Log_Read_Process(1, end_page); diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 72fb0b77d6..bea23bac47 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -19,7 +19,7 @@ static int8_t setup_range (uint8_t argc, const Men //static int8_t setup_mag_offset (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_show (uint8_t argc, const Menu::arg *argv); + #if FRAME_CONFIG == HELI_FRAME static int8_t setup_heli (uint8_t argc, const Menu::arg *argv);