You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
215 lines
3.6 KiB
215 lines
3.6 KiB
# |
|
# Message definitions for the ArduPilot Mega binary communications protocol. |
|
# |
|
# Process this file using: |
|
# |
|
# awk -f protogen.awk protocol.def > protocol.h |
|
# |
|
# Messages are declared with |
|
# |
|
# message <MESSAGE_ID> <MESSAGE_NAME> |
|
# |
|
# <MESSAGE_NAME> is a valid member of BinComm::MessageID. |
|
# <MESSAGE_ID> is the message ID byte |
|
# |
|
# Following a message declaration the fields of the message are |
|
# defined in the format: |
|
# |
|
# <TYPE> <NAME> [<COUNT>] |
|
# |
|
# <TYPE> is a C type corresponding to the field. The type must be a single |
|
# word, either an integer from <inttypes.h> or "char". |
|
# <NAME> is the name of the field; it should be unique within the message |
|
# <COUNT> is an optional array count for fields that are arrays |
|
# (note that currently there is only _pack support for character arrays) |
|
# |
|
|
|
# |
|
# Acknowledge message |
|
# |
|
message 0x00 MSG_ACKNOWLEDGE |
|
uint8_t msgID |
|
uint16_t msgSum |
|
|
|
# |
|
# System heartbeat |
|
# |
|
message 0x01 MSG_HEARTBEAT |
|
uint8_t flightMode |
|
uint16_t timeStamp |
|
uint16_t batteryVoltage |
|
uint16_t commandIndex |
|
|
|
# |
|
# Attitude report |
|
# |
|
message 0x02 MSG_ATTITUDE |
|
int16_t roll |
|
int16_t pitch |
|
int16_t yaw |
|
|
|
# |
|
# Location report |
|
# |
|
message 0x03 MSG_LOCATION |
|
int32_t latitude |
|
int32_t longitude |
|
int16_t altitude |
|
int16_t groundSpeed |
|
int16_t groundCourse |
|
uint16_t timeOfWeek |
|
|
|
# |
|
# Optional pressure-based location report |
|
# |
|
message 0x04 MSG_PRESSURE |
|
uint16_t pressureAltitude |
|
uint16_t airSpeed |
|
|
|
# |
|
# Text status message |
|
# |
|
message 0x05 MSG_STATUS_TEXT |
|
uint8_t severity |
|
char text 50 |
|
|
|
# |
|
# Algorithm performance report |
|
# |
|
message 0x06 MSG_PERF_REPORT |
|
uint32_t interval |
|
uint16_t mainLoopCycles |
|
uint8_t mainLoopTime |
|
uint8_t gyroSaturationCount |
|
uint8_t adcConstraintCount |
|
uint16_t imuHealth |
|
uint16_t gcsMessageCount |
|
|
|
# |
|
# System version messages |
|
# |
|
message 0x07 MSG_VERSION_REQUEST |
|
uint8_t systemType |
|
uint8_t systemID |
|
|
|
message 0x08 MSG_VERSION |
|
uint8_t systemType |
|
uint8_t systemID |
|
uint8_t firmwareVersion 3 |
|
|
|
# |
|
# Flight command operations |
|
# |
|
message 0x20 MSG_COMMAND_REQUEST |
|
uint16_t UNSPECIFIED |
|
|
|
message 0x21 MSG_COMMAND_UPLOAD |
|
uint8_t action |
|
uint16_t itemNumber |
|
int listLength |
|
uint8_t commandID |
|
uint8_t p1 |
|
uint16_t p2 |
|
uint32_t p3 |
|
uint32_t p4 |
|
|
|
message 0x22 MSG_COMMAND_LIST |
|
int itemNumber |
|
int listLength |
|
uint8_t commandID |
|
uint8_t p1 |
|
uint16_t p2 |
|
uint32_t p3 |
|
uint32_t p4 |
|
|
|
message 0x23 MSG_COMMAND_MODE_CHANGE |
|
uint16_t UNSPECIFIED |
|
|
|
# |
|
# Parameter operations |
|
# |
|
message 0x30 MSG_VALUE_REQUEST |
|
uint8_t valueID |
|
uint8_t broadcast |
|
|
|
|
|
message 0x31 MSG_VALUE_SET |
|
uint8_t valueID |
|
uint32_t value |
|
|
|
message 0x32 MSG_VALUE |
|
uint8_t valueID |
|
uint32_t value |
|
|
|
# |
|
# PID adjustments |
|
# |
|
message 0x40 MSG_PID_REQUEST |
|
uint8_t pidSet |
|
|
|
message 0x41 MSG_PID_SET |
|
uint8_t pidSet |
|
int32_t p |
|
int32_t i |
|
int32_t d |
|
int16_t integratorMax |
|
|
|
message 0x42 MSG_PID |
|
uint8_t pidSet |
|
int32_t p |
|
int32_t i |
|
int32_t d |
|
int16_t integratorMax |
|
|
|
|
|
# |
|
# Radio trim settings |
|
# |
|
message 0x50 MSG_TRIM_STARTUP |
|
uint16_t value 8 |
|
|
|
message 0x51 MSG_TRIM_MIN |
|
uint16_t value 8 |
|
|
|
message 0x52 MSG_TRIM_MAX |
|
uint16_t value 8 |
|
|
|
# |
|
# Direct sensor access |
|
# |
|
message 0x60 MSG_SENSOR |
|
uint16_t UNSPECIFIED |
|
|
|
# |
|
# Simulation-related messages |
|
# |
|
message 0x70 MSG_SIM |
|
uint16_t UNSPECIFIED |
|
|
|
# |
|
# Direct I/O pin control |
|
# |
|
message 0x80 MSG_PIN_REQUEST |
|
uint16_t UNSPECIFIED |
|
|
|
message 0x81 MSG_PIN_SET |
|
uint16_t UNSPECIFIED |
|
|
|
# |
|
# Dataflash operations |
|
# |
|
message 0x90 MSG_DATAFLASH_REQUEST |
|
uint16_t UNSPECIFIED |
|
|
|
message 0x91 MSG_DATAFLASH_SET |
|
uint16_t UNSPECIFIED |
|
|
|
# |
|
# EEPROM operations |
|
# |
|
message 0xa0 MSG_EEPROM_REQUEST |
|
uint16_t UNSPECIFIED |
|
|
|
message 0xa1 MSG_EEPROM_SET |
|
uint16_t UNSPECIFIED |
|
|
|
|