PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Functions | |
int | start () |
Attempt to start driver on all available I2C busses. More... | |
int | stop () |
Stop the driver. More... | |
int | info () |
Print a little info about the driver. More... | |
void | usage () |
Prints info about the driver argument usage. More... | |
void | task_main (int argc, char *argv[]) |
void | fill_input_rc (uint16_t raw_rc_count, uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS], hrt_abstime now, bool frame_drop, bool failsafe, unsigned frame_drops, int rssi, input_rc_s &input_rc) |
int | start (int argc, char *argv[]) |
Variables | |
volatile bool | _task_should_exit = false |
static bool | _is_running = false |
static px4_task_t | _task_handle = -1 |
void spektrum_rc::fill_input_rc | ( | uint16_t | raw_rc_count, |
uint16_t | raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS], | ||
hrt_abstime | now, | ||
bool | frame_drop, | ||
bool | failsafe, | ||
unsigned | frame_drops, | ||
int | rssi, | ||
input_rc_s & | input_rc | ||
) |
Definition at line 165 of file spektrum_rc.cpp.
References input_rc_s::channel_count, input_rc_s::input_source, input_rc_s::rc_failsafe, input_rc_s::rc_lost, input_rc_s::rc_lost_frame_count, input_rc_s::rc_ppm_frame_length, input_rc_s::rc_total_frame_count, input_rc_s::rssi, input_rc_s::timestamp, input_rc_s::timestamp_last_signal, and input_rc_s::values.
Referenced by task_main().
int spektrum_rc::info | ( | ) |
Print a little info about the driver.
Definition at line 252 of file spektrum_rc.cpp.
Referenced by spektrum_rc_main().
int spektrum_rc::start | ( | ) |
Attempt to start driver on all available I2C busses.
This function will return as soon as the first sensor is detected on one of the available busses or if no sensors are detected.
Attempt to start driver on all available I2C busses.
Definition at line 235 of file ets_airspeed.cpp.
References ACCEL_DEVICE_PATH, BMA180::BMA180(), DfBebopBusWrapper::DfBebopBusWrapper(), DfBebopRangeFinderWrapper::DfBebopRangeFinderWrapper(), DfBmp280Wrapper::DfBmp280Wrapper(), DfISL29501Wrapper::DfISL29501Wrapper(), DfLtc2946Wrapper::DfLtc2946Wrapper(), DfMS5607Wrapper::DfMS5607Wrapper(), DfMS5611Wrapper::DfMS5611Wrapper(), errx, fd, bma180::g_dev, I2C_ADDRESS_MS4525DO, i2c_bus_options, BMA180::init(), BMA180::ioctl(), NUM_I2C_BUS_OPTIONS, OK, SENSOR_POLLRATE_DEFAULT, SENSORIOCSPOLLRATE, DfLtc2946Wrapper::start(), DfBebopBusWrapper::start(), DfMS5607Wrapper::start(), DfMS5611Wrapper::start(), DfBmp280Wrapper::start(), DfBebopRangeFinderWrapper::start(), DfISL29501Wrapper::start(), sdp3x_airspeed::start_bus(), ms5525_airspeed::start_bus(), ets_airspeed::start_bus(), meas_airspeed::start_bus(), mb12xx::start_bus(), mappydot::start_bus(), ina226::start_bus(), df_bebop_bus_wrapper::task_main(), uart_esc::task_main_trampoline(), mpu9x50::task_main_trampoline(), and warn.
Referenced by bma180_main(), df_bebop_bus_wrapper_main(), df_bebop_rangefinder_wrapper_main(), df_bmp280_wrapper_main(), df_isl29501_wrapper_main(), df_ltc2946_wrapper_main(), df_ms5607_wrapper_main(), df_ms5611_wrapper_main(), ets_airspeed_main(), ina226_main(), mappydot_main(), mb12xx_main(), mpu9x50_main(), ms4525_airspeed_main(), ms5525_airspeed_main(), sdp3x_airspeed_main(), and spektrum_rc_main().
int spektrum_rc::start | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 210 of file spektrum_rc.cpp.
References task_main().
int spektrum_rc::stop | ( | ) |
Stop the driver.
Stop the driver.
Definition at line 234 of file spektrum_rc.cpp.
Referenced by spektrum_rc_main().
void spektrum_rc::task_main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 80 of file spektrum_rc.cpp.
References DSM_BUFFER_SIZE, dsm_deinit(), dsm_init(), dsm_parse(), fill_input_rc(), hrt_absolute_time(), hrt_abstime, orb_advert_t, orb_advertise(), ORB_ID, orb_publish(), orb_unadvertise(), read(), SPEKTRUM_UART_DEVICE_PATH, and UNUSED.
Referenced by start().
void spektrum_rc::usage | ( | void | ) |
Prints info about the driver argument usage.
Prints info about the driver argument usage.
Definition at line 260 of file spektrum_rc.cpp.
Referenced by spektrum_rc_main().
|
static |
Definition at line 67 of file spektrum_rc.cpp.
|
static |
Definition at line 68 of file spektrum_rc.cpp.
volatile bool spektrum_rc::_task_should_exit = false |
Definition at line 66 of file spektrum_rc.cpp.