APM:Libraries
RC_Channel.cpp
Go to the documentation of this file.
1 /*
2  * Example of RC_Channel library.
3  * Based on original sketch by Jason Short. 2010
4  */
5 
6 #include <AP_HAL/AP_HAL.h>
8 
9 void setup();
10 void loop();
11 
13 
14 #define NUM_CHANNELS 8
15 
17 static RC_Channel *rc;
18 
19 static void print_pwm(void);
20 static void print_radio_values();
21 
22 
23 void setup()
24 {
25  hal.console->printf("ArduPilot RC Channel test\n");
26 
28 
30 
31  // set type of output, symmetrical angles or a number range;
32  rc[CH_1].set_angle(4500);
34 
35  rc[CH_2].set_angle(4500);
37 
38  rc[CH_3].set_range(1000);
40 
41  rc[CH_4].set_angle(6000);
42  rc[CH_4].set_default_dead_zone(500);
43 
44  rc[CH_5].set_range(1000);
45  rc[CH_6].set_range(800);
46 
47  rc[CH_7].set_range(1000);
48 
49  rc[CH_8].set_range(1000);
50 }
51 
52 void loop()
53 {
55  print_pwm();
56 
57  hal.scheduler->delay(20);
58 }
59 
60 static void print_pwm(void)
61 {
62  for (int i=0; i<NUM_CHANNELS; i++) {
63  hal.console->printf("ch%u: %4d ", (unsigned)i+1, (int)rc[i].get_control_in());
64  }
65  hal.console->printf("\n");
66 }
67 
68 
69 static void print_radio_values()
70 {
71  for (int i=0; i<NUM_CHANNELS; i++) {
72  hal.console->printf("CH%u: %u|%u\n",
73  (unsigned)i+1,
74  (unsigned)rc[i].get_radio_min(),
75  (unsigned)rc[i].get_radio_max());
76  }
77 }
78 
79 
80 AP_HAL_MAIN();
#define CH_3
Definition: RCOutput.h:13
static void print_pwm(void)
Definition: RC_Channel.cpp:60
void set_range(uint16_t high)
Definition: RC_Channel.cpp:86
AP_HAL_MAIN()
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define CH_1
Definition: RCOutput.h:11
static RC_Channel * rc_channel(uint8_t chan)
Definition: RC_Channel.h:145
#define CH_6
Definition: RCOutput.h:16
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RC_Channel.cpp:12
static RC_Channels rc_channels
Definition: RC_Channel.cpp:16
#define CH_5
Definition: RCOutput.h:15
void set_angle(uint16_t angle)
Definition: RC_Channel.cpp:93
static RC_Channel * rc
Definition: RC_Channel.cpp:17
#define CH_4
Definition: RCOutput.h:14
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
RC_Channel manager, with EEPROM-backed storage of constants.
Object managing one RC channel.
Definition: RC_Channel.h:15
#define CH_2
Definition: RCOutput.h:12
#define NUM_CHANNELS
Definition: RC_Channel.cpp:14
const HAL & get_HAL()
static bool read_input(void)
static void print_radio_values()
Definition: RC_Channel.cpp:69
void setup()
Definition: RC_Channel.cpp:23
#define CH_8
Definition: RCOutput.h:18
#define CH_7
Definition: RCOutput.h:17
void set_default_dead_zone(int16_t dzone)
Definition: RC_Channel.cpp:100
void loop()
Definition: RC_Channel.cpp:52
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114