Plane: fix startup of CLI menu system

This commit is contained in:
Peter Barker 2017-02-14 23:07:54 +11:00 committed by Tom Pittenger
parent fe93bdbc5e
commit 97145f20fc
4 changed files with 13 additions and 4 deletions

View File

@ -63,6 +63,7 @@ void GCS_Plane::setup_uarts(AP_SerialManager &serial_manager)
} }
} }
#if CLI_ENABLED == ENABLED
void GCS_Plane::handle_interactive_setup() void GCS_Plane::handle_interactive_setup()
{ {
if (plane.g.cli_enabled == 1) { if (plane.g.cli_enabled == 1) {
@ -76,3 +77,4 @@ void GCS_Plane::handle_interactive_setup()
} }
} }
} }
#endif

View File

@ -2,6 +2,7 @@
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#include "GCS_Mavlink.h" #include "GCS_Mavlink.h"
#include "config.h" // for CLI_ENABLED
class GCS_Plane : public GCS class GCS_Plane : public GCS
{ {
@ -26,7 +27,9 @@ public:
void set_run_cli_func(run_cli_fn run_cli) { _run_cli = run_cli; } void set_run_cli_func(run_cli_fn run_cli) { _run_cli = run_cli; }
void setup_uarts(AP_SerialManager &serial_manager); void setup_uarts(AP_SerialManager &serial_manager);
#if CLI_ENABLED == ENABLED
void handle_interactive_setup(); void handle_interactive_setup();
#endif
private: private:

View File

@ -27,10 +27,6 @@ Plane::Plane(void)
auto_state.takeoff_complete = true; auto_state.takeoff_complete = true;
auto_state.next_wp_no_crosstrack = true; auto_state.next_wp_no_crosstrack = true;
auto_state.no_crosstrack = true; auto_state.no_crosstrack = true;
if (plane.g.cli_enabled) {
gcs().set_run_cli_func(FUNCTOR_BIND_MEMBER(&Plane::run_cli, void, AP_HAL::UARTDriver *));
}
} }
Plane plane; Plane plane;

View File

@ -124,6 +124,14 @@ void Plane::init_ardupilot()
serial_manager.init(); serial_manager.init();
gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0); gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
// specify callback function for CLI menu system
#if CLI_ENABLED == ENABLED
if (g.cli_enabled) {
gcs().set_run_cli_func(FUNCTOR_BIND_MEMBER(&Plane::run_cli, void, AP_HAL::UARTDriver *));
}
#endif
// Register mavlink_delay_cb, which will run anytime you have // Register mavlink_delay_cb, which will run anytime you have
// more than 5ms remaining in your call to hal.scheduler->delay // more than 5ms remaining in your call to hal.scheduler->delay
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5); hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);