APM:Libraries
RCOutput.h
Go to the documentation of this file.
1 #pragma once
2 
4 #include <timer.h>
5 
6 
7 #include <AP_HAL/RCOutput.h>
8 
9 #include "AP_HAL_F4Light.h"
10 #include "GPIO.h"
11 #include <AP_HAL/HAL.h>
12 
13 
14 #define PWM_IGNORE_THIS_CHANNEL 1
15 
16 #define F4Light_MAX_OUTPUT_CHANNELS 12 // motors and servos
17 
18 
26 };
27 
28 #define MOTORID1 0
29 #define MOTORID2 1
30 #define MOTORID3 2
31 #define MOTORID4 3
32 #define MOTORID5 4
33 #define MOTORID6 5
34 #define MOTORID7 6
35 #define MOTORID8 7
36 #define MOTORID9 8
37 #define MOTORID10 9
38 #define MOTORID11 10
39 #define MOTORID12 11
40 
41 
43 public:
44  void init() override;
45  void set_freq(uint32_t chmask, uint16_t freq_hz) override;
46  uint16_t get_freq(uint8_t ch) override;
47  void enable_ch(uint8_t ch) override;
48  void disable_ch(uint8_t ch) override;
49  void write(uint8_t ch, uint16_t period_us) override;
50  void write(uint8_t ch, uint16_t* period_us, uint8_t len);
51  uint16_t read(uint8_t ch) override;
52  void read(uint16_t* period_us, uint8_t len) override;
53 
54  void cork() override{ _corked = true; }
55  void push() override;
56 
57  static void lateInit(); // 2nd stage with loaded parameters
58 
59  void set_output_mode(uint16_t mask, enum output_mode mode) override { _set_output_mode(mode); };
60 
61  static void _set_output_mode(enum output_mode mode);
62 
63  static void do_4way_if(AP_HAL::UARTDriver* uart);
64 /* can be overrided
65  void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
66  void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override;
67  bool force_safety_on(void) override;
68  void force_safety_off(void) override;
69  void force_safety_no_wait(void) override;
70  void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override {
71  _esc_pwm_min = min_pwm;
72  _esc_pwm_max = max_pwm;
73  }
74 
75  void _timer_tick(void);
76  bool enable_sbus_out(uint16_t rate_hz) override;
77 */
78 
79  static uint32_t inline _timer_period(uint16_t speed_hz, const timer_dev *dev) {
80  return (uint32_t)((float)(dev->state->freq + speed_hz/2) / speed_hz);
81  }
82 
83 
84 private:
85  static void InitPWM(void);
86  static void set_pwm(uint8_t ch, uint16_t pwm);
89  static void _set_pin_output_mode(uint8_t ch);
90 
91  static bool is_servo_enabled(uint8_t ch);
92 
93  static void init_channel(uint8_t ch);
94  static void init_channels();
95 
96  static uint16_t _enabled_channels;
97  static bool _sbus_enabled;
98  static bool _corked;
99  static void _init_alt_channels() {}// we don't has channels more than 8
100  static uint8_t _used_channels;
101  static enum BOARD_PWM_MODES _mode;
102  static bool _once_mode;
103  static uint8_t _servo_mask;
104 
106 
107  //static uint32_t _timer_frequency[F4Light_MAX_OUTPUT_CHANNELS];
108 
109  static void _timer3_isr_event(TIM_TypeDef*);
110 
111  static uint32_t _timer2_preload;
112  static uint16_t _timer3_preload;
113 
114  static uint8_t _pwm_type;
115 // static float _freq_scale;
116 
117  static const timer_dev* out_timers[16]; // array of timers, used to rc_out
118  static uint8_t num_out_timers;
119 
120  static void fill_timers();
121 };
122 
static uint16_t _enabled_channels
Definition: RCOutput.h:96
static void lateInit()
Definition: RCOutput.cpp:190
void set_freq(uint32_t chmask, uint16_t freq_hz) override
Definition: RCOutput.cpp:459
static void init_channel(uint8_t ch)
Definition: RCOutput.cpp:480
static uint8_t _initialized[F4Light_MAX_OUTPUT_CHANNELS]
Definition: RCOutput.h:105
void set_output_mode(uint16_t mask, enum output_mode mode) override
Definition: RCOutput.h:59
static uint32_t _timer_period(uint16_t speed_hz, const timer_dev *dev)
Definition: RCOutput.h:79
static uint8_t _servo_mask
Definition: RCOutput.h:103
void push() override
Definition: RCOutput.cpp:641
static void fill_timers()
Definition: RCOutput.cpp:224
static void set_pwm(uint8_t ch, uint16_t pwm)
Definition: RCOutput.cpp:513
BOARD_PWM_MODES
Definition: RCOutput.h:19
static bool _once_mode
Definition: RCOutput.h:102
uint16_t read(uint8_t ch) override
Definition: RCOutput.cpp:573
static void InitPWM(void)
Definition: RCOutput.cpp:202
static uint16_t pwm
Definition: RCOutput.cpp:20
timer interface.
uint32_t freq
Definition: timer.h:563
void enable_ch(uint8_t ch) override
Definition: RCOutput.cpp:587
static bool is_servo_enabled(uint8_t ch)
Definition: RCOutput.cpp:445
#define F4Light_MAX_OUTPUT_CHANNELS
Definition: RCOutput.h:16
void disable_ch(uint8_t ch) override
Definition: RCOutput.cpp:619
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static uint16_t _period[F4Light_MAX_OUTPUT_CHANNELS]
Definition: RCOutput.h:87
static const timer_dev * out_timers[16]
Definition: RCOutput.h:117
void write(uint8_t ch, uint16_t period_us) override
Definition: RCOutput.cpp:545
static bool _corked
Definition: RCOutput.h:98
static void _timer3_isr_event(TIM_TypeDef *)
static void _set_pin_output_mode(uint8_t ch)
Definition: RCOutput.cpp:389
static uint32_t _timer2_preload
Definition: RCOutput.h:111
static uint8_t _pwm_type
Definition: RCOutput.h:114
static uint8_t num_out_timers
Definition: RCOutput.h:118
static enum BOARD_PWM_MODES _mode
Definition: RCOutput.h:101
uint16_t get_freq(uint8_t ch) override
Definition: RCOutput.cpp:214
timerState * state
Definition: timer.h:578
static uint16_t _timer3_preload
Definition: RCOutput.h:112
static uint16_t _freq[F4Light_MAX_OUTPUT_CHANNELS]
Definition: RCOutput.h:88
static uint8_t _used_channels
Definition: RCOutput.h:100
static void _set_output_mode(enum output_mode mode)
Definition: RCOutput.cpp:245
static void init_channels()
Definition: RCOutput.cpp:500
static void _init_alt_channels()
Definition: RCOutput.h:99
void cork() override
Definition: RCOutput.h:54
void init() override
Definition: RCOutput.cpp:174
static bool _sbus_enabled
Definition: RCOutput.h:97
static void do_4way_if(AP_HAL::UARTDriver *uart)
Definition: RCOutput.cpp:184