APM:Libraries
|
#include <inttypes.h>
Go to the source code of this file.
Classes | |
struct | px4io_mixdata |
struct | IOPacket |
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 |
#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 |
#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_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) |
#define | PX4IO_P_SETUP_FEATURES_SBUS2_OUT (1 << 1) |
#define | PX4IO_P_SETUP_FEATURES_PWM_RSSI (1 << 2) |
#define | PX4IO_P_SETUP_FEATURES_ADC_RSSI (1 << 3) |
#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 |
#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_PAGE_CONTROLS 51 |
#define | PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) |
#define | PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) |
#define | PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) |
#define | PX4IO_P_CONTROLS_GROUP_3 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3) |
#define | PX4IO_P_CONTROLS_GROUP_VALID 64 |
#define | PX4IO_P_CONTROLS_GROUP_VALID_GROUP0 (1 << 0) |
#define | PX4IO_P_CONTROLS_GROUP_VALID_GROUP1 (1 << 1) |
#define | PX4IO_P_CONTROLS_GROUP_VALID_GROUP2 (1 << 2) |
#define | PX4IO_P_CONTROLS_GROUP_VALID_GROUP3 (1 << 3) |
#define | PX4IO_PAGE_MIXERLOAD 52 |
#define | PX4IO_PAGE_RC_CONFIG 53 |
#define | PX4IO_P_RC_CONFIG_MIN 0 |
#define | PX4IO_P_RC_CONFIG_CENTER 1 |
#define | PX4IO_P_RC_CONFIG_MAX 2 |
#define | PX4IO_P_RC_CONFIG_DEADZONE 3 |
#define | PX4IO_P_RC_CONFIG_ASSIGNMENT 4 |
#define | PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH 100 |
#define | PX4IO_P_RC_CONFIG_OPTIONS 5 |
#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 |
#define | PX4IO_PAGE_DIRECT_PWM 54 |
#define | PX4IO_PAGE_FAILSAFE_PWM 55 |
#define | PX4IO_PAGE_SENSORS 56 |
#define | PX4IO_P_SENSORS_ALTITUDE 0 |
#define | PX4IO_PAGE_TEST 127 |
#define | PX4IO_P_TEST_LED 0 |
#define | PX4IO_PAGE_CONTROL_MIN_PWM 106 |
#define | PX4IO_PAGE_CONTROL_MAX_PWM 107 |
#define | PX4IO_PAGE_DISARMED_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */ |
#define | PX4IO_PAGE_UART_BUFFER 120 |
#define | F2I_MIXER_MAGIC 0x6d74 |
#define | F2I_MIXER_ACTION_RESET 0 |
#define | F2I_MIXER_ACTION_APPEND 1 |
#define | PKT_MAX_REGS 32 |
#define | PKT_CODE_READ 0x00 /* FMU->IO read transaction */ |
#define | PKT_CODE_WRITE 0x40 /* FMU->IO write transaction */ |
#define | PKT_CODE_SPIUART 0xC0 /* FMU<->IO spi-uart 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 const uint8_t crc8_tab [256] | __attribute__ ((unused)) |
static uint8_t | crc_packet (struct IOPacket *pkt) __attribute__((unused)) |
#define F2I_MIXER_ACTION_APPEND 1 |
Definition at line 299 of file px4io_protocol.h.
#define F2I_MIXER_ACTION_RESET 0 |
Definition at line 298 of file px4io_protocol.h.
#define F2I_MIXER_MAGIC 0x6d74 |
Definition at line 295 of file px4io_protocol.h.
#define FLOAT_TO_REG | ( | _float | ) | SIGNED_TO_REG((int16_t)((_float) * 10000.0f)) |
Definition at line 77 of file px4io_protocol.h.
#define PKT_CODE | ( | _p | ) | ((_p).count_code & PKT_CODE_MASK) |
Definition at line 332 of file px4io_protocol.h.
#define PKT_CODE_CORRUPT 0x40 /* IO->FMU bad packet reply */ |
Definition at line 325 of file px4io_protocol.h.
#define PKT_CODE_ERROR 0x80 /* IO->FMU register op error reply */ |
Definition at line 326 of file px4io_protocol.h.
#define PKT_CODE_MASK 0xc0 |
Definition at line 328 of file px4io_protocol.h.
#define PKT_CODE_READ 0x00 /* FMU->IO read transaction */ |
Definition at line 321 of file px4io_protocol.h.
#define PKT_CODE_SPIUART 0xC0 /* FMU<->IO spi-uart transaction */ |
Definition at line 323 of file px4io_protocol.h.
#define PKT_CODE_SUCCESS 0x00 /* IO->FMU success reply */ |
Definition at line 324 of file px4io_protocol.h.
#define PKT_CODE_WRITE 0x40 /* FMU->IO write transaction */ |
Definition at line 322 of file px4io_protocol.h.
#define PKT_COUNT | ( | _p | ) | ((_p).count_code & PKT_COUNT_MASK) |
Definition at line 331 of file px4io_protocol.h.
Referenced by crc_packet().
#define PKT_COUNT_MASK 0x3f |
Definition at line 329 of file px4io_protocol.h.
#define PKT_MAX_REGS 32 |
Serial protocol encapsulation.
Definition at line 309 of file px4io_protocol.h.
#define PKT_SIZE | ( | _p | ) | ((size_t)((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p)))) |
Definition at line 333 of file px4io_protocol.h.
#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */ |
Definition at line 229 of file px4io_protocol.h.
Definition at line 91 of file px4io_protocol.h.
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */ |
Definition at line 93 of file px4io_protocol.h.
#define PX4IO_P_CONFIG_BOOTLOADER_VERSION 2 /* get this how? */ |
Definition at line 88 of file px4io_protocol.h.
Definition at line 90 of file px4io_protocol.h.
#define PX4IO_P_CONFIG_CONTROL_GROUP_COUNT 8 |
hardcoded # of control groups
Definition at line 95 of file px4io_protocol.h.
#define PX4IO_P_CONFIG_HARDWARE_VERSION 1 /* magic numbers TBD */ |
Definition at line 87 of file px4io_protocol.h.
#define PX4IO_P_CONFIG_MAX_TRANSFER 3 /* maximum I2C transfer size */ |
Definition at line 89 of file px4io_protocol.h.
#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* PX4IO_PROTOCOL_VERSION */ |
Definition at line 86 of file px4io_protocol.h.
Definition at line 92 of file px4io_protocol.h.
#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */ |
Definition at line 94 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) |
0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1
Definition at line 233 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) |
0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1
Definition at line 234 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) |
0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1
Definition at line 235 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_3 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3) |
0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1
Definition at line 236 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_VALID 64 |
Definition at line 238 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP0 (1 << 0) |
group 0 is valid / received
Definition at line 239 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP1 (1 << 1) |
group 1 is valid / received
Definition at line 240 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP2 (1 << 2) |
group 2 is valid / received
Definition at line 241 of file px4io_protocol.h.
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP3 (1 << 3) |
group 3 is valid / received
Definition at line 242 of file px4io_protocol.h.
#define PX4IO_P_RAW_FRAME_COUNT 4 /* Number of total received frames (wrapping counter) */ |
Definition at line 154 of file px4io_protocol.h.
#define PX4IO_P_RAW_LOST_FRAME_COUNT 5 /* Number of total dropped frames (wrapping counter) */ |
Definition at line 155 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_BASE 6 /* CONFIG_RC_INPUT_COUNT channels from here */ |
Definition at line 156 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_COUNT 0 /* number of valid channels */ |
Definition at line 144 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_DATA 3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */ |
Definition at line 153 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_FLAGS 1 /* RC detail status flags */ |
Definition at line 145 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 1) /* receiver is in failsafe mode */ |
Definition at line 147 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP (1 << 0) /* single frame drop */ |
Definition at line 146 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK (1 << 3) /* Channel mapping is ok */ |
Definition at line 149 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11 (1 << 2) /* DSM decoding is 11 bit mode */ |
Definition at line 148 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_FLAGS_RC_OK (1 << 4) /* RC reception ok */ |
Definition at line 150 of file px4io_protocol.h.
#define PX4IO_P_RAW_RC_NRSSI 2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */ |
Definition at line 152 of file px4io_protocol.h.
#define PX4IO_P_RC_BASE 1 /* CONFIG_RC_INPUT_COUNT controls from here */ |
Definition at line 161 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 |
mapped input value
Definition at line 253 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH 100 |
magic value for mode switch
Definition at line 254 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_CENTER 1 |
center input value
Definition at line 250 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_DEADZONE 3 |
band around center that is ignored
Definition at line 252 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_MAX 2 |
highest input value
Definition at line 251 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_MIN 0 |
lowest input value
Definition at line 249 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_OPTIONS 5 |
channel options bitmask
Definition at line 255 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0) |
Definition at line 256 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1) |
Definition at line 257 of file px4io_protocol.h.
#define PX4IO_P_RC_CONFIG_STRIDE 6 |
spacing between channel config data
Definition at line 258 of file px4io_protocol.h.
#define PX4IO_P_RC_VALID 0 /* bitmask of valid controls */ |
Definition at line 160 of file px4io_protocol.h.
#define PX4IO_P_SENSORS_ALTITUDE 0 |
Altitude of an external sensor (HoTT or S.BUS2)
Definition at line 268 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING 1 /* arming controls */ |
Definition at line 178 of file px4io_protocol.h.
#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 184 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */ |
Definition at line 182 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */ |
Definition at line 180 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 8) /* If set, the system will always output the failsafe values */ |
Definition at line 187 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */ |
Definition at line 183 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */ |
Definition at line 179 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */ |
Definition at line 186 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */ |
Definition at line 181 of file px4io_protocol.h.
#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 189 of file px4io_protocol.h.
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 6) /* Disable the IO-internal evaluation of the RC */ |
Definition at line 185 of file px4io_protocol.h.
#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 188 of file px4io_protocol.h.
#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */ |
Definition at line 221 of file px4io_protocol.h.
#define PX4IO_P_SETUP_DSM 7 /* DSM bind state */ |
Definition at line 207 of file px4io_protocol.h.
#define PX4IO_P_SETUP_FEATURES 0 |
Definition at line 172 of file px4io_protocol.h.
#define PX4IO_P_SETUP_FEATURES_ADC_RSSI (1 << 3) |
enable ADC RSSI parsing
Definition at line 176 of file px4io_protocol.h.
#define PX4IO_P_SETUP_FEATURES_PWM_RSSI (1 << 2) |
enable PWM RSSI parsing
Definition at line 175 of file px4io_protocol.h.
#define PX4IO_P_SETUP_FEATURES_SBUS1_OUT (1 << 0) |
enable S.Bus v1 output
Definition at line 173 of file px4io_protocol.h.
#define PX4IO_P_SETUP_FEATURES_SBUS2_OUT (1 << 1) |
enable S.Bus v2 output
Definition at line 174 of file px4io_protocol.h.
#define PX4IO_P_SETUP_FORCE_SAFETY_OFF |
Definition at line 223 of file px4io_protocol.h.
#define PX4IO_P_SETUP_FORCE_SAFETY_ON 14 /* force safety switch into 'disarmed' (PWM disabled state) */ |
Definition at line 228 of file px4io_protocol.h.
#define PX4IO_P_SETUP_PWM_ALTRATE 4 /* 'high' PWM frame output rate in Hz */ |
Definition at line 193 of file px4io_protocol.h.
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */ |
Definition at line 192 of file px4io_protocol.h.
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */ |
Definition at line 191 of file px4io_protocol.h.
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 |
the throttle failsafe pulse length in microseconds
Definition at line 226 of file px4io_protocol.h.
#define PX4IO_P_SETUP_REBOOT_BL 10 /* reboot IO into bootloader */ |
Definition at line 218 of file px4io_protocol.h.
#define PX4IO_P_SETUP_RELAYS_PAD 5 |
Definition at line 202 of file px4io_protocol.h.
#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */ |
Definition at line 216 of file px4io_protocol.h.
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* hardware rev [1] battery voltage correction factor (float) */ |
Definition at line 205 of file px4io_protocol.h.
#define PX4IO_P_SETUP_VSERVO_SCALE 6 /* hardware rev [2] servo voltage correction factor (float) */ |
Definition at line 206 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */ |
Definition at line 120 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT (1 << 3) /* [1] accessory current limit was exceeded */ |
Definition at line 124 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS_FMU_LOST (1 << 4) /* timed out waiting for controls from FMU */ |
Definition at line 125 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS_PWM_ERROR (1 << 6) /* PWM configuration or output was bad */ |
Definition at line 127 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 5) /* timed out waiting for RC input */ |
Definition at line 126 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT (1 << 2) /* [1] servo current limit was exceeded */ |
Definition at line 123 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS_TEMPERATURE (1 << 1) /* board temperature is high */ |
Definition at line 122 of file px4io_protocol.h.
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */ |
Definition at line 121 of file px4io_protocol.h.
#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 128 of file px4io_protocol.h.
#define PX4IO_P_STATUS_CPULOAD 1 |
Definition at line 100 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS 2 /* monitoring flags */ |
Definition at line 102 of file px4io_protocol.h.
Definition at line 112 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */ |
Definition at line 114 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 13) /* FMU was initialized and OK once */ |
Definition at line 116 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_FMU_OK (1 << 6) /* controls from FMU are valid */ |
Definition at line 109 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */ |
Definition at line 113 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */ |
Definition at line 111 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED (1 << 0) /* arm-ok and locally armed */ |
Definition at line 103 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_OVERRIDE (1 << 1) /* in manual override */ |
Definition at line 104 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_RAW_PWM (1 << 7) /* raw PWM from FMU is bypassing the mixer */ |
Definition at line 110 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_RC_DSM (1 << 4) /* DSM input is valid */ |
Definition at line 107 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 2) /* RC input is valid */ |
Definition at line 105 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 3) /* PPM input is valid */ |
Definition at line 106 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_RC_SBUS (1 << 5) /* SBUS input is valid */ |
Definition at line 108 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_RC_ST24 (1 << 14) /* ST24 input is valid */ |
Definition at line 117 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_RC_SUMD (1 << 15) /* SUMD input is valid */ |
Definition at line 118 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 12) /* safety is off */ |
Definition at line 115 of file px4io_protocol.h.
#define PX4IO_P_STATUS_FREEMEM 0 |
Definition at line 99 of file px4io_protocol.h.
#define PX4IO_P_STATUS_IBATT 5 /* [1] battery current (raw ADC) */ |
Definition at line 131 of file px4io_protocol.h.
Definition at line 134 of file px4io_protocol.h.
#define PX4IO_P_STATUS_VBATT 4 /* [1] battery voltage in mV */ |
Definition at line 130 of file px4io_protocol.h.
#define PX4IO_P_STATUS_VRSSI 7 /* [2] RSSI voltage */ |
Definition at line 133 of file px4io_protocol.h.
#define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */ |
Definition at line 132 of file px4io_protocol.h.
#define PX4IO_P_TEST_LED 0 |
set the amber LED on/off
Definition at line 272 of file px4io_protocol.h.
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */ |
Definition at line 137 of file px4io_protocol.h.
#define PX4IO_PAGE_CONFIG 0 |
Definition at line 85 of file px4io_protocol.h.
#define PX4IO_PAGE_CONTROL_MAX_PWM 107 |
0..CONFIG_ACTUATOR_COUNT-1
Definition at line 278 of file px4io_protocol.h.
#define PX4IO_PAGE_CONTROL_MIN_PWM 106 |
0..CONFIG_ACTUATOR_COUNT-1
Definition at line 275 of file px4io_protocol.h.
#define PX4IO_PAGE_CONTROLS 51 |
actuator control groups, one after the other, 8 wide
Definition at line 232 of file px4io_protocol.h.
#define PX4IO_PAGE_DIRECT_PWM 54 |
0..CONFIG_ACTUATOR_COUNT-1
Definition at line 261 of file px4io_protocol.h.
#define PX4IO_PAGE_DISARMED_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */ |
Definition at line 281 of file px4io_protocol.h.
#define PX4IO_PAGE_FAILSAFE_PWM 55 |
0..CONFIG_ACTUATOR_COUNT-1
Definition at line 264 of file px4io_protocol.h.
#define PX4IO_PAGE_MIXERLOAD 52 |
Definition at line 245 of file px4io_protocol.h.
#define PX4IO_PAGE_PWM_INFO 7 |
Definition at line 167 of file px4io_protocol.h.
#define PX4IO_PAGE_RAW_ADC_INPUT 6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */ |
Definition at line 164 of file px4io_protocol.h.
#define PX4IO_PAGE_RAW_RC_INPUT 4 |
Definition at line 143 of file px4io_protocol.h.
#define PX4IO_PAGE_RC_CONFIG 53 |
R/C input configuration
Definition at line 248 of file px4io_protocol.h.
#define PX4IO_PAGE_RC_INPUT 5 |
Definition at line 159 of file px4io_protocol.h.
#define PX4IO_PAGE_SENSORS 56 |
Sensors connected to PX4IO
Definition at line 267 of file px4io_protocol.h.
#define PX4IO_PAGE_SERVOS 3 /* 0..CONFIG_ACTUATOR_COUNT-1 */ |
Definition at line 140 of file px4io_protocol.h.
#define PX4IO_PAGE_SETUP 50 |
Definition at line 171 of file px4io_protocol.h.
#define PX4IO_PAGE_STATUS 1 |
Definition at line 98 of file px4io_protocol.h.
#define PX4IO_PAGE_TEST 127 |
Definition at line 271 of file px4io_protocol.h.
#define PX4IO_PAGE_UART_BUFFER 120 |
Definition at line 284 of file px4io_protocol.h.
#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 82 of file px4io_protocol.h.
#define PX4IO_PROTOCOL_VERSION 4 |
Definition at line 79 of file px4io_protocol.h.
#define PX4IO_RATE_MAP_BASE 0 /* 0..CONFIG_ACTUATOR_COUNT bitmaps of PWM rate groups */ |
Definition at line 168 of file px4io_protocol.h.
#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */ |
Definition at line 219 of file px4io_protocol.h.
#define REG_TO_FLOAT | ( | _reg | ) | ((float)REG_TO_SIGNED(_reg) / 10000.0f) |
Definition at line 76 of file px4io_protocol.h.
#define REG_TO_SIGNED | ( | _reg | ) | ((int16_t)(_reg)) |
Definition at line 73 of file px4io_protocol.h.
#define SIGNED_TO_REG | ( | _signed | ) | ((uint16_t)(_signed)) |
Definition at line 74 of file px4io_protocol.h.
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 208 of file px4io_protocol.h.
|
static |
|
static |
Definition at line 373 of file px4io_protocol.h.