Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
protocol.h File Reference
#include "std.h"
+ Include dependency graph for protocol.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Data Structures

struct  px4io_mixdata
 As-needed mixer data upload. More...
 
struct  IOPacket
 

Macros

#define __STDC_FORMAT_MACROS
 
#define REG_TO_SIGNED(_reg)   ((int16_t)(_reg))
 
#define SIGNED_TO_REG(_signed)   ((uint16_t)(_signed))
 
#define REG_TO_FLOAT(_reg)   ((float)REG_TO_SIGNED(_reg) / 10000.0f)
 
#define FLOAT_TO_REG(_float)   SIGNED_TO_REG((int16_t)((_float) * 10000.0f))
 
#define PX4IO_PROTOCOL_VERSION   4
 
#define PX4IO_PROTOCOL_MAX_CONTROL_COUNT   8
 The protocol does not support more than set here, individual units might support less - see PX4IO_P_CONFIG_CONTROL_COUNT. More...
 
#define PX4IO_PAGE_CONFIG   0
 
#define PX4IO_P_CONFIG_PROTOCOL_VERSION   0 /* PX4IO_PROTOCOL_VERSION */
 
#define PX4IO_P_CONFIG_HARDWARE_VERSION   1 /* magic numbers TBD */
 
#define PX4IO_P_CONFIG_BOOTLOADER_VERSION   2 /* get this how? */
 
#define PX4IO_P_CONFIG_MAX_TRANSFER   3 /* maximum I2C transfer size */
 
#define PX4IO_P_CONFIG_CONTROL_COUNT   4 /* hardcoded max control count supported */
 
#define PX4IO_P_CONFIG_ACTUATOR_COUNT   5 /* hardcoded max actuator output count */
 
#define PX4IO_P_CONFIG_RC_INPUT_COUNT   6 /* hardcoded max R/C input count supported */
 
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT   7 /* hardcoded max ADC inputs */
 
#define PX4IO_P_CONFIG_RELAY_COUNT   8 /* hardcoded # of relay outputs */
 
#define PX4IO_P_CONFIG_CONTROL_GROUP_COUNT   8
 hardcoded # of control groups More...
 
#define PX4IO_PAGE_STATUS   1
 
#define PX4IO_P_STATUS_FREEMEM   0
 
#define PX4IO_P_STATUS_CPULOAD   1
 
#define PX4IO_P_STATUS_FLAGS   2 /* monitoring flags */
 
#define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED   (1 << 0) /* arm-ok and locally armed */
 
#define PX4IO_P_STATUS_FLAGS_OVERRIDE   (1 << 1) /* in manual override */
 
#define PX4IO_P_STATUS_FLAGS_RC_OK   (1 << 2) /* RC input is valid */
 
#define PX4IO_P_STATUS_FLAGS_RC_PPM   (1 << 3) /* PPM input is valid */
 
#define PX4IO_P_STATUS_FLAGS_RC_DSM   (1 << 4) /* DSM input is valid */
 
#define PX4IO_P_STATUS_FLAGS_RC_SBUS   (1 << 5) /* SBUS input is valid */
 
#define PX4IO_P_STATUS_FLAGS_FMU_OK   (1 << 6) /* controls from FMU are valid */
 
#define PX4IO_P_STATUS_FLAGS_RAW_PWM   (1 << 7) /* raw PWM from FMU is bypassing the mixer */
 
#define PX4IO_P_STATUS_FLAGS_MIXER_OK   (1 << 8) /* mixer is OK */
 
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC   (1 << 9) /* the arming state between IO and FMU is in sync */
 
#define PX4IO_P_STATUS_FLAGS_INIT_OK   (1 << 10) /* initialisation of the IO completed without error */
 
#define PX4IO_P_STATUS_FLAGS_FAILSAFE   (1 << 11) /* failsafe is active */
 
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF   (1 << 12) /* safety is off */
 
#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED   (1 << 13) /* FMU was initialized and OK once */
 
#define PX4IO_P_STATUS_FLAGS_RC_ST24   (1 << 14) /* ST24 input is valid */
 
#define PX4IO_P_STATUS_FLAGS_RC_SUMD   (1 << 15) /* SUMD input is valid */
 
#define PX4IO_P_STATUS_ALARMS   3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
 
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW   (1 << 0) /* [1] VBatt is very close to regulator dropout */
 
#define PX4IO_P_STATUS_ALARMS_TEMPERATURE   (1 << 1) /* board temperature is high */
 
#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT   (1 << 2) /* [1] servo current limit was exceeded */
 
#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT   (1 << 3) /* [1] accessory current limit was exceeded */
 
#define PX4IO_P_STATUS_ALARMS_FMU_LOST   (1 << 4) /* timed out waiting for controls from FMU */
 
#define PX4IO_P_STATUS_ALARMS_RC_LOST   (1 << 5) /* timed out waiting for RC input */
 
#define PX4IO_P_STATUS_ALARMS_PWM_ERROR   (1 << 6) /* PWM configuration or output was bad */
 
#define PX4IO_P_STATUS_ALARMS_VSERVO_FAULT   (1 << 7) /* [2] VServo was out of the valid range (2.5 - 5.5 V) */
 
#define PX4IO_P_STATUS_VBATT   4 /* [1] battery voltage in mV */
 
#define PX4IO_P_STATUS_IBATT   5 /* [1] battery current (raw ADC) */
 
#define PX4IO_P_STATUS_VSERVO   6 /* [2] servo rail voltage in mV */
 
#define PX4IO_P_STATUS_VRSSI   7 /* [2] RSSI voltage */
 
#define PX4IO_P_STATUS_PRSSI   8 /* [2] RSSI PWM value */
 
#define PX4IO_P_STATUS_MIXER   9 /* mixer actuator limit flags */
 
#define PX4IO_P_STATUS_MIXER_LOWER_LIMIT   (1 << 0)
 at least one actuator output has reached lower limit More...
 
#define PX4IO_P_STATUS_MIXER_UPPER_LIMIT   (1 << 1)
 at least one actuator output has reached upper limit More...
 
#define PX4IO_P_STATUS_MIXER_YAW_LIMIT   (1 << 2)
 yaw control is limited because it causes output clipping More...
 
#define PX4IO_PAGE_ACTUATORS   2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
 
#define PX4IO_PAGE_SERVOS   3 /* 0..CONFIG_ACTUATOR_COUNT-1 */
 
#define PX4IO_PAGE_RAW_RC_INPUT   4
 
#define PX4IO_P_RAW_RC_COUNT   0 /* number of valid channels */
 
#define PX4IO_P_RAW_RC_FLAGS   1 /* RC detail status flags */
 
#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP   (1 << 0) /* single frame drop */
 
#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE   (1 << 1) /* receiver is in failsafe mode */
 
#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11   (1 << 2) /* DSM decoding is 11 bit mode */
 
#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK   (1 << 3) /* Channel mapping is ok */
 
#define PX4IO_P_RAW_RC_FLAGS_RC_OK   (1 << 4) /* RC reception ok */
 
#define PX4IO_P_RAW_RC_NRSSI   2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
 
#define PX4IO_P_RAW_RC_DATA   3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
 
#define PX4IO_P_RAW_FRAME_COUNT   4 /* Number of total received frames (wrapping counter) */
 
#define PX4IO_P_RAW_LOST_FRAME_COUNT   5 /* Number of total dropped frames (wrapping counter) */
 
#define PX4IO_P_RAW_RC_BASE   6 /* CONFIG_RC_INPUT_COUNT channels from here */
 
#define PX4IO_PAGE_RC_INPUT   5
 
#define PX4IO_P_RC_VALID   0 /* bitmask of valid controls */
 
#define PX4IO_P_RC_BASE   1 /* CONFIG_RC_INPUT_COUNT controls from here */
 
#define PX4IO_PAGE_RAW_ADC_INPUT   6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */
 
#define PX4IO_PAGE_PWM_INFO   7
 
#define PX4IO_RATE_MAP_BASE   0 /* 0..CONFIG_ACTUATOR_COUNT bitmaps of PWM rate groups */
 
#define PX4IO_PAGE_SETUP   50
 
#define PX4IO_P_SETUP_FEATURES   0
 
#define PX4IO_P_SETUP_FEATURES_SBUS1_OUT   (1 << 0)
 enable S.Bus v1 output More...
 
#define PX4IO_P_SETUP_FEATURES_SBUS2_OUT   (1 << 1)
 enable S.Bus v2 output More...
 
#define PX4IO_P_SETUP_FEATURES_PWM_RSSI   (1 << 2)
 enable PWM RSSI parsing More...
 
#define PX4IO_P_SETUP_FEATURES_ADC_RSSI   (1 << 3)
 enable ADC RSSI parsing More...
 
#define PX4IO_P_SETUP_ARMING   1 /* arming controls */
 
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK   (1 << 0) /* OK to arm the IO side */
 
#define PX4IO_P_SETUP_ARMING_FMU_ARMED   (1 << 1) /* FMU is already armed */
 
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK   (1 << 2) /* OK to switch to manual override via override RC channel */
 
#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM   (1 << 3) /* use custom failsafe values, not 0 values of mixer */
 
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK   (1 << 4) /* OK to try in-air restart */
 
#define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE   (1 << 5) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */
 
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED   (1 << 6) /* Disable the IO-internal evaluation of the RC */
 
#define PX4IO_P_SETUP_ARMING_LOCKDOWN   (1 << 7) /* If set, the system operates normally, but won't actuate any servos */
 
#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE   (1 << 8) /* If set, the system will always output the failsafe values */
 
#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE   (1 << 9) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */
 
#define PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE   (1 << 10) /* If set then on FMU failure override is immediate. Othewise it waits for the mode switch to go past the override thrshold */
 
#define PX4IO_P_SETUP_PWM_RATES   2 /* bitmask, 0 = low rate, 1 = high rate */
 
#define PX4IO_P_SETUP_PWM_DEFAULTRATE   3 /* 'low' PWM frame output rate in Hz */
 
#define PX4IO_P_SETUP_PWM_ALTRATE   4 /* 'high' PWM frame output rate in Hz */
 
#define PX4IO_P_SETUP_RELAYS_PAD   5
 
#define PX4IO_P_SETUP_VBATT_SCALE   6 /* hardware rev [1] battery voltage correction factor (float) */
 
#define PX4IO_P_SETUP_VSERVO_SCALE   6 /* hardware rev [2] servo voltage correction factor (float) */
 
#define PX4IO_P_SETUP_DSM   7 /* DSM bind state */
 
#define PX4IO_P_SETUP_SET_DEBUG   9 /* debug level for IO board */
 
#define PX4IO_P_SETUP_REBOOT_BL   10 /* reboot IO into bootloader */
 
#define PX4IO_REBOOT_BL_MAGIC   14662 /* required argument for reboot (random) */
 
#define PX4IO_P_SETUP_CRC   11 /* get CRC of IO firmware */
 
#define PX4IO_P_SETUP_FORCE_SAFETY_OFF
 
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US   13
 the throttle failsafe pulse length in microseconds More...
 
#define PX4IO_P_SETUP_FORCE_SAFETY_ON   14 /* force safety switch into 'disarmed' (PWM disabled state) */
 
#define PX4IO_FORCE_SAFETY_MAGIC   22027 /* required argument for force safety (random) */
 
#define PX4IO_P_SETUP_PWM_REVERSE   15
 Bitmask to reverse PWM channels 1-8. More...
 
#define PX4IO_P_SETUP_TRIM_ROLL   16
 Roll trim, in actuator units. More...
 
#define PX4IO_P_SETUP_TRIM_PITCH   17
 Pitch trim, in actuator units. More...
 
#define PX4IO_P_SETUP_TRIM_YAW   18
 Yaw trim, in actuator units. More...
 
#define PX4IO_PAGE_CONTROLS   51
 actuator control groups, one after the other, 8 wide More...
 
#define PX4IO_P_CONTROLS_GROUP_0   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0)
 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 More...
 
#define PX4IO_P_CONTROLS_GROUP_1   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1)
 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 More...
 
#define PX4IO_P_CONTROLS_GROUP_2   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2)
 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 More...
 
#define PX4IO_P_CONTROLS_GROUP_3   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3)
 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 More...
 
#define PX4IO_P_CONTROLS_GROUP_VALID   64
 
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP0   (1 << 0)
 group 0 is valid / received More...
 
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP1   (1 << 1)
 group 1 is valid / received More...
 
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP2   (1 << 2)
 group 2 is valid / received More...
 
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP3   (1 << 3)
 group 3 is valid / received More...
 
#define PX4IO_PAGE_MIXERLOAD   52
 
#define PX4IO_PAGE_RC_CONFIG   53
 R/C input configuration. More...
 
#define PX4IO_P_RC_CONFIG_MIN   0
 lowest input value More...
 
#define PX4IO_P_RC_CONFIG_CENTER   1
 center input value More...
 
#define PX4IO_P_RC_CONFIG_MAX   2
 highest input value More...
 
#define PX4IO_P_RC_CONFIG_DEADZONE   3
 band around center that is ignored More...
 
#define PX4IO_P_RC_CONFIG_ASSIGNMENT   4
 mapped input value More...
 
#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH   100
 magic value for mode switch More...
 
#define PX4IO_P_RC_CONFIG_OPTIONS   5
 channel options bitmask More...
 
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED   (1 << 0)
 
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE   (1 << 1)
 
#define PX4IO_P_RC_CONFIG_STRIDE   6
 spacing between channel config data More...
 
#define PX4IO_PAGE_DIRECT_PWM   54
 0..CONFIG_ACTUATOR_COUNT-1 More...
 
#define PX4IO_PAGE_FAILSAFE_PWM   55
 0..CONFIG_ACTUATOR_COUNT-1 More...
 
#define PX4IO_PAGE_SENSORS   56
 Sensors connected to PX4IO. More...
 
#define PX4IO_P_SENSORS_ALTITUDE   0
 Altitude of an external sensor (HoTT or S.BUS2) More...
 
#define PX4IO_PAGE_TEST   127
 
#define PX4IO_P_TEST_LED   0
 set the amber LED on/off More...
 
#define PX4IO_PAGE_CONTROL_MIN_PWM   106
 0..CONFIG_ACTUATOR_COUNT-1 More...
 
#define PX4IO_PAGE_CONTROL_MAX_PWM   107
 0..CONFIG_ACTUATOR_COUNT-1 More...
 
#define PX4IO_PAGE_DISARMED_PWM   108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
 
#define F2I_MIXER_MAGIC   0x6d74
 
#define F2I_MIXER_ACTION_RESET   0
 
#define F2I_MIXER_ACTION_APPEND   1
 
#define PKT_MAX_REGS   32
 Serial protocol encapsulation. More...
 
#define PKT_CODE_READ   0x00 /* FMU->IO read transaction */
 
#define PKT_CODE_WRITE   0x40 /* FMU->IO write transaction */
 
#define PKT_CODE_SUCCESS   0x00 /* IO->FMU success reply */
 
#define PKT_CODE_CORRUPT   0x40 /* IO->FMU bad packet reply */
 
#define PKT_CODE_ERROR   0x80 /* IO->FMU register op error reply */
 
#define PKT_CODE_MASK   0xc0
 
#define PKT_COUNT_MASK   0x3f
 
#define PKT_COUNT(_p)   ((_p).count_code & PKT_COUNT_MASK)
 
#define PKT_CODE(_p)   ((_p).count_code & PKT_CODE_MASK)
 
#define PKT_SIZE(_p)   ((size_t)((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p))))
 

Enumerations

enum  {
  dsm_bind_power_down = 0, dsm_bind_power_up, dsm_bind_set_rx_out, dsm_bind_send_pulses,
  dsm_bind_reinit_uart
}
 

Functions

static uint8_t crc_packet (struct IOPacket *pkt)
 

Variables

static const uint8_t crc8_tab [256]
 

Detailed Description

PX4IO interface protocol.

Communication is performed via writes to and reads from 16-bit virtual registers organised into pages of 255 registers each.

The first two bytes of each write select a page and offset address respectively. Subsequent reads and writes increment the offset within the page.

Some pages are read- or write-only.

Note that some pages may permit offset values greater than 255, which can only be achieved by long writes. The offset does not wrap.

Writes to unimplemented registers are ignored. Reads from unimplemented registers return undefined values.

As convention, values that would be floating point in other parts of the PX4 system are expressed as signed integer values scaled by 10000, e.g. control values range from -10000..10000. Use the REG_TO_SIGNED and SIGNED_TO_REG macros to convert between register representation and the signed version, and REG_TO_FLOAT/FLOAT_TO_REG to convert to float.

Note that the implementation of readable pages prefers registers within readable pages to be densely packed. Page numbers do not need to be packed.

Definitions marked [1] are only valid on PX4IOv1 boards. Likewise, [2] denotes definitions specific to the PX4IOv2 board.

Definition in file protocol.h.


Data Structure Documentation

◆ px4io_mixdata

struct px4io_mixdata

As-needed mixer data upload.

This message adds text to the mixer text buffer; the text buffer is drained as the definitions are consumed.

Definition at line 299 of file protocol.h.

Data Fields
uint8_t action
uint16_t f2i_mixer_magic
char text[0]

◆ IOPacket

struct IOPacket

Definition at line 318 of file protocol.h.

Data Fields
uint8_t count_code
uint8_t crc
uint8_t offset
uint8_t page
uint16_t regs[PKT_MAX_REGS]

Macro Definition Documentation

◆ __STDC_FORMAT_MACROS

#define __STDC_FORMAT_MACROS

Definition at line 36 of file protocol.h.

◆ F2I_MIXER_ACTION_APPEND

#define F2I_MIXER_ACTION_APPEND   1

Definition at line 305 of file protocol.h.

◆ F2I_MIXER_ACTION_RESET

#define F2I_MIXER_ACTION_RESET   0

Definition at line 304 of file protocol.h.

◆ F2I_MIXER_MAGIC

#define F2I_MIXER_MAGIC   0x6d74

Definition at line 301 of file protocol.h.

◆ FLOAT_TO_REG

#define FLOAT_TO_REG (   _float)    SIGNED_TO_REG((int16_t)((_float) * 10000.0f))

Definition at line 78 of file protocol.h.

◆ PKT_CODE

#define PKT_CODE (   _p)    ((_p).count_code & PKT_CODE_MASK)

Definition at line 337 of file protocol.h.

◆ PKT_CODE_CORRUPT

#define PKT_CODE_CORRUPT   0x40 /* IO->FMU bad packet reply */

Definition at line 330 of file protocol.h.

◆ PKT_CODE_ERROR

#define PKT_CODE_ERROR   0x80 /* IO->FMU register op error reply */

Definition at line 331 of file protocol.h.

◆ PKT_CODE_MASK

#define PKT_CODE_MASK   0xc0

Definition at line 333 of file protocol.h.

◆ PKT_CODE_READ

#define PKT_CODE_READ   0x00 /* FMU->IO read transaction */

Definition at line 327 of file protocol.h.

◆ PKT_CODE_SUCCESS

#define PKT_CODE_SUCCESS   0x00 /* IO->FMU success reply */

Definition at line 329 of file protocol.h.

◆ PKT_CODE_WRITE

#define PKT_CODE_WRITE   0x40 /* FMU->IO write transaction */

Definition at line 328 of file protocol.h.

◆ PKT_COUNT

#define PKT_COUNT (   _p)    ((_p).count_code & PKT_COUNT_MASK)

Definition at line 336 of file protocol.h.

◆ PKT_COUNT_MASK

#define PKT_COUNT_MASK   0x3f

Definition at line 334 of file protocol.h.

◆ PKT_MAX_REGS

#define PKT_MAX_REGS   32

Serial protocol encapsulation.

Definition at line 315 of file protocol.h.

◆ PKT_SIZE

#define PKT_SIZE (   _p)    ((size_t)((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p))))

Definition at line 338 of file protocol.h.

◆ PX4IO_FORCE_SAFETY_MAGIC

#define PX4IO_FORCE_SAFETY_MAGIC   22027 /* required argument for force safety (random) */

Definition at line 233 of file protocol.h.

◆ PX4IO_P_CONFIG_ACTUATOR_COUNT

#define PX4IO_P_CONFIG_ACTUATOR_COUNT   5 /* hardcoded max actuator output count */

Definition at line 92 of file protocol.h.

◆ PX4IO_P_CONFIG_ADC_INPUT_COUNT

#define PX4IO_P_CONFIG_ADC_INPUT_COUNT   7 /* hardcoded max ADC inputs */

Definition at line 94 of file protocol.h.

◆ PX4IO_P_CONFIG_BOOTLOADER_VERSION

#define PX4IO_P_CONFIG_BOOTLOADER_VERSION   2 /* get this how? */

Definition at line 89 of file protocol.h.

◆ PX4IO_P_CONFIG_CONTROL_COUNT

#define PX4IO_P_CONFIG_CONTROL_COUNT   4 /* hardcoded max control count supported */

Definition at line 91 of file protocol.h.

◆ PX4IO_P_CONFIG_CONTROL_GROUP_COUNT

#define PX4IO_P_CONFIG_CONTROL_GROUP_COUNT   8

hardcoded # of control groups

Definition at line 96 of file protocol.h.

◆ PX4IO_P_CONFIG_HARDWARE_VERSION

#define PX4IO_P_CONFIG_HARDWARE_VERSION   1 /* magic numbers TBD */

Definition at line 88 of file protocol.h.

◆ PX4IO_P_CONFIG_MAX_TRANSFER

#define PX4IO_P_CONFIG_MAX_TRANSFER   3 /* maximum I2C transfer size */

Definition at line 90 of file protocol.h.

◆ PX4IO_P_CONFIG_PROTOCOL_VERSION

#define PX4IO_P_CONFIG_PROTOCOL_VERSION   0 /* PX4IO_PROTOCOL_VERSION */

Definition at line 87 of file protocol.h.

◆ PX4IO_P_CONFIG_RC_INPUT_COUNT

#define PX4IO_P_CONFIG_RC_INPUT_COUNT   6 /* hardcoded max R/C input count supported */

Definition at line 93 of file protocol.h.

◆ PX4IO_P_CONFIG_RELAY_COUNT

#define PX4IO_P_CONFIG_RELAY_COUNT   8 /* hardcoded # of relay outputs */

Definition at line 95 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_0

#define PX4IO_P_CONTROLS_GROUP_0   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0)

0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1

Definition at line 242 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_1

#define PX4IO_P_CONTROLS_GROUP_1   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1)

0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1

Definition at line 243 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_2

#define PX4IO_P_CONTROLS_GROUP_2   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2)

0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1

Definition at line 244 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_3

#define PX4IO_P_CONTROLS_GROUP_3   (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3)

0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1

Definition at line 245 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_VALID

#define PX4IO_P_CONTROLS_GROUP_VALID   64

Definition at line 247 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_VALID_GROUP0

#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP0   (1 << 0)

group 0 is valid / received

Definition at line 248 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_VALID_GROUP1

#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP1   (1 << 1)

group 1 is valid / received

Definition at line 249 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_VALID_GROUP2

#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP2   (1 << 2)

group 2 is valid / received

Definition at line 250 of file protocol.h.

◆ PX4IO_P_CONTROLS_GROUP_VALID_GROUP3

#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP3   (1 << 3)

group 3 is valid / received

Definition at line 251 of file protocol.h.

◆ PX4IO_P_RAW_FRAME_COUNT

#define PX4IO_P_RAW_FRAME_COUNT   4 /* Number of total received frames (wrapping counter) */

Definition at line 160 of file protocol.h.

◆ PX4IO_P_RAW_LOST_FRAME_COUNT

#define PX4IO_P_RAW_LOST_FRAME_COUNT   5 /* Number of total dropped frames (wrapping counter) */

Definition at line 161 of file protocol.h.

◆ PX4IO_P_RAW_RC_BASE

#define PX4IO_P_RAW_RC_BASE   6 /* CONFIG_RC_INPUT_COUNT channels from here */

Definition at line 162 of file protocol.h.

◆ PX4IO_P_RAW_RC_COUNT

#define PX4IO_P_RAW_RC_COUNT   0 /* number of valid channels */

Definition at line 150 of file protocol.h.

◆ PX4IO_P_RAW_RC_DATA

#define PX4IO_P_RAW_RC_DATA   3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */

Definition at line 159 of file protocol.h.

◆ PX4IO_P_RAW_RC_FLAGS

#define PX4IO_P_RAW_RC_FLAGS   1 /* RC detail status flags */

Definition at line 151 of file protocol.h.

◆ PX4IO_P_RAW_RC_FLAGS_FAILSAFE

#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE   (1 << 1) /* receiver is in failsafe mode */

Definition at line 153 of file protocol.h.

◆ PX4IO_P_RAW_RC_FLAGS_FRAME_DROP

#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP   (1 << 0) /* single frame drop */

Definition at line 152 of file protocol.h.

◆ PX4IO_P_RAW_RC_FLAGS_MAPPING_OK

#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK   (1 << 3) /* Channel mapping is ok */

Definition at line 155 of file protocol.h.

◆ PX4IO_P_RAW_RC_FLAGS_RC_DSM11

#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11   (1 << 2) /* DSM decoding is 11 bit mode */

Definition at line 154 of file protocol.h.

◆ PX4IO_P_RAW_RC_FLAGS_RC_OK

#define PX4IO_P_RAW_RC_FLAGS_RC_OK   (1 << 4) /* RC reception ok */

Definition at line 156 of file protocol.h.

◆ PX4IO_P_RAW_RC_NRSSI

#define PX4IO_P_RAW_RC_NRSSI   2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */

Definition at line 158 of file protocol.h.

◆ PX4IO_P_RC_BASE

#define PX4IO_P_RC_BASE   1 /* CONFIG_RC_INPUT_COUNT controls from here */

Definition at line 167 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_ASSIGNMENT

#define PX4IO_P_RC_CONFIG_ASSIGNMENT   4

mapped input value

Definition at line 262 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH

#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH   100

magic value for mode switch

Definition at line 263 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_CENTER

#define PX4IO_P_RC_CONFIG_CENTER   1

center input value

Definition at line 259 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_DEADZONE

#define PX4IO_P_RC_CONFIG_DEADZONE   3

band around center that is ignored

Definition at line 261 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_MAX

#define PX4IO_P_RC_CONFIG_MAX   2

highest input value

Definition at line 260 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_MIN

#define PX4IO_P_RC_CONFIG_MIN   0

lowest input value

Definition at line 258 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_OPTIONS

#define PX4IO_P_RC_CONFIG_OPTIONS   5

channel options bitmask

Definition at line 264 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_OPTIONS_ENABLED

#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED   (1 << 0)

Definition at line 265 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_OPTIONS_REVERSE

#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE   (1 << 1)

Definition at line 266 of file protocol.h.

◆ PX4IO_P_RC_CONFIG_STRIDE

#define PX4IO_P_RC_CONFIG_STRIDE   6

spacing between channel config data

Definition at line 267 of file protocol.h.

◆ PX4IO_P_RC_VALID

#define PX4IO_P_RC_VALID   0 /* bitmask of valid controls */

Definition at line 166 of file protocol.h.

◆ PX4IO_P_SENSORS_ALTITUDE

#define PX4IO_P_SENSORS_ALTITUDE   0

Altitude of an external sensor (HoTT or S.BUS2)

Definition at line 277 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING

#define PX4IO_P_SETUP_ARMING   1 /* arming controls */

Definition at line 184 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE

#define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE   (1 << 5) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */

Definition at line 190 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM

#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM   (1 << 3) /* use custom failsafe values, not 0 values of mixer */

Definition at line 188 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_FMU_ARMED

#define PX4IO_P_SETUP_ARMING_FMU_ARMED   (1 << 1) /* FMU is already armed */

Definition at line 186 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE

#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE   (1 << 8) /* If set, the system will always output the failsafe values */

Definition at line 193 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK

#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK   (1 << 4) /* OK to try in-air restart */

Definition at line 189 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_IO_ARM_OK

#define PX4IO_P_SETUP_ARMING_IO_ARM_OK   (1 << 0) /* OK to arm the IO side */

Definition at line 185 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_LOCKDOWN

#define PX4IO_P_SETUP_ARMING_LOCKDOWN   (1 << 7) /* If set, the system operates normally, but won't actuate any servos */

Definition at line 192 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK

#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK   (1 << 2) /* OK to switch to manual override via override RC channel */

Definition at line 187 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE

#define PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE   (1 << 10) /* If set then on FMU failure override is immediate. Othewise it waits for the mode switch to go past the override thrshold */

Definition at line 195 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED

#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED   (1 << 6) /* Disable the IO-internal evaluation of the RC */

Definition at line 191 of file protocol.h.

◆ PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE

#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE   (1 << 9) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */

Definition at line 194 of file protocol.h.

◆ PX4IO_P_SETUP_CRC

#define PX4IO_P_SETUP_CRC   11 /* get CRC of IO firmware */

Definition at line 227 of file protocol.h.

◆ PX4IO_P_SETUP_DSM

#define PX4IO_P_SETUP_DSM   7 /* DSM bind state */

Definition at line 213 of file protocol.h.

◆ PX4IO_P_SETUP_FEATURES

#define PX4IO_P_SETUP_FEATURES   0

Definition at line 178 of file protocol.h.

◆ PX4IO_P_SETUP_FEATURES_ADC_RSSI

#define PX4IO_P_SETUP_FEATURES_ADC_RSSI   (1 << 3)

enable ADC RSSI parsing

Definition at line 182 of file protocol.h.

◆ PX4IO_P_SETUP_FEATURES_PWM_RSSI

#define PX4IO_P_SETUP_FEATURES_PWM_RSSI   (1 << 2)

enable PWM RSSI parsing

Definition at line 181 of file protocol.h.

◆ PX4IO_P_SETUP_FEATURES_SBUS1_OUT

#define PX4IO_P_SETUP_FEATURES_SBUS1_OUT   (1 << 0)

enable S.Bus v1 output

Definition at line 179 of file protocol.h.

◆ PX4IO_P_SETUP_FEATURES_SBUS2_OUT

#define PX4IO_P_SETUP_FEATURES_SBUS2_OUT   (1 << 1)

enable S.Bus v2 output

Definition at line 180 of file protocol.h.

◆ PX4IO_P_SETUP_FORCE_SAFETY_OFF

#define PX4IO_P_SETUP_FORCE_SAFETY_OFF
Value:
12 /* force safety switch into
'armed' (PWM enabled) state - this is a non-data write and
hence index 12 can safely be used. */

Definition at line 229 of file protocol.h.

◆ PX4IO_P_SETUP_FORCE_SAFETY_ON

#define PX4IO_P_SETUP_FORCE_SAFETY_ON   14 /* force safety switch into 'disarmed' (PWM disabled state) */

Definition at line 232 of file protocol.h.

◆ PX4IO_P_SETUP_PWM_ALTRATE

#define PX4IO_P_SETUP_PWM_ALTRATE   4 /* 'high' PWM frame output rate in Hz */

Definition at line 199 of file protocol.h.

◆ PX4IO_P_SETUP_PWM_DEFAULTRATE

#define PX4IO_P_SETUP_PWM_DEFAULTRATE   3 /* 'low' PWM frame output rate in Hz */

Definition at line 198 of file protocol.h.

◆ PX4IO_P_SETUP_PWM_RATES

#define PX4IO_P_SETUP_PWM_RATES   2 /* bitmask, 0 = low rate, 1 = high rate */

Definition at line 197 of file protocol.h.

◆ PX4IO_P_SETUP_PWM_REVERSE

#define PX4IO_P_SETUP_PWM_REVERSE   15

Bitmask to reverse PWM channels 1-8.

Definition at line 235 of file protocol.h.

◆ PX4IO_P_SETUP_RC_THR_FAILSAFE_US

#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US   13

the throttle failsafe pulse length in microseconds

Definition at line 230 of file protocol.h.

◆ PX4IO_P_SETUP_REBOOT_BL

#define PX4IO_P_SETUP_REBOOT_BL   10 /* reboot IO into bootloader */

Definition at line 224 of file protocol.h.

◆ PX4IO_P_SETUP_RELAYS_PAD

#define PX4IO_P_SETUP_RELAYS_PAD   5

Definition at line 208 of file protocol.h.

◆ PX4IO_P_SETUP_SET_DEBUG

#define PX4IO_P_SETUP_SET_DEBUG   9 /* debug level for IO board */

Definition at line 222 of file protocol.h.

◆ PX4IO_P_SETUP_TRIM_PITCH

#define PX4IO_P_SETUP_TRIM_PITCH   17

Pitch trim, in actuator units.

Definition at line 237 of file protocol.h.

◆ PX4IO_P_SETUP_TRIM_ROLL

#define PX4IO_P_SETUP_TRIM_ROLL   16

Roll trim, in actuator units.

Definition at line 236 of file protocol.h.

◆ PX4IO_P_SETUP_TRIM_YAW

#define PX4IO_P_SETUP_TRIM_YAW   18

Yaw trim, in actuator units.

Definition at line 238 of file protocol.h.

◆ PX4IO_P_SETUP_VBATT_SCALE

#define PX4IO_P_SETUP_VBATT_SCALE   6 /* hardware rev [1] battery voltage correction factor (float) */

Definition at line 211 of file protocol.h.

◆ PX4IO_P_SETUP_VSERVO_SCALE

#define PX4IO_P_SETUP_VSERVO_SCALE   6 /* hardware rev [2] servo voltage correction factor (float) */

Definition at line 212 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS

#define PX4IO_P_STATUS_ALARMS   3 /* alarm flags - alarms latch, write 1 to a bit to clear it */

Definition at line 121 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_ACC_CURRENT

#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT   (1 << 3) /* [1] accessory current limit was exceeded */

Definition at line 125 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_FMU_LOST

#define PX4IO_P_STATUS_ALARMS_FMU_LOST   (1 << 4) /* timed out waiting for controls from FMU */

Definition at line 126 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_PWM_ERROR

#define PX4IO_P_STATUS_ALARMS_PWM_ERROR   (1 << 6) /* PWM configuration or output was bad */

Definition at line 128 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_RC_LOST

#define PX4IO_P_STATUS_ALARMS_RC_LOST   (1 << 5) /* timed out waiting for RC input */

Definition at line 127 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_SERVO_CURRENT

#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT   (1 << 2) /* [1] servo current limit was exceeded */

Definition at line 124 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_TEMPERATURE

#define PX4IO_P_STATUS_ALARMS_TEMPERATURE   (1 << 1) /* board temperature is high */

Definition at line 123 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_VBATT_LOW

#define PX4IO_P_STATUS_ALARMS_VBATT_LOW   (1 << 0) /* [1] VBatt is very close to regulator dropout */

Definition at line 122 of file protocol.h.

◆ PX4IO_P_STATUS_ALARMS_VSERVO_FAULT

#define PX4IO_P_STATUS_ALARMS_VSERVO_FAULT   (1 << 7) /* [2] VServo was out of the valid range (2.5 - 5.5 V) */

Definition at line 129 of file protocol.h.

◆ PX4IO_P_STATUS_CPULOAD

#define PX4IO_P_STATUS_CPULOAD   1

Definition at line 101 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS

#define PX4IO_P_STATUS_FLAGS   2 /* monitoring flags */

Definition at line 103 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_ARM_SYNC

#define PX4IO_P_STATUS_FLAGS_ARM_SYNC   (1 << 9) /* the arming state between IO and FMU is in sync */

Definition at line 113 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_FAILSAFE

#define PX4IO_P_STATUS_FLAGS_FAILSAFE   (1 << 11) /* failsafe is active */

Definition at line 115 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED

#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED   (1 << 13) /* FMU was initialized and OK once */

Definition at line 117 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_FMU_OK

#define PX4IO_P_STATUS_FLAGS_FMU_OK   (1 << 6) /* controls from FMU are valid */

Definition at line 110 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_INIT_OK

#define PX4IO_P_STATUS_FLAGS_INIT_OK   (1 << 10) /* initialisation of the IO completed without error */

Definition at line 114 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_MIXER_OK

#define PX4IO_P_STATUS_FLAGS_MIXER_OK   (1 << 8) /* mixer is OK */

Definition at line 112 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED

#define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED   (1 << 0) /* arm-ok and locally armed */

Definition at line 104 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_OVERRIDE

#define PX4IO_P_STATUS_FLAGS_OVERRIDE   (1 << 1) /* in manual override */

Definition at line 105 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_RAW_PWM

#define PX4IO_P_STATUS_FLAGS_RAW_PWM   (1 << 7) /* raw PWM from FMU is bypassing the mixer */

Definition at line 111 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_RC_DSM

#define PX4IO_P_STATUS_FLAGS_RC_DSM   (1 << 4) /* DSM input is valid */

Definition at line 108 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_RC_OK

#define PX4IO_P_STATUS_FLAGS_RC_OK   (1 << 2) /* RC input is valid */

Definition at line 106 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_RC_PPM

#define PX4IO_P_STATUS_FLAGS_RC_PPM   (1 << 3) /* PPM input is valid */

Definition at line 107 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_RC_SBUS

#define PX4IO_P_STATUS_FLAGS_RC_SBUS   (1 << 5) /* SBUS input is valid */

Definition at line 109 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_RC_ST24

#define PX4IO_P_STATUS_FLAGS_RC_ST24   (1 << 14) /* ST24 input is valid */

Definition at line 118 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_RC_SUMD

#define PX4IO_P_STATUS_FLAGS_RC_SUMD   (1 << 15) /* SUMD input is valid */

Definition at line 119 of file protocol.h.

◆ PX4IO_P_STATUS_FLAGS_SAFETY_OFF

#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF   (1 << 12) /* safety is off */

Definition at line 116 of file protocol.h.

◆ PX4IO_P_STATUS_FREEMEM

#define PX4IO_P_STATUS_FREEMEM   0

Definition at line 100 of file protocol.h.

◆ PX4IO_P_STATUS_IBATT

#define PX4IO_P_STATUS_IBATT   5 /* [1] battery current (raw ADC) */

Definition at line 132 of file protocol.h.

◆ PX4IO_P_STATUS_MIXER

#define PX4IO_P_STATUS_MIXER   9 /* mixer actuator limit flags */

Definition at line 137 of file protocol.h.

◆ PX4IO_P_STATUS_MIXER_LOWER_LIMIT

#define PX4IO_P_STATUS_MIXER_LOWER_LIMIT   (1 << 0)

at least one actuator output has reached lower limit

Definition at line 138 of file protocol.h.

◆ PX4IO_P_STATUS_MIXER_UPPER_LIMIT

#define PX4IO_P_STATUS_MIXER_UPPER_LIMIT   (1 << 1)

at least one actuator output has reached upper limit

Definition at line 139 of file protocol.h.

◆ PX4IO_P_STATUS_MIXER_YAW_LIMIT

#define PX4IO_P_STATUS_MIXER_YAW_LIMIT   (1 << 2)

yaw control is limited because it causes output clipping

Definition at line 140 of file protocol.h.

◆ PX4IO_P_STATUS_PRSSI

#define PX4IO_P_STATUS_PRSSI   8 /* [2] RSSI PWM value */

Definition at line 135 of file protocol.h.

◆ PX4IO_P_STATUS_VBATT

#define PX4IO_P_STATUS_VBATT   4 /* [1] battery voltage in mV */

Definition at line 131 of file protocol.h.

◆ PX4IO_P_STATUS_VRSSI

#define PX4IO_P_STATUS_VRSSI   7 /* [2] RSSI voltage */

Definition at line 134 of file protocol.h.

◆ PX4IO_P_STATUS_VSERVO

#define PX4IO_P_STATUS_VSERVO   6 /* [2] servo rail voltage in mV */

Definition at line 133 of file protocol.h.

◆ PX4IO_P_TEST_LED

#define PX4IO_P_TEST_LED   0

set the amber LED on/off

Definition at line 281 of file protocol.h.

◆ PX4IO_PAGE_ACTUATORS

#define PX4IO_PAGE_ACTUATORS   2 /* 0..CONFIG_ACTUATOR_COUNT-1 */

Definition at line 143 of file protocol.h.

◆ PX4IO_PAGE_CONFIG

#define PX4IO_PAGE_CONFIG   0

Definition at line 86 of file protocol.h.

◆ PX4IO_PAGE_CONTROL_MAX_PWM

#define PX4IO_PAGE_CONTROL_MAX_PWM   107

0..CONFIG_ACTUATOR_COUNT-1

Definition at line 287 of file protocol.h.

◆ PX4IO_PAGE_CONTROL_MIN_PWM

#define PX4IO_PAGE_CONTROL_MIN_PWM   106

0..CONFIG_ACTUATOR_COUNT-1

Definition at line 284 of file protocol.h.

◆ PX4IO_PAGE_CONTROLS

#define PX4IO_PAGE_CONTROLS   51

actuator control groups, one after the other, 8 wide

Definition at line 241 of file protocol.h.

◆ PX4IO_PAGE_DIRECT_PWM

#define PX4IO_PAGE_DIRECT_PWM   54

0..CONFIG_ACTUATOR_COUNT-1

Definition at line 270 of file protocol.h.

◆ PX4IO_PAGE_DISARMED_PWM

#define PX4IO_PAGE_DISARMED_PWM   108 /* 0..CONFIG_ACTUATOR_COUNT-1 */

Definition at line 290 of file protocol.h.

◆ PX4IO_PAGE_FAILSAFE_PWM

#define PX4IO_PAGE_FAILSAFE_PWM   55

0..CONFIG_ACTUATOR_COUNT-1

Definition at line 273 of file protocol.h.

◆ PX4IO_PAGE_MIXERLOAD

#define PX4IO_PAGE_MIXERLOAD   52

Definition at line 254 of file protocol.h.

◆ PX4IO_PAGE_PWM_INFO

#define PX4IO_PAGE_PWM_INFO   7

Definition at line 173 of file protocol.h.

◆ PX4IO_PAGE_RAW_ADC_INPUT

#define PX4IO_PAGE_RAW_ADC_INPUT   6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */

Definition at line 170 of file protocol.h.

◆ PX4IO_PAGE_RAW_RC_INPUT

#define PX4IO_PAGE_RAW_RC_INPUT   4

Definition at line 149 of file protocol.h.

◆ PX4IO_PAGE_RC_CONFIG

#define PX4IO_PAGE_RC_CONFIG   53

R/C input configuration.

Definition at line 257 of file protocol.h.

◆ PX4IO_PAGE_RC_INPUT

#define PX4IO_PAGE_RC_INPUT   5

Definition at line 165 of file protocol.h.

◆ PX4IO_PAGE_SENSORS

#define PX4IO_PAGE_SENSORS   56

Sensors connected to PX4IO.

Definition at line 276 of file protocol.h.

◆ PX4IO_PAGE_SERVOS

#define PX4IO_PAGE_SERVOS   3 /* 0..CONFIG_ACTUATOR_COUNT-1 */

Definition at line 146 of file protocol.h.

◆ PX4IO_PAGE_SETUP

#define PX4IO_PAGE_SETUP   50

Definition at line 177 of file protocol.h.

◆ PX4IO_PAGE_STATUS

#define PX4IO_PAGE_STATUS   1

Definition at line 99 of file protocol.h.

◆ PX4IO_PAGE_TEST

#define PX4IO_PAGE_TEST   127

Definition at line 280 of file protocol.h.

◆ PX4IO_PROTOCOL_MAX_CONTROL_COUNT

#define PX4IO_PROTOCOL_MAX_CONTROL_COUNT   8

The protocol does not support more than set here, individual units might support less - see PX4IO_P_CONFIG_CONTROL_COUNT.

Definition at line 83 of file protocol.h.

◆ PX4IO_PROTOCOL_VERSION

#define PX4IO_PROTOCOL_VERSION   4

Definition at line 80 of file protocol.h.

◆ PX4IO_RATE_MAP_BASE

#define PX4IO_RATE_MAP_BASE   0 /* 0..CONFIG_ACTUATOR_COUNT bitmaps of PWM rate groups */

Definition at line 174 of file protocol.h.

◆ PX4IO_REBOOT_BL_MAGIC

#define PX4IO_REBOOT_BL_MAGIC   14662 /* required argument for reboot (random) */

Definition at line 225 of file protocol.h.

◆ REG_TO_FLOAT

#define REG_TO_FLOAT (   _reg)    ((float)REG_TO_SIGNED(_reg) / 10000.0f)

Definition at line 77 of file protocol.h.

◆ REG_TO_SIGNED

#define REG_TO_SIGNED (   _reg)    ((int16_t)(_reg))

Definition at line 74 of file protocol.h.

◆ SIGNED_TO_REG

#define SIGNED_TO_REG (   _signed)    ((uint16_t)(_signed))

Definition at line 75 of file protocol.h.

Enumeration Type Documentation

◆ anonymous enum

anonymous enum
Enumerator
dsm_bind_power_down 
dsm_bind_power_up 
dsm_bind_set_rx_out 
dsm_bind_send_pulses 
dsm_bind_reinit_uart 

Definition at line 214 of file protocol.h.

Function Documentation

◆ crc_packet()

static uint8_t crc_packet ( struct IOPacket pkt)
static

Definition at line 377 of file protocol.h.

Referenced by px4flash_event().

+ Here is the caller graph for this function:

Variable Documentation

◆ crc8_tab

const uint8_t crc8_tab[256]
static

Definition at line 340 of file protocol.h.