APM:Libraries
Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
Linux::RCOutput_AeroIO Class Reference

#include <RCOutput_AeroIO.h>

Inheritance diagram for Linux::RCOutput_AeroIO:
[legend]
Collaboration diagram for Linux::RCOutput_AeroIO:
[legend]

Public Member Functions

 RCOutput_AeroIO ()
 
 ~RCOutput_AeroIO ()
 
void init () override
 
void enable_ch (uint8_t ch) override
 
void disable_ch (uint8_t ch) override
 
void set_freq (uint32_t chmask, uint16_t freq_hz) override
 
uint16_t get_freq (uint8_t ch) override
 
void write (uint8_t ch, uint16_t period_us) override
 
void cork () override
 
void push () override
 
uint16_t read (uint8_t ch) override
 
void read (uint16_t *period_us, uint8_t len) override
 
- Public Member Functions inherited from AP_HAL::RCOutput
virtual uint16_t read_last_sent (uint8_t ch)
 
virtual void read_last_sent (uint16_t *period_us, uint8_t len)
 
virtual void set_safety_pwm (uint32_t chmask, uint16_t period_us)
 
virtual void set_failsafe_pwm (uint32_t chmask, uint16_t period_us)
 
virtual bool force_safety_on (void)
 
virtual void force_safety_off (void)
 
virtual void force_safety_no_wait (void)
 
virtual void set_esc_scaling (uint16_t min_pwm, uint16_t max_pwm)
 
virtual bool get_esc_scaling (uint16_t &min_pwm, uint16_t &max_pwm)
 
virtual float scale_esc_to_unity (uint16_t pwm)
 
virtual bool enable_px4io_sbus_out (uint16_t rate_hz)
 
virtual void timer_tick (void)
 
virtual bool serial_setup_output (uint8_t chan, uint32_t baudrate)
 
virtual bool serial_write_bytes (const uint8_t *bytes, uint16_t len)
 
virtual uint16_t serial_read_bytes (uint8_t *buf, uint16_t len)
 
virtual void serial_end (void)
 
virtual void set_output_mode (uint16_t mask, enum output_mode mode)
 
virtual void set_default_rate (uint16_t rate_hz)
 
virtual void set_telem_request_mask (uint16_t mask)
 

Private Member Functions

bool _hw_write (uint16_t address, uint16_t data)
 
uint16_t _hw_read (uint16_t address)
 

Static Private Member Functions

static uint16_t _usec_to_hw (uint16_t freq, uint16_t usec)
 
static uint16_t _hw_to_usec (uint16_t freq, uint16_t hw_val)
 

Private Attributes

AP_HAL::OwnPtr< AP_HAL::Device_spi
 
uint16_t * _freq_buffer
 
uint16_t * _duty_buffer
 
uint32_t _pending_duty_write_mask = 0
 
uint32_t _pending_freq_write_mask = 0
 
bool _corking = false
 

Additional Inherited Members

- Public Types inherited from AP_HAL::RCOutput
enum  output_mode {
  MODE_PWM_NONE, MODE_PWM_NORMAL, MODE_PWM_ONESHOT, MODE_PWM_ONESHOT125,
  MODE_PWM_BRUSHED, MODE_PWM_DSHOT150, MODE_PWM_DSHOT300, MODE_PWM_DSHOT600,
  MODE_PWM_DSHOT1200
}
 

Detailed Description

Definition at line 24 of file RCOutput_AeroIO.h.

Constructor & Destructor Documentation

◆ RCOutput_AeroIO()

RCOutput_AeroIO::RCOutput_AeroIO ( )

Definition at line 96 of file RCOutput_AeroIO.cpp.

◆ ~RCOutput_AeroIO()

RCOutput_AeroIO::~RCOutput_AeroIO ( )

Definition at line 102 of file RCOutput_AeroIO.cpp.

Member Function Documentation

◆ _hw_read()

uint16_t RCOutput_AeroIO::_hw_read ( uint16_t  address)
private

Low-level spi read

register address

Return: value read from

Definition at line 243 of file RCOutput_AeroIO.cpp.

Referenced by read().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _hw_to_usec()

uint16_t RCOutput_AeroIO::_hw_to_usec ( uint16_t  freq,
uint16_t  hw_val 
)
staticprivate

Convert from hw units, 16bits percentage of the frequency, to time in µs

Frequency 16b percentage

Definition at line 282 of file RCOutput_AeroIO.cpp.

Referenced by read().

Here is the caller graph for this function:

◆ _hw_write()

bool RCOutput_AeroIO::_hw_write ( uint16_t  address,
uint16_t  data 
)
private

Low-level spi write

register address value to be written

Return: true on success, false otherwise

Definition at line 226 of file RCOutput_AeroIO.cpp.

Referenced by push().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _usec_to_hw()

uint16_t RCOutput_AeroIO::_usec_to_hw ( uint16_t  freq,
uint16_t  usec 
)
staticprivate

Convert from µs to hw units, 16bits percentage of the frequency, where 0xFFFF is 1/Freq seconds in high

Frequency Time in µseconds

Return: conversion from µs in a specific frequency to 16bits

Definition at line 275 of file RCOutput_AeroIO.cpp.

Referenced by push().

Here is the caller graph for this function:

◆ cork()

void RCOutput_AeroIO::cork ( void  )
overridevirtual

Implements AP_HAL::RCOutput.

Definition at line 180 of file RCOutput_AeroIO.cpp.

Referenced by init().

Here is the caller graph for this function:

◆ disable_ch()

void RCOutput_AeroIO::disable_ch ( uint8_t  ch)
overridevirtual

Disable channel (0 of duty cycle)

Implements AP_HAL::RCOutput.

Definition at line 158 of file RCOutput_AeroIO.cpp.

Here is the call graph for this function:

◆ enable_ch()

void RCOutput_AeroIO::enable_ch ( uint8_t  ch)
overridevirtual

Enable channel

Implements AP_HAL::RCOutput.

Definition at line 148 of file RCOutput_AeroIO.cpp.

Here is the call graph for this function:

◆ get_freq()

uint16_t RCOutput_AeroIO::get_freq ( uint8_t  ch)
overridevirtual

Get frequency of channel

channel

Return: frequency of this channel

Implements AP_HAL::RCOutput.

Definition at line 140 of file RCOutput_AeroIO.cpp.

◆ init()

void RCOutput_AeroIO::init ( void  )
overridevirtual

Implements AP_HAL::RCOutput.

Definition at line 108 of file RCOutput_AeroIO.cpp.

Here is the call graph for this function:

◆ push()

void RCOutput_AeroIO::push ( void  )
overridevirtual

Implements AP_HAL::RCOutput.

Definition at line 185 of file RCOutput_AeroIO.cpp.

Referenced by disable_ch(), enable_ch(), init(), set_freq(), and write().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read() [1/2]

uint16_t RCOutput_AeroIO::read ( uint8_t  ch)
overridevirtual

Get period of the duty cycle in µs

Implements AP_HAL::RCOutput.

Definition at line 207 of file RCOutput_AeroIO.cpp.

Referenced by read().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read() [2/2]

void RCOutput_AeroIO::read ( uint16_t *  period_us,
uint8_t  len 
)
overridevirtual

Set with the values in µs of each channel

vector that will be filled with duty cycle periods of each channel size of period_us vector

Implements AP_HAL::RCOutput.

Definition at line 219 of file RCOutput_AeroIO.cpp.

Here is the call graph for this function:

◆ set_freq()

void RCOutput_AeroIO::set_freq ( uint32_t  chmask,
uint16_t  freq_hz 
)
overridevirtual

Set all channels in the same frequency

Bitmask Frequency

Implements AP_HAL::RCOutput.

Definition at line 124 of file RCOutput_AeroIO.cpp.

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write()

void RCOutput_AeroIO::write ( uint8_t  ch,
uint16_t  period_us 
)
overridevirtual

Set period in µs

channel time in µs

Implements AP_HAL::RCOutput.

Definition at line 169 of file RCOutput_AeroIO.cpp.

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _corking

bool Linux::RCOutput_AeroIO::_corking = false
private

If true the push must be called to perform the writing, otherwise will be not necessary.

Definition at line 152 of file RCOutput_AeroIO.h.

Referenced by cork(), disable_ch(), enable_ch(), push(), set_freq(), and write().

◆ _duty_buffer

uint16_t* Linux::RCOutput_AeroIO::_duty_buffer
private

Duty cycle buffer of last written values

Definition at line 134 of file RCOutput_AeroIO.h.

Referenced by disable_ch(), push(), read(), write(), and ~RCOutput_AeroIO().

◆ _freq_buffer

uint16_t* Linux::RCOutput_AeroIO::_freq_buffer
private

Frequency buffer of last written values

Definition at line 129 of file RCOutput_AeroIO.h.

Referenced by get_freq(), push(), read(), set_freq(), and ~RCOutput_AeroIO().

◆ _pending_duty_write_mask

uint32_t Linux::RCOutput_AeroIO::_pending_duty_write_mask = 0
private

Save information about the channel that will be write in the next push call.

0b...101 ││└── 1st channel (Pending operation) │└─── 2nd Channel (No pending operation) └──── 3rd Channel (Pending operation)

Definition at line 145 of file RCOutput_AeroIO.h.

Referenced by disable_ch(), enable_ch(), push(), and write().

◆ _pending_freq_write_mask

uint32_t Linux::RCOutput_AeroIO::_pending_freq_write_mask = 0
private

Definition at line 146 of file RCOutput_AeroIO.h.

Referenced by push(), and set_freq().

◆ _spi

AP_HAL::OwnPtr<AP_HAL::Device> Linux::RCOutput_AeroIO::_spi
private

Definition at line 124 of file RCOutput_AeroIO.h.

Referenced by _hw_read(), _hw_write(), and init().


The documentation for this class was generated from the following files: