PX4 Firmware
PX4 Autopilot Software http://px4.io
|
R/C inputs and servo outputs. More...
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_rc_input.h>
#include <perf/perf_counter.h>
#include <systemlib/ppm_decode.h>
#include <rc/st24.h>
#include <rc/sumd.h>
#include <rc/sbus.h>
#include <rc/dsm.h>
#include "px4io.h"
Go to the source code of this file.
Macros | |
#define | RC_CHANNEL_HIGH_THRESH 5000 /* 75% threshold */ |
#define | RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */ |
Functions | |
static bool | ppm_input (uint16_t *values, uint16_t *num_values, uint16_t *frame_len) |
static bool | dsm_port_input (uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool *sumd_updated) |
void | controls_init (void) |
R/C receiver handling. More... | |
void | controls_tick () |
Variables | |
static perf_counter_t | c_gather_dsm |
static perf_counter_t | c_gather_sbus |
static perf_counter_t | c_gather_ppm |
static int | _dsm_fd = -1 |
int | _sbus_fd = -1 |
static uint16_t | rc_value_override = 0 |
static unsigned | _rssi_adc_counts = 0 |
static uint16_t | _rssi = 0 |
R/C inputs and servo outputs.
Definition in file controls.c.
#define RC_CHANNEL_HIGH_THRESH 5000 /* 75% threshold */ |
Definition at line 56 of file controls.c.
#define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */ |
Definition at line 57 of file controls.c.
Referenced by controls_tick().
void controls_init | ( | void | ) |
R/C receiver handling.
Input functions return true when they receive an update from the RC controller.
Definition at line 173 of file controls.c.
References _dsm_fd, _sbus_fd, dsm_init(), PC_ELAPSED, perf_alloc, PX4IO_P_RC_CONFIG_ASSIGNMENT, PX4IO_P_RC_CONFIG_CENTER, PX4IO_P_RC_CONFIG_DEADZONE, PX4IO_P_RC_CONFIG_MAX, PX4IO_P_RC_CONFIG_MIN, PX4IO_P_RC_CONFIG_OPTIONS, PX4IO_P_RC_CONFIG_OPTIONS_ENABLED, PX4IO_P_RC_CONFIG_STRIDE, PX4IO_RC_INPUT_CHANNELS, r_page_rc_input_config, r_raw_rc_count, sys_state_s::rc_channels_timestamp_received, sys_state_s::rc_channels_timestamp_valid, sbus_init(), and system_state.
Referenced by user_start().
void controls_tick | ( | void | ) |
Definition at line 205 of file controls.c.
References _rssi, _rssi_adc_counts, _sbus_fd, adc_measure(), ADC_RSSI, atomic_modify_clear(), atomic_modify_or(), dsm_port_input(), f(), hrt_absolute_time(), hrt_elapsed_time_atomic(), perf_begin(), perf_end(), ppm_input(), PX4IO_CONTROL_CHANNELS, PX4IO_P_RAW_RC_DATA, PX4IO_P_RAW_RC_FLAGS_FAILSAFE, PX4IO_P_RAW_RC_FLAGS_FRAME_DROP, PX4IO_P_RAW_RC_FLAGS_MAPPING_OK, PX4IO_P_RAW_RC_FLAGS_RC_OK, PX4IO_P_RAW_RC_NRSSI, PX4IO_P_RC_CONFIG_ASSIGNMENT, PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH, PX4IO_P_RC_CONFIG_CENTER, PX4IO_P_RC_CONFIG_DEADZONE, PX4IO_P_RC_CONFIG_MAX, PX4IO_P_RC_CONFIG_MIN, PX4IO_P_RC_CONFIG_OPTIONS, PX4IO_P_RC_CONFIG_OPTIONS_ENABLED, PX4IO_P_RC_CONFIG_OPTIONS_REVERSE, PX4IO_P_RC_CONFIG_STRIDE, PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE, PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED, PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE, PX4IO_P_SETUP_FEATURES_ADC_RSSI, PX4IO_P_STATUS_ALARMS_RC_LOST, PX4IO_P_STATUS_FLAGS_FMU_OK, PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_P_STATUS_FLAGS_OVERRIDE, PX4IO_P_STATUS_FLAGS_RC_DSM, PX4IO_P_STATUS_FLAGS_RC_OK, PX4IO_P_STATUS_FLAGS_RC_PPM, PX4IO_P_STATUS_FLAGS_RC_SBUS, PX4IO_P_STATUS_FLAGS_RC_ST24, PX4IO_P_STATUS_FLAGS_RC_SUMD, PX4IO_RC_INPUT_CHANNELS, r_page_raw_rc_input, r_page_rc_input_config, r_raw_rc_count, r_raw_rc_flags, r_raw_rc_values, r_rc_valid, r_rc_values, r_setup_arming, r_setup_features, r_setup_rc_thr_failsafe, r_status_alarms, r_status_flags, RC_CHANNEL_LOW_THRESH, sys_state_s::rc_channels_timestamp_received, sys_state_s::rc_channels_timestamp_valid, RC_INPUT_RSSI_MAX, rc_value_override, REG_TO_SIGNED, sbus_input(), SIGNED_TO_REG, and system_state.
Referenced by user_start().
|
static |
Definition at line 79 of file controls.c.
References _dsm_fd, atomic_modify_or(), dsm_input(), OK, perf_begin(), perf_end(), PX4IO_P_RAW_RC_FLAGS_FAILSAFE, PX4IO_P_RAW_RC_FLAGS_FRAME_DROP, PX4IO_P_RAW_RC_FLAGS_RC_DSM11, PX4IO_P_SETUP_FEATURES_ADC_RSSI, PX4IO_P_STATUS_FLAGS_RC_ST24, PX4IO_P_STATUS_FLAGS_RC_SUMD, PX4IO_RC_INPUT_CHANNELS, r_raw_rc_count, r_raw_rc_flags, r_raw_rc_values, r_setup_features, r_status_flags, RC_INPUT_RSSI_MAX, st24_decode(), and sumd_decode().
Referenced by controls_tick().
|
static |
Definition at line 562 of file controls.c.
References hrt_elapsed_time(), ppm_buffer, ppm_decoded_channels, ppm_frame_length, ppm_last_valid_decode, PPM_MAX_CHANNELS, PX4IO_RC_INPUT_CHANNELS, and state.
Referenced by controls_tick().
|
static |
Definition at line 66 of file controls.c.
Referenced by controls_init(), and dsm_port_input().
|
static |
Definition at line 77 of file controls.c.
Referenced by controls_tick().
|
static |
Definition at line 72 of file controls.c.
Referenced by controls_tick().
int _sbus_fd = -1 |
Definition at line 67 of file controls.c.
Referenced by controls_init(), controls_tick(), and mixer_tick().
|
static |
Definition at line 62 of file controls.c.
|
static |
Definition at line 64 of file controls.c.
|
static |
Definition at line 63 of file controls.c.
|
static |
Definition at line 69 of file controls.c.
Referenced by controls_tick().