APM:Libraries
RCOutput.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_Namespace.h"
4 #include <stdint.h>
5 
6 #define RC_OUTPUT_MIN_PULSEWIDTH 400
7 #define RC_OUTPUT_MAX_PULSEWIDTH 2100
8 
9 /* Define the CH_n names, indexed from 1, if we don't have them already */
10 #ifndef CH_1
11 #define CH_1 0
12 #define CH_2 1
13 #define CH_3 2
14 #define CH_4 3
15 #define CH_5 4
16 #define CH_6 5
17 #define CH_7 6
18 #define CH_8 7
19 #define CH_9 8
20 #define CH_10 9
21 #define CH_11 10
22 #define CH_12 11
23 #define CH_13 12
24 #define CH_14 13
25 #define CH_15 14
26 #define CH_16 15
27 #define CH_17 16
28 #define CH_18 17
29 #define CH_NONE 255
30 #endif
31 
32 class ByteBuffer;
33 
35 public:
36  virtual void init() = 0;
37 
38  /* Output freq (1/period) control */
39  virtual void set_freq(uint32_t chmask, uint16_t freq_hz) = 0;
40  virtual uint16_t get_freq(uint8_t ch) = 0;
41 
42  /* Output active/highZ control, either by single channel at a time
43  * or a mask of channels */
44  virtual void enable_ch(uint8_t ch) = 0;
45  virtual void disable_ch(uint8_t ch) = 0;
46 
47  /*
48  * Output a single channel, possibly grouped with previous writes if
49  * cork() has been called before.
50  */
51  virtual void write(uint8_t ch, uint16_t period_us) = 0;
52 
53  /*
54  * Delay subsequent calls to write() going to the underlying hardware in
55  * order to group related writes together. When all the needed writes are
56  * done, call push() to commit the changes.
57  */
58  virtual void cork() = 0;
59 
60  /*
61  * Push pending changes to the underlying hardware. All changes between a
62  * call to cork() and push() are pushed together in a single transaction.
63  */
64  virtual void push() = 0;
65 
66  /* Read back current output state, as either single channel or
67  * array of channels. On boards that have a separate IO controller,
68  * this returns the latest output value that the IO controller has
69  * reported */
70  virtual uint16_t read(uint8_t ch) = 0;
71  virtual void read(uint16_t* period_us, uint8_t len) = 0;
72 
73  /* Read the current input state. This returns the last value that was written. */
74  virtual uint16_t read_last_sent(uint8_t ch) { return read(ch); }
75  virtual void read_last_sent(uint16_t* period_us, uint8_t len) { read(period_us, len); };
76 
77  /*
78  set PWM to send to a set of channels when the safety switch is
79  in the safe state
80  */
81  virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us) {}
82 
83  /*
84  set PWM to send to a set of channels if the FMU firmware dies
85  */
86  virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) {}
87 
88  /*
89  force the safety switch on, disabling PWM output from the IO board
90  return false (indicating failure) by default so that boards with no safety switch
91  do not need to implement this method
92  */
93  virtual bool force_safety_on(void) { return false; }
94 
95  /*
96  force the safety switch off, enabling PWM output from the IO board
97  */
98  virtual void force_safety_off(void) {}
99 
100  /*
101  If we support async sends (px4), this will force it to be serviced immediately
102  */
103  virtual void force_safety_no_wait(void) {}
104 
105  /*
106  setup scaling of ESC output for ESCs that can output a
107  percentage of power (such as UAVCAN ESCs). The values are in
108  microseconds, and represent minimum and maximum PWM values which
109  will be used to convert channel writes into a percentage
110  */
111  virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) {}
112 
113  /*
114  return ESC scaling value from set_esc_scaling()
115  */
116  virtual bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) { return false; }
117 
118  /*
119  returns the pwm value scaled to [-1;1] regrading to set_esc_scaling ranges range without constraints.
120  */
121  virtual float scale_esc_to_unity(uint16_t pwm) { return 0; }
122 
123  /*
124  enable PX4IO SBUS out at the given rate
125  */
126  virtual bool enable_px4io_sbus_out(uint16_t rate_hz) { return false; }
127 
128  /*
129  * Optional method to control the update of the motors. Derived classes
130  * can implement it if their HAL layer requires.
131  */
132  virtual void timer_tick(void) { }
133 
134  /*
135  setup for serial output to an ESC using the given
136  baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
137  databits. This is used for passthrough ESC configuration and
138  firmware flashing
139 
140  While serial output is active normal output to this channel is
141  suspended. Output to some other channels (such as those in the
142  same channel timer group) may also be stopped, depending on the
143  implementation
144  */
145  virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate) { return false; }
146 
147  /*
148  write a set of bytes to an ESC, using settings from
149  serial_setup_output. This is a blocking call
150  */
151  virtual bool serial_write_bytes(const uint8_t *bytes, uint16_t len) { return false; }
152 
153  /*
154  read a series of bytes from a port, using serial parameters from serial_setup_output()
155  return the number of bytes read. This is a blocking call
156  */
157  virtual uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) { return 0; }
158 
159  /*
160  stop serial output. This restores the previous output mode for
161  the channel and any other channels that were stopped by
162  serial_setup_output()
163  */
164  virtual void serial_end(void) {}
165 
166  /*
167  output modes. Allows for support of PWM, oneshot and dshot
168  */
169  enum output_mode {
179  };
180  virtual void set_output_mode(uint16_t mask, enum output_mode mode) {}
181 
182  /*
183  set default update rate
184  */
185  virtual void set_default_rate(uint16_t rate_hz) {}
186 
187  /*
188  enable telemetry request for a mask of channels. This is used
189  with DShot to get telemetry feedback
190  */
191  virtual void set_telem_request_mask(uint16_t mask) {}
192 };
virtual void force_safety_no_wait(void)
Definition: RCOutput.h:103
virtual void force_safety_off(void)
Definition: RCOutput.h:98
virtual uint16_t read(uint8_t ch)=0
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
Definition: RCOutput.h:111
virtual void set_freq(uint32_t chmask, uint16_t freq_hz)=0
virtual uint16_t get_freq(uint8_t ch)=0
virtual uint16_t read_last_sent(uint8_t ch)
Definition: RCOutput.h:74
static uint16_t pwm
Definition: RCOutput.cpp:20
virtual void read_last_sent(uint16_t *period_us, uint8_t len)
Definition: RCOutput.h:75
virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us)
Definition: RCOutput.h:81
virtual void enable_ch(uint8_t ch)=0
virtual void init()=0
virtual void timer_tick(void)
Definition: RCOutput.h:132
virtual void set_default_rate(uint16_t rate_hz)
Definition: RCOutput.h:185
virtual bool enable_px4io_sbus_out(uint16_t rate_hz)
Definition: RCOutput.h:126
virtual bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm)
Definition: RCOutput.h:116
virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
Definition: RCOutput.h:86
virtual void set_telem_request_mask(uint16_t mask)
Definition: RCOutput.h:191
virtual void cork()=0
virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate)
Definition: RCOutput.h:145
virtual void serial_end(void)
Definition: RCOutput.h:164
virtual void write(uint8_t ch, uint16_t period_us)=0
virtual bool force_safety_on(void)
Definition: RCOutput.h:93
virtual void push()=0
virtual void set_output_mode(uint16_t mask, enum output_mode mode)
Definition: RCOutput.h:180
virtual void disable_ch(uint8_t ch)=0
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
virtual bool serial_write_bytes(const uint8_t *bytes, uint16_t len)
Definition: RCOutput.h:151
virtual float scale_esc_to_unity(uint16_t pwm)
Definition: RCOutput.h:121
virtual uint16_t serial_read_bytes(uint8_t *buf, uint16_t len)
Definition: RCOutput.h:157