APM:Libraries
RCOutput.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_PX4.h"
4 #include <systemlib/perf_counter.h>
5 #include <uORB/topics/actuator_outputs.h>
6 #include <uORB/topics/actuator_armed.h>
7 
8 #define PX4_NUM_OUTPUT_CHANNELS 16
9 
11 {
12 public:
13  void init() override;
14  void set_freq(uint32_t chmask, uint16_t freq_hz) override;
15  uint16_t get_freq(uint8_t ch) override;
16  void enable_ch(uint8_t ch) override;
17  void disable_ch(uint8_t ch) override;
18  void write(uint8_t ch, uint16_t period_us) override;
19  uint16_t read(uint8_t ch) override;
20  void read(uint16_t* period_us, uint8_t len) override;
21  uint16_t read_last_sent(uint8_t ch) override;
22  void read_last_sent(uint16_t* period_us, uint8_t len) override;
23  void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
24  void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override;
25  bool force_safety_on(void) override;
26  void force_safety_off(void) override;
27  void force_safety_no_wait(void) override;
28  void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override {
29  _esc_pwm_min = min_pwm;
30  _esc_pwm_max = max_pwm;
31  }
32  bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) override {
33  min_pwm = _esc_pwm_min;
34  max_pwm = _esc_pwm_max;
35  return true;
36  }
37  float scale_esc_to_unity(uint16_t pwm) override {
38  return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0;
39  }
40  void cork();
41  void push();
42 
43  void set_output_mode(uint16_t mask, enum output_mode mode) override;
44 
45  void timer_tick(void) override;
46  bool enable_px4io_sbus_out(uint16_t rate_hz) override;
47 
48  // set default output update rate
49  void set_default_rate(uint16_t rate_hz) override;
50 
51 private:
52  int _pwm_fd;
53  int _alt_fd;
54  uint16_t _freq_hz;
56  // we keep the last_sent value separately, as we need to keep the unscaled
57  // value for systems with brushed motors which scale outputs
59  volatile uint8_t _max_channel;
60  volatile bool _need_update;
61  bool _sbus_enabled:1;
62  perf_counter_t _perf_rcout;
63  uint32_t _last_output;
64  uint32_t _last_config_us;
65  unsigned _servo_count;
66  unsigned _alt_servo_count;
67  uint32_t _rate_mask_main;
68  uint32_t _rate_mask_alt;
70  uint32_t _period_max;
72  uint16_t _last_safety_options = 0xFFFF;
73  struct {
74  int pwm_sub;
75  actuator_outputs_s outputs;
76  } _outputs[ORB_MULTI_MAX_INSTANCES] {};
77  actuator_armed_s _armed;
78 
79  orb_advert_t _actuator_armed_pub;
80  uint16_t _esc_pwm_min;
81  uint16_t _esc_pwm_max;
82 
83  void _init_alt_channels(void);
84  void _arm_actuators(bool arm);
85  void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask);
86  bool _corking;
88  void _send_outputs(void);
92  uint16_t _default_rate_hz = 50;
93 };
void timer_tick(void) override
Definition: RCOutput.cpp:563
uint16_t _last_sent[PX4_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:58
actuator_armed_s _armed
Definition: RCOutput.h:77
void set_output_mode(uint16_t mask, enum output_mode mode) override
Definition: RCOutput.cpp:601
void set_freq(uint32_t chmask, uint16_t freq_hz) override
Definition: RCOutput.cpp:173
uint32_t _rate_mask_alt
Definition: RCOutput.h:68
bool _sbus_enabled
Definition: RCOutput.h:61
void _arm_actuators(bool arm)
Definition: RCOutput.cpp:437
perf_counter_t _perf_rcout
Definition: RCOutput.h:62
uint16_t read_last_sent(uint8_t ch) override
Definition: RCOutput.cpp:418
uint32_t _safety_state_request_last_ms
Definition: RCOutput.h:90
bool enable_px4io_sbus_out(uint16_t rate_hz) override
Definition: RCOutput.cpp:577
void disable_ch(uint8_t ch) override
Definition: RCOutput.cpp:233
void write(uint8_t ch, uint16_t period_us) override
Definition: RCOutput.cpp:340
static uint16_t pwm
Definition: RCOutput.cpp:20
bool force_safety_on(void) override
Definition: RCOutput.cpp:275
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
Definition: RCOutput.cpp:98
enum output_mode _output_mode
Definition: RCOutput.h:87
bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) override
Definition: RCOutput.h:32
uint16_t _last_safety_options
Definition: RCOutput.h:72
void force_safety_pending_requests(void)
Definition: RCOutput.cpp:288
unsigned _alt_servo_count
Definition: RCOutput.h:66
uint32_t _last_safety_options_check_ms
Definition: RCOutput.h:71
void force_safety_off(void) override
Definition: RCOutput.cpp:282
float scale_esc_to_unity(uint16_t pwm) override
Definition: RCOutput.h:37
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:259
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:55
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
Definition: RCOutput.h:28
uint32_t _last_config_us
Definition: RCOutput.h:64
struct PX4::PX4RCOutput::@107 _outputs[ORB_MULTI_MAX_INSTANCES]
volatile bool _need_update
Definition: RCOutput.h:60
uint16_t _default_rate_hz
Definition: RCOutput.h:92
uint16_t _esc_pwm_min
Definition: RCOutput.h:80
void set_default_rate(uint16_t rate_hz) override
Definition: RCOutput.cpp:654
unsigned _servo_count
Definition: RCOutput.h:65
uint16_t _esc_pwm_max
Definition: RCOutput.h:81
safety_state
Definition: Util.h:35
uint16_t read(uint8_t ch) override
Definition: RCOutput.cpp:393
orb_advert_t _actuator_armed_pub
Definition: RCOutput.h:79
void _init_alt_channels(void)
Definition: RCOutput.cpp:77
actuator_outputs_s outputs
Definition: RCOutput.h:75
uint32_t _last_output
Definition: RCOutput.h:63
void _send_outputs(void)
Definition: RCOutput.cpp:461
uint32_t _rate_mask_main
Definition: RCOutput.h:67
uint32_t _period_max
Definition: RCOutput.h:70
enum AP_HAL::Util::safety_state _safety_state_request
Definition: RCOutput.h:89
void init() override
Definition: RCOutput.cpp:28
uint16_t _enabled_channels
Definition: RCOutput.h:69
uint16_t _freq_hz
Definition: RCOutput.h:54
void enable_ch(uint8_t ch) override
Definition: RCOutput.cpp:215
#define PX4_NUM_OUTPUT_CHANNELS
Definition: RCOutput.h:8
uint16_t get_freq(uint8_t ch) override
Definition: RCOutput.cpp:201
volatile uint8_t _max_channel
Definition: RCOutput.h:59
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:243
void force_safety_no_wait(void) override
Definition: RCOutput.cpp:332