PX4 Firmware
PX4 Autopilot Software http://px4.io
px4io.h File Reference

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>
Include dependency graph for px4io.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  sys_state_s
 

Macros

#define perf_alloc(a, b)   NULL
 
#define PX4IO_BL_VERSION   3
 
#define PX4IO_SERVO_COUNT   8
 
#define PX4IO_CONTROL_CHANNELS   8
 
#define PX4IO_CONTROL_GROUPS   4
 
#define PX4IO_RC_INPUT_CHANNELS   18
 
#define PX4IO_RC_MAPPED_CONTROL_CHANNELS   8
 This is the maximum number of channels mapped/used. More...
 
#define debug(fmt, args...)   do {} while(0)
 
#define r_status_flags   r_page_status[PX4IO_P_STATUS_FLAGS]
 
#define r_status_alarms   r_page_status[PX4IO_P_STATUS_ALARMS]
 
#define r_raw_rc_count   r_page_raw_rc_input[PX4IO_P_RAW_RC_COUNT]
 
#define r_raw_rc_values   (&r_page_raw_rc_input[PX4IO_P_RAW_RC_BASE])
 
#define r_raw_rc_flags   r_page_raw_rc_input[PX4IO_P_RAW_RC_FLAGS]
 
#define r_rc_valid   r_page_rc_input[PX4IO_P_RC_VALID]
 
#define r_rc_values   (&r_page_rc_input[PX4IO_P_RC_BASE])
 
#define r_mixer_limits   r_page_status[PX4IO_P_STATUS_MIXER]
 
#define r_setup_features   r_page_setup[PX4IO_P_SETUP_FEATURES]
 
#define r_setup_arming   r_page_setup[PX4IO_P_SETUP_ARMING]
 
#define r_setup_pwm_rates   r_page_setup[PX4IO_P_SETUP_PWM_RATES]
 
#define r_setup_pwm_defaultrate   r_page_setup[PX4IO_P_SETUP_PWM_DEFAULTRATE]
 
#define r_setup_pwm_altrate   r_page_setup[PX4IO_P_SETUP_PWM_ALTRATE]
 
#define r_setup_rc_thr_failsafe   r_page_setup[PX4IO_P_SETUP_RC_THR_FAILSAFE_US]
 
#define r_setup_pwm_reverse   r_page_setup[PX4IO_P_SETUP_PWM_REVERSE]
 
#define r_setup_trim_roll   r_page_setup[PX4IO_P_SETUP_TRIM_ROLL]
 
#define r_setup_trim_pitch   r_page_setup[PX4IO_P_SETUP_TRIM_PITCH]
 
#define r_setup_trim_yaw   r_page_setup[PX4IO_P_SETUP_TRIM_YAW]
 
#define r_setup_scale_roll   r_page_setup[PX4IO_P_SETUP_SCALE_ROLL]
 
#define r_setup_scale_pitch   r_page_setup[PX4IO_P_SETUP_SCALE_PITCH]
 
#define r_setup_scale_yaw   r_page_setup[PX4IO_P_SETUP_SCALE_YAW]
 
#define r_setup_sbus_rate   r_page_setup[PX4IO_P_SETUP_SBUS_RATE]
 
#define r_setup_thr_fac   r_page_setup[PX4IO_P_SETUP_THR_MDL_FAC]
 
#define r_setup_slew_max   r_page_setup[PX4IO_P_SETUP_MOTOR_SLEW_MAX]
 
#define r_setup_airmode   r_page_setup[PX4IO_P_SETUP_AIRMODE]
 
#define r_setup_flighttermination   r_page_setup[PX4IO_P_SETUP_ENABLE_FLIGHTTERMINATION]
 
#define r_control_values   (&r_page_controls[0])
 
#define LED_BLUE(_s)   px4_arch_gpiowrite(GPIO_LED1, !(_s))
 
#define LED_AMBER(_s)   px4_arch_gpiowrite(GPIO_LED2, !(_s))
 
#define LED_SAFETY(_s)   px4_arch_gpiowrite(GPIO_LED3, !(_s))
 
#define LED_RING(_s)   px4_arch_gpiowrite(GPIO_LED4, (_s))
 
#define PX4IO_RELAY_CHANNELS   0
 
#define ENABLE_SBUS_OUT(_s)   px4_arch_gpiowrite(GPIO_SBUS_OENABLE, !(_s))
 
#define VDD_SERVO_FAULT   (!px4_arch_gpioread(GPIO_SERVO_FAULT_DETECT))
 
#define PX4IO_ADC_CHANNEL_COUNT   2
 
#define ADC_VSERVO   4
 
#define ADC_RSSI   5
 
#define BUTTON_SAFETY   px4_arch_gpioread(GPIO_BTN_SAFETY)
 
#define CONTROL_PAGE_INDEX(_group, _channel)   (_group * PX4IO_CONTROL_CHANNELS + _channel)
 
#define PX4_CRITICAL_SECTION(cmd)   { irqstate_t flags = px4_enter_critical_section(); cmd; px4_leave_critical_section(flags); }
 

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...
 

Detailed Description

General defines and structures for the PX4IO module firmware.

Author
Lorenz Meier loren.nosp@m.z@px.nosp@m.4.io

Definition in file px4io.h.

Macro Definition Documentation

◆ ADC_RSSI

#define ADC_RSSI   5

Definition at line 181 of file px4io.h.

Referenced by controls_tick(), and registers_get().

◆ ADC_VSERVO

#define ADC_VSERVO   4

Definition at line 180 of file px4io.h.

Referenced by registers_get().

◆ BUTTON_SAFETY

#define BUTTON_SAFETY   px4_arch_gpioread(GPIO_BTN_SAFETY)

Definition at line 183 of file px4io.h.

Referenced by safety_check_button().

◆ CONTROL_PAGE_INDEX

#define CONTROL_PAGE_INDEX (   _group,
  _channel 
)    (_group * PX4IO_CONTROL_CHANNELS + _channel)

Definition at line 185 of file px4io.h.

Referenced by mixer_callback().

◆ debug

#define debug (   fmt,
  args... 
)    do {} while(0)

Definition at line 79 of file px4io.h.

◆ ENABLE_SBUS_OUT

#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().

◆ LED_AMBER

#define LED_AMBER (   _s)    px4_arch_gpiowrite(GPIO_LED2, !(_s))

Definition at line 169 of file px4io.h.

◆ LED_BLUE

#define LED_BLUE (   _s)    px4_arch_gpiowrite(GPIO_LED1, !(_s))

Definition at line 168 of file px4io.h.

◆ LED_RING

#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().

◆ LED_SAFETY

#define LED_SAFETY (   _s)    px4_arch_gpiowrite(GPIO_LED3, !(_s))

Definition at line 170 of file px4io.h.

◆ perf_alloc

◆ PX4_CRITICAL_SECTION

#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().

◆ PX4IO_ADC_CHANNEL_COUNT

#define PX4IO_ADC_CHANNEL_COUNT   2

Definition at line 179 of file px4io.h.

◆ PX4IO_BL_VERSION

#define PX4IO_BL_VERSION   3

Definition at line 64 of file px4io.h.

◆ PX4IO_CONTROL_CHANNELS

#define PX4IO_CONTROL_CHANNELS   8

Definition at line 66 of file px4io.h.

Referenced by controls_tick(), mixer_callback(), and registers_set().

◆ PX4IO_CONTROL_GROUPS

#define PX4IO_CONTROL_GROUPS   4

Definition at line 67 of file px4io.h.

Referenced by mixer_callback(), and registers_set().

◆ PX4IO_RC_INPUT_CHANNELS

#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().

◆ PX4IO_RC_MAPPED_CONTROL_CHANNELS

#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().

◆ PX4IO_RELAY_CHANNELS

#define PX4IO_RELAY_CHANNELS   0

Definition at line 174 of file px4io.h.

◆ PX4IO_SERVO_COUNT

#define PX4IO_SERVO_COUNT   8

◆ r_control_values

#define r_control_values   (&r_page_controls[0])

Definition at line 138 of file px4io.h.

◆ r_mixer_limits

#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().

◆ r_raw_rc_count

#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().

◆ r_raw_rc_flags

#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().

◆ r_raw_rc_values

#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().

◆ r_rc_valid

#define r_rc_valid   r_page_rc_input[PX4IO_P_RC_VALID]

Definition at line 113 of file px4io.h.

Referenced by controls_tick().

◆ r_rc_values

#define r_rc_values   (&r_page_rc_input[PX4IO_P_RC_BASE])

Definition at line 114 of file px4io.h.

Referenced by controls_tick().

◆ r_setup_airmode

#define r_setup_airmode   r_page_setup[PX4IO_P_SETUP_AIRMODE]

Definition at line 135 of file px4io.h.

Referenced by mixer_tick().

◆ r_setup_arming

◆ r_setup_features

#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().

◆ r_setup_flighttermination

#define r_setup_flighttermination   r_page_setup[PX4IO_P_SETUP_ENABLE_FLIGHTTERMINATION]

Definition at line 136 of file px4io.h.

Referenced by mixer_tick().

◆ r_setup_pwm_altrate

#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().

◆ r_setup_pwm_defaultrate

#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().

◆ r_setup_pwm_rates

#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().

◆ r_setup_pwm_reverse

#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().

◆ r_setup_rc_thr_failsafe

#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().

◆ r_setup_sbus_rate

#define r_setup_sbus_rate   r_page_setup[PX4IO_P_SETUP_SBUS_RATE]

Definition at line 132 of file px4io.h.

◆ r_setup_scale_pitch

#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().

◆ r_setup_scale_roll

#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().

◆ r_setup_scale_yaw

#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().

◆ r_setup_slew_max

#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().

◆ r_setup_thr_fac

#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().

◆ r_setup_trim_pitch

#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().

◆ r_setup_trim_roll

#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().

◆ r_setup_trim_yaw

#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().

◆ r_status_alarms

#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().

◆ r_status_flags

◆ VDD_SERVO_FAULT

#define VDD_SERVO_FAULT   (!px4_arch_gpioread(GPIO_SERVO_FAULT_DETECT))

Definition at line 177 of file px4io.h.

Function Documentation

◆ adc_init()

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().

Here is the caller graph for this function:

◆ adc_measure()

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().

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

◆ atomic_modify_and()

void atomic_modify_and ( volatile uint16_t *  target,
uint16_t  modification 
)

Definition at line 109 of file px4io.c.

References PX4_CRITICAL_SECTION.

◆ atomic_modify_clear()

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().

Here is the caller graph for this function:

◆ atomic_modify_or()

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().

Here is the caller graph for this function:

◆ controls_init()

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().

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

◆ controls_tick()

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().

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

◆ failsafe_led_init()

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().

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

◆ interface_init()

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().

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

◆ interface_tick()

void interface_tick ( void  )

◆ isr_debug()

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().

Here is the caller graph for this function:

◆ mixer_handle_text()

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().

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

◆ mixer_handle_text_create_mixer()

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().

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

◆ mixer_set_failsafe()

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().

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

◆ mixer_tick()

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().

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

◆ registers_get()

◆ registers_set()

int registers_set ( uint8_t  page,
uint8_t  offset,
const uint16_t *  values,
unsigned  num_values 
)

◆ safety_init()

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().

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

◆ schedule_reboot()

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().

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

Variable Documentation

◆ debug_level

volatile uint8_t debug_level

global debug level for isr_debug()

◆ dt

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().

◆ pwm_limit

output_limit_t pwm_limit

Definition at line 71 of file px4io.c.

Referenced by mixer_callback(), and mixer_tick().

◆ r_page_actuators

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().

◆ r_page_adc

uint16_t r_page_adc[]

◆ r_page_controls

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().

◆ r_page_direct_pwm

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().

◆ r_page_raw_rc_input

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().

◆ r_page_rc_input

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().

◆ r_page_rc_input_config

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().

◆ r_page_servo_control_max

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().

◆ r_page_servo_control_min

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().

◆ r_page_servo_control_trim

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().

◆ r_page_servo_disarmed

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().

◆ r_page_servo_failsafe

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().

◆ r_page_servos

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().

◆ r_page_setup

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().

◆ r_page_status

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().

◆ system_state

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().

◆ update_mc_thrust_param

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().

◆ update_trims

bool update_trims

Definition at line 61 of file registers.c.

Referenced by mixer_handle_text(), mixer_tick(), and registers_set().