APM:Libraries
RCOutput.cpp
Go to the documentation of this file.
1 /*
2  simple test of RC output interface
3  */
4 
5 #include <AP_HAL/AP_HAL.h>
6 
7 void setup();
8 void loop();
9 
11 
12 void setup (void)
13 {
14  hal.console->printf("Starting AP_HAL::RCOutput test\n");
15  for (uint8_t i = 0; i< 14; i++) {
16  hal.rcout->enable_ch(i);
17  }
18 }
19 
20 static uint16_t pwm = 1500;
21 static int8_t delta = 1;
22 
23 void loop (void)
24 {
25  for (uint8_t i=0; i < 14; i++) {
26  hal.rcout->write(i, pwm);
27  pwm += delta;
28  if (delta > 0 && pwm >= 2000) {
29  delta = -1;
30  hal.console->printf("reversing\n");
31  } else if (delta < 0 && pwm <= 1000) {
32  delta = 1;
33  hal.console->printf("reversing\n");
34  }
35  }
36  hal.scheduler->delay(5);
37 }
38 
39 AP_HAL_MAIN();
void setup()
Definition: RCOutput.cpp:12
AP_HAL::UARTDriver * console
Definition: HAL.h:110
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCOutput.cpp:10
static uint16_t pwm
Definition: RCOutput.cpp:20
AP_HAL_MAIN()
static int8_t delta
Definition: RCOutput.cpp:21
virtual void delay(uint16_t ms)=0
virtual void enable_ch(uint8_t ch)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual void write(uint8_t ch, uint16_t period_us)=0
const HAL & get_HAL()
void loop()
Definition: RCOutput.cpp:23
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114