Browse Source

Copter: updates for new notify API

master
Andrew Tridgell 12 years ago
parent
commit
25d517f5d6
  1. 22
      ArduCopter/ArduCopter.pde
  2. 1
      ArduCopter/GCS_Mavlink.pde
  3. 8
      ArduCopter/leds.pde

22
ArduCopter/ArduCopter.pde

@ -105,9 +105,6 @@ @@ -105,9 +105,6 @@
#include <AP_Scheduler.h> // main loop scheduler
#include <AP_RCMapper.h> // RC input mapping library
#include <AP_Notify.h> // Notify library
#include <AP_BoardLED.h> // BoardLEDs library
#include <ToshibaLED.h> // ToshibaLED library
#include <ToshibaLED_PX4.h> // ToshibaLED library for PX4
// AP_HAL to Arduino compatibility layer
#include "compat.h"
@ -147,15 +144,9 @@ static Parameters g; @@ -147,15 +144,9 @@ static Parameters g;
// main loop scheduler
static AP_Scheduler scheduler;
// AP_BoardLED instance
static AP_BoardLED board_led;
// AP_Notify instance
static AP_Notify notify;
// Toshiba LED instance
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static ToshibaLED_PX4 toshiba_led;
#else
static ToshibaLED toshiba_led;
#endif
////////////////////////////////////////////////////////////////////////////////
@ -881,7 +872,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { @@ -881,7 +872,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ compass_accumulate, 2, 700 },
{ barometer_accumulate, 2, 900 },
{ super_slow_loop, 100, 1100 },
{ update_toshiba_led, 2, 100 },
{ update_notify, 2, 100 },
{ perf_update, 1000, 500 }
};
@ -895,11 +886,8 @@ void setup() { @@ -895,11 +886,8 @@ void setup() {
// Load the default values of variables listed in var_info[]s
AP_Param::setup_sketch_defaults();
// initialise board leds
board_led.init();
// initialise toshiba led
toshiba_led.init();
// initialise notify system
notify.init();
#if CONFIG_SONAR == ENABLED
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC

1
ArduCopter/GCS_Mavlink.pde

@ -2161,6 +2161,7 @@ static void mavlink_delay_cb() @@ -2161,6 +2161,7 @@ static void mavlink_delay_cb()
gcs_check_input();
gcs_data_stream_send();
gcs_send_deferred();
notify.update();
}
if (tnow - last_5s > 5000) {
last_5s = tnow;

8
ArduCopter/leds.pde

@ -1,10 +1,10 @@ @@ -1,10 +1,10 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// update_toshiba_led - updates the status of the toshiba led
// should be called at 50hz ~ 100hz
static void update_toshiba_led()
// updates the status of notify
// should be called at 50hz
static void update_notify()
{
AP_Notify::update();
notify.update();
}
/////////////////////////////////////////////////////////////////////////////////////////////

Loading…
Cancel
Save