ardupilot/libraries/APM_BinComm/protocol/protocol.def

280 lines
5.6 KiB
Modula-2

#
# Message definitions for the ArduPilot Mega binary communications protocol.
#
# Process this file to generate protocol.h, using:
#
# awk -f protogen.awk protocol.def > protocol.h
#
# Messages are declared with
#
# message <MESSAGE_ID> <MESSAGE_NAME>
#
# <MESSAGE_NAME> is a unique name by which the message will
# be known.
#
# <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
#
# Each message causes the definition of several items in the APM_BinComm
# class. Note that <MESSAGE_NAME> is uppercase, and <message_name> is
# lowercase.
#
# BinComm::<MESSAGE_NAME>
#
# An enumeration with the value <MESSAGE_ID>
#
# BinComm::<message_name>
#
# A structure which corresponds to the layout of the message payload.
# In a message reception callout function the messageData pointer can
# be cast to this type to directly access specific elements of the
# message. Do not modify fields in the structure in this case.
#
# BinComm::send_<message_name>(<TYPE> <NAME>[, <TYPE> <NAME>...])
#
# A function which takes arguments as listed in the message definition
# and which constructs and sends the message.
# The send_<message_name> functions queue data for transmission but
# do not wait for the message to be completed before returning, as long
# as there is space in the Stream buffer for the message.
# These functions are not re-entrant, and must not be called from an
# interrupt handler.
#
# BinComm::unpack_<message_name>(<TYPE> &<NAME>[, <TYPE> &<NAME>...])
#
# A function which unpacks the message. Use this instead of casting
# to the structure when you intend to use most of the values from the
# message. Must only be called inside the message reception callout
# function, as it references the message receive buffer directly.
#
#
# Acknowledge message
# Required by protocol, don't change
message 0x00 MSG_ACKNOWLEDGE
uint8_t msgID
uint8_t sum1
uint8_t sum2
#
# Text status message
# Required by protocol, don't change
message 0x05 MSG_STATUS_TEXT
uint8_t severity
char text 50
#
# 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
uint16_t yaw
#
# Location report
#
message 0x03 MSG_LOCATION
int32_t latitude
int32_t longitude
int32_t altitude
uint16_t groundSpeed
uint16_t groundCourse
uint32_t timeOfWeek
#
# Optional pressure-based location report
#
message 0x04 MSG_PRESSURE
int32_t pressureAltitude
int16_t airSpeed
#
# Algorithm performance report
#
message 0x06 MSG_PERF_REPORT
uint32_t interval
uint16_t mainLoopCycles
uint8_t mainLoopCycleTime
uint8_t gyroSaturationCount
uint8_t adcConstraintCount
uint8_t renormSqrtCount
uint8_t renormBlowupCount
uint8_t gpsFixCount
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
uint16_t listLength
uint8_t commandID
uint8_t p1
int32_t p2
int32_t p3
int32_t p4
message 0x22 MSG_COMMAND_LIST
uint16_t itemNumber
uint16_t listLength
uint8_t commandID
uint8_t p1
int32_t p2
int32_t p3
int32_t p4
# this message is not in the standard
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 settings and values
#
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
message 0x53 MSG_RADIO_OUT
uint16_t value 8
#
# Direct sensor access
#
message 0x60 MSG_SENSOR
uint16_t UNSPECIFIED
#
# Simulation-related messages
#
message 0x70 MSG_SERVO_OUT
int16_t value 8
#
# 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
#
# Navigation Augmentation
#
message 0xb0 MSG_POSITION_CORRECT
int16_t latError
int16_t lonError
int16_t altError
int16_t groundSpeedError
message 0xb1 MSG_ATTITUDE_CORRECT
int16_t rollError
int16_t pitchError
int16_t yawError
message 0xb2 MSG_POSITION_SET
int32_t latitude
int32_t longitude
int32_t altitude
uint16_t heading
message 0xb3 MSG_ATTITUDE_SET
int16_t roll
int16_t pitch
uint16_t yaw