2012-08-23 19:18:32 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <StorageManager/StorageManager.h>
|
|
|
|
#include <AP_Progmem/AP_Progmem.h>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
2012-08-23 19:18:32 -03:00
|
|
|
|
2012-12-11 15:24:27 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
2012-08-23 19:18:32 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
2012-12-11 15:24:27 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
|
|
|
#endif
|
2012-08-23 19:18:32 -03:00
|
|
|
|
2012-11-28 18:52:13 -04:00
|
|
|
AP_HAL::DigitalSource *a_led;
|
|
|
|
AP_HAL::DigitalSource *b_led;
|
|
|
|
AP_HAL::DigitalSource *c_led;
|
|
|
|
|
2012-08-23 19:18:32 -03:00
|
|
|
void loop (void) {
|
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
hal.gpio->write(13, 1);
|
2012-11-28 18:52:13 -04:00
|
|
|
|
|
|
|
a_led->write(1);
|
|
|
|
b_led->write(0);
|
|
|
|
c_led->write(1);
|
|
|
|
|
2012-08-23 19:18:32 -03:00
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
hal.gpio->write(13, 0);
|
2012-11-28 18:52:13 -04:00
|
|
|
|
|
|
|
a_led->write(0);
|
|
|
|
b_led->write(1);
|
|
|
|
c_led->write(0);
|
2012-08-23 19:18:32 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void setup (void) {
|
2014-06-01 20:26:19 -03:00
|
|
|
hal.gpio->pinMode(13, HAL_GPIO_OUTPUT);
|
2012-08-23 19:18:32 -03:00
|
|
|
hal.gpio->write(13, 0);
|
2012-11-28 18:52:13 -04:00
|
|
|
|
|
|
|
a_led = hal.gpio->channel(27);
|
|
|
|
b_led = hal.gpio->channel(26);
|
|
|
|
c_led = hal.gpio->channel(25);
|
|
|
|
|
2014-06-01 20:26:19 -03:00
|
|
|
a_led->mode(HAL_GPIO_OUTPUT);
|
|
|
|
b_led->mode(HAL_GPIO_OUTPUT);
|
|
|
|
c_led->mode(HAL_GPIO_OUTPUT);
|
2012-11-28 18:52:13 -04:00
|
|
|
|
|
|
|
a_led->write(0);
|
|
|
|
b_led->write(0);
|
|
|
|
c_led->write(0);
|
2012-08-23 19:18:32 -03:00
|
|
|
}
|
|
|
|
|
2012-12-03 20:25:11 -04:00
|
|
|
AP_HAL_MAIN();
|