APM:Libraries
RCOutput.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_VRBRAIN.h"
4 #include <systemlib/perf_counter.h>
5 #include <uORB/topics/actuator_outputs.h>
6 #include <uORB/topics/actuator_armed.h>
7 
8 #define VRBRAIN_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  float scale_esc_to_unity(uint16_t pwm) override {
33  return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0;
34  }
35  void cork();
36  void push();
37 
38  void set_output_mode(uint16_t mask, enum output_mode mode) override;
39 
40  void timer_tick(void) override;
41  bool enable_px4io_sbus_out(uint16_t rate_hz) override;
42 
43  // set default output update rate
44  void set_default_rate(uint16_t rate_hz) override;
45 
46 private:
47  int _pwm_fd;
48  int _alt_fd;
49  uint16_t _freq_hz;
51  // we keep the last_sent value separately, as we need to keep the unscaled
52  // value for systems with brushed motors which scale outputs
54  volatile uint8_t _max_channel;
55  volatile bool _need_update;
56  bool _sbus_enabled:1;
57  perf_counter_t _perf_rcout;
58  uint32_t _last_output;
59  uint32_t _last_config_us;
60  unsigned _servo_count;
61  unsigned _alt_servo_count;
62  uint32_t _rate_mask_main;
63  uint32_t _rate_mask_alt;
65  uint32_t _period_max;
66  struct {
67  int pwm_sub;
68  actuator_outputs_s outputs;
69  } _outputs[ORB_MULTI_MAX_INSTANCES] {};
70  actuator_armed_s _armed;
71 
72  orb_advert_t _actuator_armed_pub;
73  uint16_t _esc_pwm_min;
74  uint16_t _esc_pwm_max;
75 
76  void _init_alt_channels(void);
77  void _arm_actuators(bool arm);
78  void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask);
79  bool _corking;
81  void _send_outputs(void);
85  uint16_t _default_rate_hz = 50;
86 };
void timer_tick(void) override
Definition: RCOutput.cpp:579
perf_counter_t _perf_rcout
Definition: RCOutput.h:57
uint16_t get_freq(uint8_t ch) override
Definition: RCOutput.cpp:243
enum AP_HAL::Util::safety_state _safety_state_request
Definition: RCOutput.h:82
void disable_ch(uint8_t ch) override
Definition: RCOutput.cpp:275
uint32_t _safety_state_request_last_ms
Definition: RCOutput.h:83
volatile bool _need_update
Definition: RCOutput.h:55
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
Definition: RCOutput.cpp:98
unsigned _alt_servo_count
Definition: RCOutput.h:61
uint16_t read_last_sent(uint8_t ch) override
Definition: RCOutput.cpp:435
struct VRBRAIN::VRBRAINRCOutput::@116 _outputs[ORB_MULTI_MAX_INSTANCES]
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:301
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:285
bool enable_px4io_sbus_out(uint16_t rate_hz) override
Definition: RCOutput.cpp:593
static uint16_t pwm
Definition: RCOutput.cpp:20
volatile uint8_t _max_channel
Definition: RCOutput.h:54
uint32_t _last_config_us
Definition: RCOutput.h:59
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
Definition: RCOutput.h:28
orb_advert_t _actuator_armed_pub
Definition: RCOutput.h:72
float scale_esc_to_unity(uint16_t pwm) override
Definition: RCOutput.h:32
void force_safety_off(void) override
Definition: RCOutput.cpp:324
enum output_mode _output_mode
Definition: RCOutput.h:80
uint16_t _enabled_channels
Definition: RCOutput.h:64
#define VRBRAIN_NUM_OUTPUT_CHANNELS
Definition: RCOutput.h:8
void set_freq(uint32_t chmask, uint16_t freq_hz) override
Definition: RCOutput.cpp:215
void init() override
Definition: RCOutput.cpp:28
void write(uint8_t ch, uint16_t period_us) override
Definition: RCOutput.cpp:359
void force_safety_no_wait(void) override
Definition: RCOutput.cpp:351
safety_state
Definition: Util.h:35
void _arm_actuators(bool arm)
Definition: RCOutput.cpp:454
actuator_outputs_s outputs
Definition: RCOutput.h:68
uint16_t _period[VRBRAIN_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:50
void enable_ch(uint8_t ch) override
Definition: RCOutput.cpp:257
uint16_t _last_sent[VRBRAIN_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:53
void set_output_mode(uint16_t mask, enum output_mode mode) override
Definition: RCOutput.cpp:617
uint16_t read(uint8_t ch) override
Definition: RCOutput.cpp:410
void force_safety_pending_requests(void)
Definition: RCOutput.cpp:330
uint32_t _rate_mask_main
Definition: RCOutput.h:62
void _init_alt_channels(void)
Definition: RCOutput.cpp:77
void set_default_rate(uint16_t rate_hz) override
Definition: RCOutput.cpp:669
uint16_t _default_rate_hz
Definition: RCOutput.h:85
bool force_safety_on(void) override
Definition: RCOutput.cpp:317
actuator_armed_s _armed
Definition: RCOutput.h:70