#include <airbourne_board.h>
|
| AirbourneBoard () |
|
bool | baro_present () override |
|
void | baro_read (float *pressure, float *temperature) override |
|
void | baro_update () override |
|
void | board_reset (bool bootloader) override |
|
void | clock_delay (uint32_t milliseconds) override |
|
uint64_t | clock_micros () override |
|
uint32_t | clock_millis () override |
|
bool | diff_pressure_present () override |
|
void | diff_pressure_read (float *diff_pressure, float *temperature) override |
|
void | diff_pressure_update () override |
|
rosflight_firmware::BackupData | get_backup_data () override |
|
bool | gnss_has_new_data () override |
|
bool | gnss_present () override |
|
GNSSRaw | gnss_raw_read () override |
|
GNSSData | gnss_read () override |
|
void | gnss_update () override |
|
bool | has_backup_data () override |
|
void | imu_not_responding_error () override |
|
bool | imu_read (float accel[3], float *temperature, float gyro[3], uint64_t *time_us) override |
|
void | init_board () override |
|
void | led0_off () override |
|
void | led0_on () override |
|
void | led0_toggle () override |
|
void | led1_off () override |
|
void | led1_on () override |
|
void | led1_toggle () override |
|
bool | mag_present () override |
|
void | mag_read (float mag[3]) override |
|
void | mag_update () override |
|
void | memory_init () override |
|
bool | memory_read (void *dest, size_t len) override |
|
bool | memory_write (const void *src, size_t len) override |
|
bool | new_imu_data () override |
|
uint16_t | num_sensor_errors () override |
|
void | pwm_disable () override |
|
void | pwm_init (uint32_t refresh_rate, uint16_t idle_pwm) override |
|
void | pwm_write (uint8_t channel, float value) override |
|
void | rc_init (rc_type_t rc_type) override |
|
bool | rc_lost () override |
|
float | rc_read (uint8_t channel) override |
|
void | sensors_init () override |
|
uint16_t | serial_bytes_available () override |
|
void | serial_flush () override |
|
void | serial_init (uint32_t baud_rate, uint32_t dev) override |
|
uint8_t | serial_read () override |
|
void | serial_write (const uint8_t *src, size_t len) override |
|
bool | sonar_present () override |
|
float | sonar_read () override |
|
void | sonar_update () override |
|
Definition at line 67 of file airbourne_board.h.
Enumerator |
---|
SERIAL_DEVICE_VCP |
|
SERIAL_DEVICE_UART3 |
|
Definition at line 93 of file airbourne_board.h.
rosflight_firmware::AirbourneBoard::AirbourneBoard |
( |
| ) |
|
bool rosflight_firmware::AirbourneBoard::baro_present |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::baro_read |
( |
float * |
pressure, |
|
|
float * |
temperature |
|
) |
| |
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::baro_update |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::board_reset |
( |
bool |
bootloader | ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::clock_delay |
( |
uint32_t |
milliseconds | ) |
|
|
overridevirtual |
uint64_t rosflight_firmware::AirbourneBoard::clock_micros |
( |
| ) |
|
|
overridevirtual |
uint32_t rosflight_firmware::AirbourneBoard::clock_millis |
( |
| ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::diff_pressure_present |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::diff_pressure_read |
( |
float * |
diff_pressure, |
|
|
float * |
temperature |
|
) |
| |
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::diff_pressure_update |
( |
| ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::gnss_has_new_data |
( |
| ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::gnss_present |
( |
| ) |
|
|
overridevirtual |
GNSSRaw rosflight_firmware::AirbourneBoard::gnss_raw_read |
( |
| ) |
|
|
overridevirtual |
GNSSData rosflight_firmware::AirbourneBoard::gnss_read |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::gnss_update |
( |
| ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::has_backup_data |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::imu_not_responding_error |
( |
| ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::imu_read |
( |
float |
accel[3], |
|
|
float * |
temperature, |
|
|
float |
gyro[3], |
|
|
uint64_t * |
time_us |
|
) |
| |
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::init_board |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::led0_off |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::led0_on |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::led0_toggle |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::led1_off |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::led1_on |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::led1_toggle |
( |
| ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::mag_present |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::mag_read |
( |
float |
mag[3] | ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::mag_update |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::memory_init |
( |
| ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::memory_read |
( |
void * |
dest, |
|
|
size_t |
len |
|
) |
| |
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::memory_write |
( |
const void * |
src, |
|
|
size_t |
len |
|
) |
| |
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::new_imu_data |
( |
| ) |
|
|
overridevirtual |
uint16_t rosflight_firmware::AirbourneBoard::num_sensor_errors |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::pwm_disable |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::pwm_init |
( |
uint32_t |
refresh_rate, |
|
|
uint16_t |
idle_pwm |
|
) |
| |
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::pwm_write |
( |
uint8_t |
channel, |
|
|
float |
value |
|
) |
| |
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::rc_init |
( |
rc_type_t |
rc_type | ) |
|
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::rc_lost |
( |
| ) |
|
|
overridevirtual |
float rosflight_firmware::AirbourneBoard::rc_read |
( |
uint8_t |
channel | ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::sensors_init |
( |
| ) |
|
|
overridevirtual |
uint16_t rosflight_firmware::AirbourneBoard::serial_bytes_available |
( |
void |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::serial_flush |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::serial_init |
( |
uint32_t |
baud_rate, |
|
|
uint32_t |
dev |
|
) |
| |
|
overridevirtual |
uint8_t rosflight_firmware::AirbourneBoard::serial_read |
( |
void |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::serial_write |
( |
const uint8_t * |
src, |
|
|
size_t |
len |
|
) |
| |
|
overridevirtual |
bool rosflight_firmware::AirbourneBoard::sonar_present |
( |
| ) |
|
|
overridevirtual |
float rosflight_firmware::AirbourneBoard::sonar_read |
( |
| ) |
|
|
overridevirtual |
void rosflight_firmware::AirbourneBoard::sonar_update |
( |
| ) |
|
|
overridevirtual |
float rosflight_firmware::AirbourneBoard::_accel_scale = 1.0 |
|
private |
int rosflight_firmware::AirbourneBoard::_board_revision = 2 |
|
private |
float rosflight_firmware::AirbourneBoard::_gyro_scale = 1.0 |
|
private |
MS4525 rosflight_firmware::AirbourneBoard::airspeed_ |
|
private |
MS5611 rosflight_firmware::AirbourneBoard::baro_ |
|
private |
Serial* rosflight_firmware::AirbourneBoard::current_serial_ |
|
private |
I2C rosflight_firmware::AirbourneBoard::ext_i2c_ |
|
private |
M25P16 rosflight_firmware::AirbourneBoard::flash_ |
|
private |
UBLOX rosflight_firmware::AirbourneBoard::gnss_ |
|
private |
MPU6000 rosflight_firmware::AirbourneBoard::imu_ |
|
private |
std::function<void()> rosflight_firmware::AirbourneBoard::imu_callback_ |
|
private |
uint64_t rosflight_firmware::AirbourneBoard::imu_time_us_ |
|
private |
I2C rosflight_firmware::AirbourneBoard::int_i2c_ |
|
private |
GPIO rosflight_firmware::AirbourneBoard::inv_pin_ |
|
private |
LED rosflight_firmware::AirbourneBoard::led1_ |
|
private |
LED rosflight_firmware::AirbourneBoard::led2_ |
|
private |
HMC5883L rosflight_firmware::AirbourneBoard::mag_ |
|
private |
bool rosflight_firmware::AirbourneBoard::new_imu_data_ |
|
private |
RC_BASE* rosflight_firmware::AirbourneBoard::rc_ = nullptr |
|
private |
RC_PPM rosflight_firmware::AirbourneBoard::rc_ppm_ |
|
private |
RC_SBUS rosflight_firmware::AirbourneBoard::rc_sbus_ |
|
private |
UART rosflight_firmware::AirbourneBoard::sbus_uart_ |
|
private |
I2CSonar rosflight_firmware::AirbourneBoard::sonar_ |
|
private |
uint8_t rosflight_firmware::AirbourneBoard::sonar_type = SONAR_NONE |
|
private |
SPI rosflight_firmware::AirbourneBoard::spi1_ |
|
private |
SPI rosflight_firmware::AirbourneBoard::spi3_ |
|
private |
UART rosflight_firmware::AirbourneBoard::uart3_ |
|
private |
VCP rosflight_firmware::AirbourneBoard::vcp_ |
|
private |
The documentation for this class was generated from the following files: