PX4 Firmware
PX4 Autopilot Software http://px4.io
|
General defines and structures for the PX4IO module firmware. More...
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include <stdint.h>
#include <board_config.h>
#include "protocol.h"
#include <output_limit/output_limit.h>
#include <debug.h>
Go to the source code of this file.
Classes | |
struct | sys_state_s |
Functions | |
void | atomic_modify_or (volatile uint16_t *target, uint16_t modification) |
void | atomic_modify_clear (volatile uint16_t *target, uint16_t modification) |
void | atomic_modify_and (volatile uint16_t *target, uint16_t modification) |
void | mixer_tick (void) |
int | mixer_handle_text_create_mixer (void) |
int | mixer_handle_text (const void *buffer, size_t length) |
void | mixer_set_failsafe (void) |
void | safety_init (void) |
Safety switch/LED. More... | |
void | failsafe_led_init (void) |
void | interface_init (void) |
FMU communications. More... | |
void | interface_tick (void) |
int | registers_set (uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values) |
Register space. More... | |
int | registers_get (uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values) |
int | adc_init (void) |
Sensors/misc inputs. More... | |
uint16_t | adc_measure (unsigned channel) |
void | controls_init (void) |
R/C receiver handling. More... | |
void | controls_tick (void) |
void | isr_debug (uint8_t level, const char *fmt,...) |
send a debug message to the console More... | |
void | schedule_reboot (uint32_t time_delta_usec) |
schedule a reboot More... | |
Variables | |
volatile uint16_t | r_page_status [] |
PAGE 1. More... | |
uint16_t | r_page_actuators [] |
PAGE 2. More... | |
uint16_t | r_page_servos [] |
PAGE 3. More... | |
uint16_t | r_page_direct_pwm [] |
PAGE 8. More... | |
uint16_t | r_page_raw_rc_input [] |
PAGE 4. More... | |
uint16_t | r_page_rc_input [] |
PAGE 5. More... | |
uint16_t | r_page_adc [] |
volatile uint16_t | r_page_setup [] |
PAGE 100. More... | |
uint16_t | r_page_controls [] |
PAGE 101. More... | |
uint16_t | r_page_rc_input_config [] |
PAGE 103. More... | |
uint16_t | r_page_servo_failsafe [] |
PAGE 105. More... | |
uint16_t | r_page_servo_control_min [] |
PAGE 106. More... | |
uint16_t | r_page_servo_control_max [] |
PAGE 107. More... | |
int16_t | r_page_servo_control_trim [] |
PAGE 108. More... | |
uint16_t | r_page_servo_disarmed [] |
PAGE 109. More... | |
struct sys_state_s | system_state |
float | dt |
bool | update_mc_thrust_param |
bool | update_trims |
output_limit_t | pwm_limit |
volatile uint8_t | debug_level |
global debug level for isr_debug() More... | |
#define ADC_RSSI 5 |
Definition at line 181 of file px4io.h.
Referenced by controls_tick(), and registers_get().
#define ADC_VSERVO 4 |
Definition at line 180 of file px4io.h.
Referenced by registers_get().
#define BUTTON_SAFETY px4_arch_gpioread(GPIO_BTN_SAFETY) |
Definition at line 183 of file px4io.h.
Referenced by safety_check_button().
#define CONTROL_PAGE_INDEX | ( | _group, | |
_channel | |||
) | (_group * PX4IO_CONTROL_CHANNELS + _channel) |
Definition at line 185 of file px4io.h.
Referenced by mixer_callback().
#define ENABLE_SBUS_OUT | ( | _s | ) | px4_arch_gpiowrite(GPIO_SBUS_OENABLE, !(_s)) |
Definition at line 175 of file px4io.h.
Referenced by registers_set_one(), and user_start().
#define LED_AMBER | ( | _s | ) | px4_arch_gpiowrite(GPIO_LED2, !(_s)) |
#define LED_RING | ( | _s | ) | px4_arch_gpiowrite(GPIO_LED4, (_s)) |
Definition at line 171 of file px4io.h.
Referenced by ring_blink(), and user_start().
#define LED_SAFETY | ( | _s | ) | px4_arch_gpiowrite(GPIO_LED3, !(_s)) |
#define perf_alloc | ( | a, | |
b | |||
) | NULL |
Definition at line 59 of file px4io.h.
Referenced by adc_init(), at24c_initialize(), BMM150::BMM150(), controls_init(), Mavlink::DEFINE_PARAMETERS(), DfAK8963Wrapper::DfAK8963Wrapper(), DfHmc5883Wrapper::DfHmc5883Wrapper(), DfLsm9ds1Wrapper::DfLsm9ds1Wrapper(), DfMPU6050Wrapper::DfMPU6050Wrapper(), DfMpu9250Wrapper::DfMpu9250Wrapper(), HMC5883::HMC5883(), hott_telemetry_thread_main(), interface_init(), LIS3MDL::LIS3MDL(), px4::logger::LogWriterFile::LogWriterFile(), MixingOutput::MixingOutput(), param_init(), PX4IO_serial_interface(), QMC5883::QMC5883(), RM3100::RM3100(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), task_main(), test_perf(), and user_start().
#define PX4_CRITICAL_SECTION | ( | cmd | ) | { irqstate_t flags = px4_enter_critical_section(); cmd; px4_leave_critical_section(flags); } |
Definition at line 187 of file px4io.h.
Referenced by atomic_modify_and(), atomic_modify_clear(), and atomic_modify_or().
#define PX4IO_CONTROL_CHANNELS 8 |
Definition at line 66 of file px4io.h.
Referenced by controls_tick(), mixer_callback(), and registers_set().
#define PX4IO_CONTROL_GROUPS 4 |
Definition at line 67 of file px4io.h.
Referenced by mixer_callback(), and registers_set().
#define PX4IO_RC_INPUT_CHANNELS 18 |
Definition at line 68 of file px4io.h.
Referenced by controls_init(), controls_tick(), dsm_port_input(), ppm_input(), and registers_set_one().
#define PX4IO_RC_MAPPED_CONTROL_CHANNELS 8 |
This is the maximum number of channels mapped/used.
Definition at line 69 of file px4io.h.
Referenced by registers_set_one().
#define PX4IO_SERVO_COUNT 8 |
Definition at line 65 of file px4io.h.
Referenced by mixer_mix_threadsafe(), mixer_set_failsafe(), mixer_tick(), pwm_configure_rates(), registers_get(), and registers_set().
#define r_control_values (&r_page_controls[0]) |
#define r_mixer_limits r_page_status[PX4IO_P_STATUS_MIXER] |
Definition at line 115 of file px4io.h.
Referenced by mixer_set_failsafe(), and mixer_tick().
#define r_raw_rc_count r_page_raw_rc_input[PX4IO_P_RAW_RC_COUNT] |
Definition at line 110 of file px4io.h.
Referenced by controls_init(), controls_tick(), and dsm_port_input().
#define r_raw_rc_flags r_page_raw_rc_input[PX4IO_P_RAW_RC_FLAGS] |
Definition at line 112 of file px4io.h.
Referenced by controls_tick(), and dsm_port_input().
#define r_raw_rc_values (&r_page_raw_rc_input[PX4IO_P_RAW_RC_BASE]) |
Definition at line 111 of file px4io.h.
Referenced by controls_tick(), and dsm_port_input().
#define r_rc_valid r_page_rc_input[PX4IO_P_RC_VALID] |
Definition at line 113 of file px4io.h.
Referenced by controls_tick().
#define r_rc_values (&r_page_rc_input[PX4IO_P_RC_BASE]) |
Definition at line 114 of file px4io.h.
Referenced by controls_tick().
#define r_setup_airmode r_page_setup[PX4IO_P_SETUP_AIRMODE] |
Definition at line 135 of file px4io.h.
Referenced by mixer_tick().
#define r_setup_arming r_page_setup[PX4IO_P_SETUP_ARMING] |
Definition at line 118 of file px4io.h.
Referenced by controls_tick(), mixer_handle_text(), mixer_handle_text_create_mixer(), mixer_set_failsafe(), mixer_tick(), registers_set(), registers_set_one(), ring_blink(), safety_check_button(), update_mem_usage(), and user_start().
#define r_setup_features r_page_setup[PX4IO_P_SETUP_FEATURES] |
Definition at line 117 of file px4io.h.
Referenced by controls_tick(), dsm_port_input(), mixer_tick(), registers_set_one(), and user_start().
#define r_setup_flighttermination r_page_setup[PX4IO_P_SETUP_ENABLE_FLIGHTTERMINATION] |
Definition at line 136 of file px4io.h.
Referenced by mixer_tick().
#define r_setup_pwm_altrate r_page_setup[PX4IO_P_SETUP_PWM_ALTRATE] |
Definition at line 121 of file px4io.h.
Referenced by pwm_configure_rates(), and registers_set_one().
#define r_setup_pwm_defaultrate r_page_setup[PX4IO_P_SETUP_PWM_DEFAULTRATE] |
Definition at line 120 of file px4io.h.
Referenced by pwm_configure_rates(), and registers_set_one().
#define r_setup_pwm_rates r_page_setup[PX4IO_P_SETUP_PWM_RATES] |
Definition at line 119 of file px4io.h.
Referenced by pwm_configure_rates(), and registers_set_one().
#define r_setup_pwm_reverse r_page_setup[PX4IO_P_SETUP_PWM_REVERSE] |
Definition at line 124 of file px4io.h.
Referenced by mixer_tick().
#define r_setup_rc_thr_failsafe r_page_setup[PX4IO_P_SETUP_RC_THR_FAILSAFE_US] |
Definition at line 122 of file px4io.h.
Referenced by controls_tick().
#define r_setup_sbus_rate r_page_setup[PX4IO_P_SETUP_SBUS_RATE] |
#define r_setup_scale_pitch r_page_setup[PX4IO_P_SETUP_SCALE_PITCH] |
Definition at line 130 of file px4io.h.
Referenced by mixer_callback().
#define r_setup_scale_roll r_page_setup[PX4IO_P_SETUP_SCALE_ROLL] |
Definition at line 129 of file px4io.h.
Referenced by mixer_callback().
#define r_setup_scale_yaw r_page_setup[PX4IO_P_SETUP_SCALE_YAW] |
Definition at line 131 of file px4io.h.
Referenced by mixer_callback().
#define r_setup_slew_max r_page_setup[PX4IO_P_SETUP_MOTOR_SLEW_MAX] |
Definition at line 134 of file px4io.h.
Referenced by mixer_set_failsafe(), and mixer_tick().
#define r_setup_thr_fac r_page_setup[PX4IO_P_SETUP_THR_MDL_FAC] |
Definition at line 133 of file px4io.h.
Referenced by mixer_set_failsafe(), and mixer_tick().
#define r_setup_trim_pitch r_page_setup[PX4IO_P_SETUP_TRIM_PITCH] |
Definition at line 127 of file px4io.h.
Referenced by mixer_callback().
#define r_setup_trim_roll r_page_setup[PX4IO_P_SETUP_TRIM_ROLL] |
Definition at line 126 of file px4io.h.
Referenced by mixer_callback().
#define r_setup_trim_yaw r_page_setup[PX4IO_P_SETUP_TRIM_YAW] |
Definition at line 128 of file px4io.h.
Referenced by mixer_callback().
#define r_status_alarms r_page_status[PX4IO_P_STATUS_ALARMS] |
Definition at line 108 of file px4io.h.
Referenced by controls_tick(), mixer_tick(), pwm_configure_rates(), and registers_set_one().
#define r_status_flags r_page_status[PX4IO_P_STATUS_FLAGS] |
Definition at line 107 of file px4io.h.
Referenced by controls_tick(), dsm_port_input(), failsafe_blink(), mixer_handle_text(), mixer_handle_text_create_mixer(), mixer_mix_threadsafe(), mixer_set_failsafe(), mixer_tick(), registers_set(), registers_set_one(), ring_blink(), safety_check_button(), update_mem_usage(), and user_start().
#define VDD_SERVO_FAULT (!px4_arch_gpioread(GPIO_SERVO_FAULT_DETECT)) |
int adc_init | ( | void | ) |
Sensors/misc inputs.
Definition at line 82 of file adc.c.
References PC_ELAPSED, perf_alloc, rCR2, rSMPR1, rSMPR2, rSQR1, rSQR2, and rSQR3.
Referenced by user_start().
uint16_t adc_measure | ( | unsigned | channel | ) |
Definition at line 137 of file adc.c.
References hrt_absolute_time(), hrt_abstime, hrt_elapsed_time(), perf_begin(), perf_end(), rCR2, rDR, rSQR3, and rSR.
Referenced by controls_tick(), and registers_get().
void atomic_modify_and | ( | volatile uint16_t * | target, |
uint16_t | modification | ||
) |
Definition at line 109 of file px4io.c.
References PX4_CRITICAL_SECTION.
void atomic_modify_clear | ( | volatile uint16_t * | target, |
uint16_t | modification | ||
) |
Definition at line 102 of file px4io.c.
References PX4_CRITICAL_SECTION.
Referenced by controls_tick(), mixer_handle_text(), mixer_tick(), and safety_check_button().
void atomic_modify_or | ( | volatile uint16_t * | target, |
uint16_t | modification | ||
) |
Definition at line 95 of file px4io.c.
References PX4_CRITICAL_SECTION.
Referenced by controls_tick(), dsm_port_input(), mixer_tick(), and safety_check_button().
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().
void failsafe_led_init | ( | void | ) |
Definition at line 91 of file safety.c.
References failsafe_blink(), failsafe_call, and hrt_call_every().
Referenced by user_start().
void interface_init | ( | void | ) |
FMU communications.
Definition at line 90 of file serial.c.
References debug, dma_reset(), PC_COUNT, PC_ELAPSED, perf_alloc, rBRR, rCR1, rCR2, rCR3, rDR, rSR, rx_dma, serial_interrupt(), and tx_dma.
Referenced by user_start().
void interface_tick | ( | void | ) |
void isr_debug | ( | uint8_t | level, |
const char * | fmt, | ||
... | |||
) |
send a debug message to the console
Definition at line 120 of file px4io.c.
References msg, msg_counter, msg_next_in, NUM_MSG, PX4IO_P_SETUP_SET_DEBUG, and r_page_setup.
Referenced by mixer_handle_text(), mixer_handle_text_create_mixer(), mixer_tick(), registers_set_one(), and user_start().
int mixer_handle_text | ( | const void * | buffer, |
size_t | length | ||
) |
Definition at line 566 of file mixer.cpp.
References px4io_mixdata::action, atomic_modify_clear(), F2I_MIXER_ACTION_APPEND, F2I_MIXER_ACTION_RESET, in_mixer, isr_debug(), mixer_text, mixer_text_length, mixer_update_pending, msg, PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, r_setup_arming, r_status_flags, MixerGroup::reset(), px4io_mixdata::text, update_mc_thrust_param, and update_trims.
Referenced by registers_set().
int mixer_handle_text_create_mixer | ( | void | ) |
Definition at line 523 of file mixer.cpp.
References in_mixer, isr_debug(), MixerGroup::load_from_buf(), mixer_callback(), mixer_text, mixer_text_length, mixer_update_pending, PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, r_setup_arming, and r_status_flags.
Referenced by mixer_tick().
void mixer_set_failsafe | ( | void | ) |
Definition at line 635 of file mixer.cpp.
References dt, FLT_EPSILON, mixer_mix_threadsafe(), PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM, PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_SERVO_COUNT, r_mixer_limits, r_page_servo_control_max, r_page_servo_control_min, r_page_servo_failsafe, r_setup_arming, r_setup_slew_max, r_setup_thr_fac, r_status_flags, REG_TO_FLOAT, MixerGroup::set_max_delta_out_once(), MixerGroup::set_thrust_factor(), and update_mc_thrust_param.
Referenced by registers_set_one().
void mixer_tick | ( | void | ) |
Definition at line 117 of file mixer.cpp.
References _sbus_fd, atomic_modify_clear(), atomic_modify_or(), dt, f(), FLOAT_TO_REG, FLT_EPSILON, sys_state_s::fmu_data_received_time, FMU_INPUT_DROP_LIMIT_US, hrt_abstime, hrt_elapsed_time(), isr_debug(), last_fmu_update, MIX_DISARMED, MIX_FAILSAFE, MIX_FMU, MIX_NONE, MIX_OVERRIDE, MIX_OVERRIDE_FMU_OK, mixer_handle_text_create_mixer(), mixer_mix_threadsafe(), mixer_servos_armed, new_fmu_data, output_limit_calc(), pwm_limit, PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_SETUP_ARMING_FMU_PREARMED, PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE, PX4IO_P_SETUP_ARMING_LOCKDOWN, PX4IO_P_SETUP_FEATURES_SBUS1_OUT, PX4IO_P_SETUP_FEATURES_SBUS2_OUT, PX4IO_P_STATUS_ALARMS_FMU_LOST, PX4IO_P_STATUS_FLAGS_FAILSAFE, PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED, PX4IO_P_STATUS_FLAGS_FMU_OK, PX4IO_P_STATUS_FLAGS_INIT_OK, PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED, PX4IO_P_STATUS_FLAGS_OVERRIDE, PX4IO_P_STATUS_FLAGS_RAW_PWM, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, PX4IO_SERVO_COUNT, r_mixer_limits, r_page_actuators, r_page_direct_pwm, r_page_servo_control_max, r_page_servo_control_min, r_page_servo_control_trim, r_page_servo_disarmed, r_page_servo_failsafe, r_page_servos, r_setup_airmode, r_setup_arming, r_setup_features, r_setup_flighttermination, r_setup_pwm_reverse, r_setup_slew_max, r_setup_thr_fac, r_status_alarms, r_status_flags, REG_TO_BOOL, REG_TO_FLOAT, REG_TO_SIGNED, sbus1_output(), sbus2_output(), MixerGroup::set_airmode(), MixerGroup::set_max_delta_out_once(), MixerGroup::set_thrust_factor(), MixerGroup::set_trims(), should_always_enable_pwm, should_arm, should_arm_nothrottle, source, system_state, up_pwm_servo_arm(), up_pwm_servo_set(), up_pwm_update(), update_mc_thrust_param, and update_trims.
Referenced by user_start().
int registers_get | ( | uint8_t | page, |
uint8_t | offset, | ||
uint16_t ** | values, | ||
unsigned * | num_values | ||
) |
Definition at line 844 of file registers.c.
References adc_measure(), ADC_RSSI, ADC_VSERVO, last_offset, last_page, PX4IO_P_STATUS_VRSSI, PX4IO_P_STATUS_VSERVO, PX4IO_PAGE_ACTUATORS, PX4IO_PAGE_CONFIG, PX4IO_PAGE_CONTROL_MAX_PWM, PX4IO_PAGE_CONTROL_MIN_PWM, PX4IO_PAGE_CONTROL_TRIM_PWM, PX4IO_PAGE_CONTROLS, PX4IO_PAGE_DIRECT_PWM, PX4IO_PAGE_DISARMED_PWM, PX4IO_PAGE_FAILSAFE_PWM, PX4IO_PAGE_PWM_INFO, PX4IO_PAGE_RAW_ADC_INPUT, PX4IO_PAGE_RAW_RC_INPUT, PX4IO_PAGE_RC_CONFIG, PX4IO_PAGE_RC_INPUT, PX4IO_PAGE_SERVOS, PX4IO_PAGE_SETUP, PX4IO_PAGE_STATUS, PX4IO_RATE_MAP_BASE, PX4IO_SERVO_COUNT, r_page_actuators, r_page_config, r_page_controls, r_page_direct_pwm, r_page_raw_rc_input, r_page_rc_input, r_page_rc_input_config, r_page_scratch, r_page_servo_control_max, r_page_servo_control_min, r_page_servo_control_trim, r_page_servo_disarmed, r_page_servo_failsafe, r_page_servos, r_page_setup, r_page_status, SELECT_PAGE, and up_pwm_servo_get_rate_group().
Referenced by rx_handle_packet().
int registers_set | ( | uint8_t | page, |
uint8_t | offset, | ||
const uint16_t * | values, | ||
unsigned | num_values | ||
) |
Register space.
Definition at line 275 of file registers.c.
References sys_state_s::fmu_data_received_time, hrt_absolute_time(), mixer_handle_text(), PWM_HIGHEST_MAX, PWM_HIGHEST_MIN, PWM_IGNORE_THIS_CHANNEL, PWM_LOWEST_MAX, PWM_LOWEST_MIN, PX4IO_CONTROL_CHANNELS, PX4IO_CONTROL_GROUPS, PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM, PX4IO_P_STATUS_FLAGS_RAW_PWM, PX4IO_PAGE_CONTROL_MAX_PWM, PX4IO_PAGE_CONTROL_MIN_PWM, PX4IO_PAGE_CONTROL_TRIM_PWM, PX4IO_PAGE_CONTROLS, PX4IO_PAGE_DIRECT_PWM, PX4IO_PAGE_DISARMED_PWM, PX4IO_PAGE_FAILSAFE_PWM, PX4IO_PAGE_MIXERLOAD, PX4IO_SERVO_COUNT, r_page_controls, r_page_direct_pwm, r_page_servo_control_max, r_page_servo_control_min, r_page_servo_control_trim, r_page_servo_disarmed, r_page_servo_failsafe, r_setup_arming, r_status_flags, registers_set_one(), system_state, up_pwm_update(), and update_trims.
Referenced by rx_handle_packet().
void safety_init | ( | void | ) |
Safety switch/LED.
Definition at line 84 of file safety.c.
References arming_call, hrt_call_every(), and safety_check_button().
Referenced by user_start().
void schedule_reboot | ( | uint32_t | time_delta_usec | ) |
schedule a reboot
schedule a reboot
Definition at line 246 of file px4io.c.
References hrt_absolute_time(), and reboot_time.
Referenced by registers_set_one().
volatile uint8_t debug_level |
global debug level for isr_debug()
float dt |
Definition at line 73 of file px4io.c.
Referenced by vmount::OutputBase::_calculate_output_angles(), TECS::_update_speed_states(), PositionControl::_velocityController(), SmoothZTest::accelerateDownwardFromBrake(), SmoothZTest::accelerateUpwardFromBrake(), SmoothZTest::brakeDownward(), SmoothZTest::brakeUpward(), MavlinkRateLimiter::check(), ECL_YawController::control_bodyrate(), ECL_WheelController::control_bodyrate(), ECL_RollController::control_bodyrate(), ECL_PitchController::control_bodyrate(), RoverPositionControl::control_position(), FixedwingPositionControl::control_position(), RoverPositionControl::control_velocity(), detect_orientation(), Ekf2::filter_altitude_ellipsoid(), frsky_telemetry_thread_main(), TerrainEstimator::get_velocity(), Ekf::gps_is_good(), Ekf::initialiseCovariance(), main(), mixer_set_failsafe(), mixer_tick(), motor_ramp_thread_main(), perf_count(), perf_end(), perf_set_elapsed(), pid_calculate(), positionError(), TerrainEstimator::predict(), landing_target_estimator::KalmanFilter::predict(), Ekf::predictCovariance(), Integrator::put(), matrix::Quaternion< Type >::Quaternion(), Ekf::reset_imu_bias(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), AttitudeEstimatorQ::Run(), GPS::run(), BlockLocalPositionEstimator::Run(), ECL_L1_Pos_Controller::set_dt(), control::Block::setDt(), RateControl::setFeedForwardGain(), PositionControl::setHoverThrust(), EstimatorInterface::setIMUData(), Takeoff::setSpoolupTime(), uORB::DeviceMaster::showTop(), PrecLand::slewrate(), MatrixTest::squareMatrixTests(), Battery::sumDischarged(), control::SuperBlock::SuperBlock(), Mavlink::task_main(), FixedwingPositionControl::tecs_update_pitch_throttle(), TEST_F(), WindEstimator::update(), launchdetection::CatapultLaunchMethod::update(), landing_target_estimator::LandingTargetEstimator::update(), MavlinkStream::update(), AttitudeEstimatorQ::update(), FixedwingPositionControl::update_desired_altitude(), TECS::update_vehicle_state_estimates(), RateControl::updateIntegral(), ManualSmoothingXY::updateMaxVelocity(), MixingOutput::updateOutputSlewrate(), user_start(), and landing_target_estimator::KalmanFilter::~KalmanFilter().
output_limit_t pwm_limit |
Definition at line 71 of file px4io.c.
Referenced by mixer_callback(), and mixer_tick().
uint16_t r_page_actuators[] |
PAGE 2.
Post-mixed actuator values.
Definition at line 101 of file registers.c.
Referenced by mixer_tick(), and registers_get().
uint16_t r_page_adc[] |
uint16_t r_page_controls[] |
PAGE 101.
Control values from the FMU.
Definition at line 213 of file registers.c.
Referenced by mixer_callback(), registers_get(), and registers_set().
uint16_t r_page_direct_pwm[] |
PAGE 8.
RAW PWM values
Definition at line 148 of file registers.c.
Referenced by mixer_tick(), registers_get(), and registers_set().
uint16_t r_page_raw_rc_input[] |
PAGE 4.
Raw RC input
Definition at line 115 of file registers.c.
Referenced by controls_tick(), and registers_get().
uint16_t r_page_rc_input[] |
PAGE 5.
Scaled/routed RC input
Definition at line 130 of file registers.c.
Referenced by mixer_callback(), and registers_get().
uint16_t r_page_rc_input_config[] |
PAGE 103.
R/C channel input configuration.
Definition at line 224 of file registers.c.
Referenced by controls_init(), controls_tick(), registers_get(), and registers_set_one().
uint16_t r_page_servo_control_max[] |
PAGE 107.
maximum PWM values when armed
Definition at line 256 of file registers.c.
Referenced by mixer_set_failsafe(), mixer_tick(), MixerTest::mixerTest(), registers_get(), and registers_set().
uint16_t r_page_servo_control_min[] |
PAGE 106.
minimum PWM values when armed
Definition at line 248 of file registers.c.
Referenced by mixer_set_failsafe(), mixer_tick(), MixerTest::mixerTest(), registers_get(), and registers_set().
int16_t r_page_servo_control_trim[] |
PAGE 108.
trim values for center position
Definition at line 264 of file registers.c.
Referenced by mixer_tick(), registers_get(), and registers_set().
uint16_t r_page_servo_disarmed[] |
PAGE 109.
disarmed PWM values for difficult ESCs
Definition at line 272 of file registers.c.
Referenced by mixer_tick(), MixerTest::mixerTest(), registers_get(), and registers_set().
uint16_t r_page_servo_failsafe[] |
PAGE 105.
Failsafe servo PWM values
Disable pulses as default.
Definition at line 240 of file registers.c.
Referenced by mixer_set_failsafe(), mixer_tick(), registers_get(), and registers_set().
uint16_t r_page_servos[] |
PAGE 3.
Servo PWM values
Definition at line 108 of file registers.c.
Referenced by mixer_tick(), MixerTest::mixerTest(), and registers_get().
volatile uint16_t r_page_setup[] |
PAGE 100.
Setup registers
Definition at line 155 of file registers.c.
Referenced by calculate_fw_crc(), isr_debug(), registers_get(), registers_set_one(), and user_start().
volatile uint16_t r_page_status[] |
PAGE 1.
Status values.
Definition at line 85 of file registers.c.
Referenced by registers_get(), update_mem_usage(), and user_start().
struct sys_state_s system_state |
Definition at line 67 of file px4io.c.
Referenced by controls_init(), controls_tick(), mixer_tick(), registers_set(), and user_start().
bool update_mc_thrust_param |
Definition at line 60 of file registers.c.
Referenced by mixer_handle_text(), mixer_set_failsafe(), mixer_tick(), and registers_set_one().
bool update_trims |
Definition at line 61 of file registers.c.
Referenced by mixer_handle_text(), mixer_tick(), and registers_set().