CLI: fixed accel setup

disable mavlink callback in CLI
This commit is contained in:
Andrew Tridgell 2012-12-24 08:51:33 +11:00
parent 091c14a33e
commit cf8e648558
3 changed files with 9 additions and 0 deletions

View File

@ -51,6 +51,9 @@ static void run_cli(AP_HAL::UARTDriver *port)
// disable the failsafe code in the CLI
hal.scheduler->register_timer_failsafe(NULL,1);
// disable the mavlink delay callback
hal.scheduler->register_delay_callback(NULL, 5);
cliSerial = port;
Menu::set_port(port);
port->set_blocking_writes(true);

View File

@ -54,6 +54,9 @@ static void run_cli(AP_HAL::UARTDriver *port)
Menu::set_port(port);
port->set_blocking_writes(true);
// disable the mavlink delay callback
hal.scheduler->register_delay_callback(NULL, 5);
while (1) {
main_menu.run();
}

View File

@ -54,6 +54,9 @@ static void run_cli(AP_HAL::UARTDriver *port)
// disable the failsafe code in the CLI
hal.scheduler->register_timer_failsafe(NULL,1);
// disable the mavlink delay callback
hal.scheduler->register_delay_callback(NULL, 5);
cliSerial = port;
Menu::set_port(port);
port->set_blocking_writes(true);