4 changed files with 61 additions and 54 deletions
@ -1,39 +1,42 @@
@@ -1,39 +1,42 @@
|
||||
/* |
||||
* Example of AC_Notify library . |
||||
* DIYDrones.com |
||||
*/ |
||||
|
||||
#include <AP_Common.h> |
||||
#include <AP_Progmem.h> |
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
||||
#include <AP_Param.h> |
||||
#include <AP_HAL.h> |
||||
#include <AP_HAL_AVR.h> |
||||
#include <AP_Notify.h> // Notify library |
||||
#include <AP_BoardLED.h> // Board LED library |
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; |
||||
|
||||
// create board led object |
||||
AP_BoardLED board_led; |
||||
|
||||
void setup() |
||||
{ |
||||
hal.console->println("AP_Notify library test"); |
||||
|
||||
// initialise the board leds |
||||
board_led.init(); |
||||
|
||||
// turn on initialising notification |
||||
AP_Notify::flags.initialising = true; |
||||
AP_Notify::flags.gps_status = 1; |
||||
AP_Notify::flags.armed = 1; |
||||
AP_Notify::flags.pre_arm_check = 1; |
||||
} |
||||
|
||||
void loop() |
||||
{ |
||||
hal.scheduler->delay(1000); |
||||
} |
||||
|
||||
AP_HAL_MAIN(); |
||||
/* |
||||
* Example of AC_Notify library . |
||||
* DIYDrones.com |
||||
*/ |
||||
|
||||
#include <AP_Common.h> |
||||
#include <AP_Progmem.h> |
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library |
||||
#include <AP_Param.h> |
||||
#include <AP_HAL.h> |
||||
#include <AP_HAL_AVR.h> |
||||
#include <AP_HAL_Linux.h> |
||||
#include <AP_HAL_PX4.h> |
||||
#include <AP_HAL_Empty.h> |
||||
#include <AP_Notify.h> // Notify library |
||||
#include <AP_BoardLED.h> // Board LED library |
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; |
||||
|
||||
// create board led object |
||||
AP_BoardLED board_led; |
||||
|
||||
void setup() |
||||
{ |
||||
hal.console->println("AP_Notify library test"); |
||||
|
||||
// initialise the board leds |
||||
board_led.init(); |
||||
|
||||
// turn on initialising notification |
||||
AP_Notify::flags.initialising = true; |
||||
AP_Notify::flags.gps_status = 1; |
||||
AP_Notify::flags.armed = 1; |
||||
AP_Notify::flags.pre_arm_check = 1; |
||||
} |
||||
|
||||
void loop() |
||||
{ |
||||
hal.scheduler->delay(1000); |
||||
} |
||||
|
||||
AP_HAL_MAIN(); |
||||
|
Loading…
Reference in new issue