4 #include <systemlib/perf_counter.h> 5 #include <uORB/topics/actuator_outputs.h> 6 #include <uORB/topics/actuator_armed.h> 8 #define PX4_NUM_OUTPUT_CHANNELS 16 14 void set_freq(uint32_t chmask, uint16_t freq_hz)
override;
15 uint16_t
get_freq(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;
76 }
_outputs[ORB_MULTI_MAX_INSTANCES] {};
85 void set_freq_fd(
int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask);
void timer_tick(void) override
uint16_t _last_sent[PX4_NUM_OUTPUT_CHANNELS]
void set_output_mode(uint16_t mask, enum output_mode mode) override
void set_freq(uint32_t chmask, uint16_t freq_hz) override
void _arm_actuators(bool arm)
perf_counter_t _perf_rcout
uint16_t read_last_sent(uint8_t ch) override
uint32_t _safety_state_request_last_ms
bool enable_px4io_sbus_out(uint16_t rate_hz) override
void disable_ch(uint8_t ch) override
void write(uint8_t ch, uint16_t period_us) override
bool force_safety_on(void) override
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
enum output_mode _output_mode
bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) override
uint16_t _last_safety_options
void force_safety_pending_requests(void)
unsigned _alt_servo_count
uint32_t _last_safety_options_check_ms
void force_safety_off(void) override
float scale_esc_to_unity(uint16_t pwm) override
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS]
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
struct PX4::PX4RCOutput::@107 _outputs[ORB_MULTI_MAX_INSTANCES]
volatile bool _need_update
uint16_t _default_rate_hz
void set_default_rate(uint16_t rate_hz) override
uint16_t read(uint8_t ch) override
orb_advert_t _actuator_armed_pub
void _init_alt_channels(void)
actuator_outputs_s outputs
enum AP_HAL::Util::safety_state _safety_state_request
uint16_t _enabled_channels
void enable_ch(uint8_t ch) override
#define PX4_NUM_OUTPUT_CHANNELS
uint16_t get_freq(uint8_t ch) override
volatile uint8_t _max_channel
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
void force_safety_no_wait(void) override