Rover: updates for new notify API

This commit is contained in:
Andrew Tridgell 2013-08-29 13:14:16 +10:00
parent 25d517f5d6
commit 1646b9c815
3 changed files with 8 additions and 20 deletions

View File

@ -97,9 +97,6 @@
#include "compat.h"
#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
// Configuration
#include "config.h"
@ -343,15 +340,8 @@ static struct {
uint8_t triggered;
} failsafe;
////////////////////////////////////////////////////////////////////////////////
// LED output
////////////////////////////////////////////////////////////////////////////////
static AP_BoardLED board_led;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static ToshibaLED_PX4 toshiba_led;
#else
static ToshibaLED toshiba_led;
#endif
// notify object
static AP_Notify notify;
////////////////////////////////////////////////////////////////////////////////
// GPS variables
@ -588,7 +578,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ mount_update, 1, 500 },
{ failsafe_check, 5, 500 },
{ compass_accumulate, 1, 900 },
{ update_toshiba_led, 1, 100 },
{ update_notify, 1, 100 },
{ one_second_loop, 50, 3000 }
};
@ -604,13 +594,10 @@ void setup() {
AP_Param::setup_sketch_defaults();
// arduplane does not use arming nor pre-arm checks
notify.init();
AP_Notify::flags.armed = true;
AP_Notify::flags.pre_arm_check = true;
// initialise board and toshiba led
board_led.init();
toshiba_led.init();
rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
vcc_pin = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
batt_volt_pin = hal.analogin->channel(g.battery_volt_pin);

View File

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

View File

@ -408,11 +408,11 @@ static void startup_INS_ground(bool force_accel_level)
digitalWrite(C_LED_PIN, LED_OFF);
}
// update_toshiba_led - updates the status of the toshiba led
// updates the notify state
// should be called at 50hz
static void update_toshiba_led()
static void update_notify()
{
AP_Notify::update();
notify.update();
}
static void resetPerfData(void) {