Skip to content
Arthur Benemann edited this page Mar 15, 2013 · 1 revision

GENERAL MESSAGING RULES

  1. Messages may be sent from UAV to Ground Station or Ground Station to UAV
  2. Messages from Ground Station to UAV will be acknowledged by UAV with message 0x00
  3. Messages from UAV to Ground Station will not be acknowledged except for message 0x05 !StatusText messages with a severity code of 200 or greater

BINARY MESSAGE COMPONENTS

  1. Each message will begin with a 2 byte PREAMBLE. The preamble is "4D", or 0x34 44. (2 Bytes)
  2. Following the preamble will be a single byte containing the PAYLOAD LENGTH. (1 Byte)
  3. Following the payload length will be a byte for the MESSAGE ID. The message ID will distinguish between different message types using this protocol. (1 Byte)
  4. Following the message ID will be the message version. This byte is for future use if significant revision to the messages is necessary.
  5. Following the message version is the payload. The payload length in bytes is defined in item 2 above. (1-32 Bytes)
  6. Following the payload is the checksum. The checksum will be 2 bytes, produced with the Fletcher-8 algorithm using the payload length byte, message ID byte, message version byte, and payload bytes. This is the same checksum algorithm used by uBlox.
  7. Payload length should be always the same for determined Msg ID#.

Example: 0x3444, 0x03, 0x00, 0x01, 0x1A2B3C

DEFINED MESSAGES

**Message ID** **Request type/Rate** **Name (Typical rate)** **Payload length (# of bytes)** **Payload Details**
**0x0x messages are general use messages **
0x00 Message received acknowledgement (after uplink msg or severe !StatusText message) 3 MsgReceivedID(byte), !ChecksumReceived(2 bytes)
0x01 Poll or 1Hz System Status (Heartbeat) (1hz) 7 !FlightMode(byte),Timestamp(uint16) (seconds),batt(uint16) (volts*100), !CommandIndex(uint16)
0x02 Constant/10Hz Attitude Data (10hz) 6 roll(int16) (degrees*100), pitch(int16) (degrees x 100), yaw(uint16) (degrees x 100)
0x03 Location Data (GPS) (1-4hz) 18 Lat(int32) (decimal degrees x 10^7), Lon(int32), Alt_MSL(int32) (meters x 100), ground_speed(uint16) (M/S x 100), ground_course(uint16) (degrees x 100), Time of Week (uint32) (milliseconds)
0x04 Pressure Data (10Hz) 4 !PressureAlt (int32) (meters x 100)(mixed value if pressure/gps mixing in use), Airspeed (int16)(TBD)
0x05 On event !StatusText (on event occurrence) variable up to 51 Severity (uint8) (0=info, 255=critical), array(50) (Status text message, with null termination character)
0x06 Performance report (20 sec interval) 16 report interval(uint32) milliseconds, main loop cycles(uint16), max main loop cycle time(uint8) (milliseconds), gyro saturation count(byte), adc contraint count(byte), renorm sqrt count(byte), renorm blowup count(byte), gps fix count(byte), IMU health(uint16) (0 to 1 x1000), GCS message sent count(uint16)
0x07 Request Startup Message 2 system type (byte), system identifier (byte)
0x08 Startup Message 5 system type (byte), system identifier (byte), firmware version (3 bytes)
**0x2x messages are command and mode messages**
||0x20|| ||Request command list item|| || || ||0x21|| ||Command upload||17||Action (byte) (0=insert in list, 1=execute immediately), Item number (uint16), List length (uint16), Command ID (byte), Command P1 (byte), Command P2 (int32), Command P3 (int32), Command P4 (int32). See APM Mission Commands for a list of commands|| ||0x22|| ||Command List Item (polled or when next WP command becomes active )||16||Item number (uint16), List length (uint16), Command ID (byte), Command P1 (byte), Command P2 (int32), Command P3 (int32), Command P4 (int32)|| || **0x3x messages are value and variable messages** || ||0x30|| ||Request Value||2||Requested value ID (byte), Broadcast (byte) (0=send once, 1=broadcast) One value ID may be broadcast at a time. Requesting a “send once” of a value being broadcast discontinues broadcast.|| ||0x31|| ||Set Value||5||Value ID (byte), Value (4 bytes). See appendix 1 for list of values and scaling/format|| ||0x32|| ||Requested Value (polled or broadcast at 10Hz)||5||Requested Value ID (byte), Requested Value (4 bytes). See appendix 1 for list of values and scaling/format|| || **0x4x messages are PID messages** || ||0x40|| || Request PID||1||Requested PID set (byte)|| ||0x41|| ||Set PID||15||PID Set (byte), P I D gains (each int32) (gain value x 1000000), Integrator max(int16). See appendix 2 for list of PID sets|| ||0x42|| ||Requested PID Gains (polled)||15||PID Set (byte), PID gains (each int32) (gain value x 1000000), Integrator max(int16). See appendix 2 for list of PID sets|| || **0x5x messages are radio messages** || ||0x50|| ||Radio trims (startup)||16||ch1_trim(uint16)(pulse width) - ch8_trim(uint16)(pulse width);|| ||0x51|| ||Radio mins (startup)||16||ch1_min(uint16)(pulse width) - ch8_min(uint16)(pulse width);|| ||0x52|| ||Radio maxes (startup)||16||ch1_max(uint16)(pulse width) - ch8_max(uint16)(pulse width);|| ||0x53|| ||Current radio outputs||16||ch1(uint16)(pulse width) - ch8(uint16)(pulse width);|| ||0x6x|| || || ||messages are raw sensor data messages|| || **0x7x messages are for simulation I/O** || ||0x70|| ||Current normalized servo outputs.||16|| ch1(int16)(-100 to 100 x 100)-ch8(int16)(-100 to 100 x 100) || ||0x8x|| || || ||messages are for messages for reading ATmega pins|| ||0x9x|| || || ||messages are for !DataFlash messages|| ||0xax|| || || ||messages are for EEPROM messages|| || **0xbx messages are for navigation augmentation** || ||0xb0|| ||Position Correction||8||error Lat(int16) (decimal degrees x 10^7), error Lon(int16), error Alt_MSL(int16) (meters x 100), error ground_speed(int16) (M/S x 100)|| ||0xb1|| ||Attitude Correction||6||error roll(int16) (degrees*100), error pitch(int16) (degrees x 100), error yaw(int16) (degrees x 100)|| ||0xb2|| ||Set Position||16||Lat(int32) (decimal degrees x 10^7), Lon(int32), Alt_MSL(int32) (meters x 100), ground_speed(uint16) (M/S x 100)|| ||0xb3|| ||Set Attitude||6||roll(int16) (degrees*100), pitch(int16) (degrees x 100), yaw(uint16) (degrees x 100)||

APPENDIX 1

Requestable/Settable values

**Value** **Setting** **Type**
0x00 Roll Mode Integer
0x01 Pitch Mode Integer
0x02 Throttle Mode Integer
0x03 Yaw Mode Integer
0x04 Elevon 1 trim Integer
0x05 Elevon 2 trim Integer
0x10 Integrator(0) x 1000
0x11 Integrator(1) x 1000
0x12 Integrator(2) x 1000
0x13 Integrator(3) x 1000
0x14 Integrator(4) x 1000
0x15 Integrator(5) x 1000
0x16 Integrator(6) x 1000
0x17 Integrator(7) x 1000
0x1a Kff(0) x 1000
0x1b Kff(1) x 1000
0x1c Kff(2) x 1000
0x20 target_bearing degrees x 100
||0x21||nav_bearing||degrees x 100|| ||0x22||bearing_error||degrees x 100|| ||0x23||crosstrack bearing||degrees x 100|| ||0x24||crosstrack_error||meters|| ||0x25||altitude_error||meters x 100|| ||0x26||wp_radius||meters|| ||0x27||loiter_radius||meters|| ||0x28||wp_mode||int|| ||0x29||loop_commands||int|| ||0x2a||nav_gain_scaler||x 1000||

To be continued

APPENDIX 2 - PID Sets

CASE_SERVO_ROLL 0
CASE_SERVO_PITCH 1
CASE_SERVO_RUDDER 2
CASE_NAV_ROLL 3
CASE_NAV_PITCH_ASP 4
CASE_NAV_PITCH_ALT 5
CASE_TE_THROTTLE 6
CASE_ALT_THROTTLE 7
Clone this wiki locally