User Tools

Site Tools


phantom_2_can_bus

Messages

The CAN Bus on the Phantom 2 carries messages from the following ID's 0x108, 0x090, 0x0A8, 0x1FE, 0x118, 0x7F8. These are present on a stock Phantom 2 without a Zenmuse Gimbal.

Format:

  • BYTE 1-4: 55 AA 55 AA
  • BYTE 5-6: Message ID
  • BYTE 7-8: Payload Length

Payload


Decoded 0x108

Message 0910- I/O

Used by Naza Can Decoder. This message is considered an I/O Message. Example:

55 AA 55 AA 09 10 B8 00 44 4A 49 01 18 42 18 42 18 42 18 42 00 00 00 00 00 00 64 00 00 00 00 00 17 FC E9 03 E9 03 00 00 EB 01 E9 03 17 FC 17 FC E9 03 E9 03 00 00 00 00 18 04 01 00 00 00 33 02 00 00 00 00 00 00 F1 8F 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 DA 03 00 00 4B 29 57 C1 6C 77 0C C1 00 40 0D C4 64 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 0E FE 00 00 3B 00 00 00 00 00 00 00 54 2D 16 0F 22 0F 1C 0F 51 2D 85 BF C9 41 DE 31 C9 41 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 F0 BF FF FF FF FF 00 00 00 00 00 00 00 00 00 0A 78 78 00 00 66 CC 66 CC 
  • Header: 55 AA 55 AA
  • ID: 09 10
  • Length: B8 00
  • Payload:
    • BYTE 9-12: ???
    • BYTE 13-14 (M1): motor 1 output (unsigned, 16920~35000 range)
    • BYTE 15-16 (M2): motor 2 output (unsigned, 16920~35000 range)
    • BYTE 17-18 (M3): motor 3 output (unsigned, 16920~35000 range)
    • BYTE 19-20 (M4): motor 4 output (unsigned, 16920~35000 range)
    • BYTE 21-22 (M5): motor 5 output (unsigned, 16920~35000 range)
    • BYTE 23-24 (M6): motor 6 output (unsigned, 16920~35000 range)
    • BYTE 25-26 (F1): motor 7 output (unsigned, 16920~35000 range)
    • BYTE 27-28 (F2): motor 8 output (unsigned, 16920~35000 range)
    • BYTE 29-32: ???
    • BYTE 33-34 (R?): RC controller unused channel 1 input (signed, always 1001)
    • BYTE 35-36 (RA): RC controller A channel input (signed, about -1000~1000 range)
    • BYTE 37-38 (RE): RC controller E channel input (signed, about -1000~1000 range)
    • BYTE 39-40 (RR): RC controller R channel input (signed, about -1000~1000 range)
    • BYTE 41-42 (RU): RC controller U channel input (signed, about -1000~1000 range)
    • BYTE 43-44 (RT): RC controller T channel input (signed, about -1000~1000 range)
    • BYTE 45-46 (R?): RC controller unused channel 2 input (signed, always 1001)
    • BYTE 47-48 (R1): RC controller X1 channel input (signed, about -1000~1000 range)
    • BYTE 49-50 (R2): RC controller X2 channel input (signed, about -1000~1000 range)
    • BYTE 51-52 (R8): RC controller CH8 when using SBUS or PPM, unused when traditional connection is used signed, about -1000~1000 range, 1001 when unused)
    • BYTE 53-63: ???
    • BYTE 64 (FM): flight mode (0 - manual, 1 - GPS, 2 - failsafe, 3 - atti)
    • BYTE 65-72: ???
    • BYTE 73-80 (HL): Home latitude (double, radians)
    • BYTE 81-88 (Hl): Home longitude (double, radians)
    • BYTE 89-92 (HA): Home altitude from barometric sensor + 20m (float, meters)
    • BYTE 93-94 (SN): sequence number, increases with every message
    • BYTE 95-96: ???
    • BYTE 97-100 (RS): attitude stabilizer roll input to the system, merged with aileron input, flight mode
    • ependent (float, -1000 ~ 1000 range)
    • BYTE 101-104 (PS): attitude stabilizer pitch input the system, merged elevator input, flight mode dependent (float, -1000~1000 range)
    • BYTE 105-108 (ST): altitude stabilizer throttle input to the system based on flight mode and arm state
    • float, about -1000~1000 range)
    • BYTE 109-112: ???
    • BYTE 113-116 (AA): ??? actual aileron feed to the system based on mode and arm state (float, about
    • 1000~1000 range)
    • BYTE 117-120 (AE): ??? actual elevator feed to the system based on flight mode and arm state (float, about 1000~1000 range)
    • BYTE 121-124 (AT): ??? actual throttle feed to the system based on flight mode (float, about -1000~1000 range, changes to -200 in failsafe)
    • BYTE 125-126 (BA): battery voltage (unsigned, millivolts)
    • BYTE 127-128 (BE): BEC voltage (unsigned, millivolts)
    • BYTE 129-132: ???
    • BYTE 133 (CM): control mode (0 - GPS/failsafe, 1 - waypoint mode?, 3 - manual, 6 - atti)
    • BYTE 134-176: ???
    • BYTE 177-180 (DV): downward velocity? (float, m/s)
    • BYTE 181-184 (AB): altitude from the barometric sensor (float, meters)
    • BYTE 185-188 (RO): roll (float, radians)
    • BYTE 189-192 (PI): pitch (float, radians)

Decoder 0x090

Message 0110- Gyroscope Data

55 AA 55 AA 01 10 0E 00 1A 00 00 00 D4 FF FF FF 34 00 00 00 51 69 66 CC 66 CC
  • Payload
    • BYTE 9-12 (GX): gyroscope X axis raw data (x100, degree/s)
    • BYTE 13-16 (GY): gyroscope Y axis raw data (x100, degree/s)
    • BYTE 17-20 (GZ): gyroscope Z axis raw data (x100, degree/s)
    • BYTE 21-22 (SN): sequence number, increases with every message

Message 0210- OSD Info

55 AA 55 AA 02 10 78 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 88 C1 52 6D 06 3D 4B 8C 8C BB A6 C7 7F BF C0 AF 62 3C 3E EE 0B BC A9 03 5B 3C 66 61 CE 41 7E B3 7A 3F A3 D5 5C 3C 22 16 12 3C A0 9A 4E BE CC 60 25 3E 96 96 03 3E 5C 02 38 BD 00 00 00 00 00 00 00 00 B2 52 B2 BC 80 7C 93 3B B4 CF 8D BB 3A 04 1E 3B 71 01 D5 00 E5 04 37 00 37 00 20 00 00 00 70 00 00 00 8C 11 66 CC 66 CC 
  • Payload
    • BYTE 9-16 (LO): longitude (double, radians)
    • BYTE 17-24 (LA): latitude (double, radians)
    • BYTE 25-28 (AG): altitude from GPS (float, meters)
    • BYTE 29-32 (AX): accelerometer X axis data (float, g)
    • BYTE 33-36 (AY): accelerometer Y axis data (float, g)
    • BYTE 37-40 (AZ): accelerometer Z axis data (float, g):
    • BYTE 41-44 (GY): ? gyroscope X axis data (float, radians/s):
    • BYTE 45-48 (GY): ? gyroscope Y axis data (float, radians/s):
    • BYTE 49-52 (GZ): ? gyroscope Z axis data (float, radians/s):
    • BYTE 53-56 (AB): altitude from the barometric sensor (float, meters)
    • BYTE 57-84 ???
    • BYTE 85-88 (NV): averaged northward velocity, or 0 when less than 5 satellites locked (float, m/s)
    • BYTE 89-92 (EV): averaged eastward velocity, or 0 when less than 5 satellites locked (float, m/s)
    • BYTE 93-96 (EV): downward velocity (barometric) (float, m/s)
    • BYTE 97-108 ???
    • BYTE 109-110 (CX): calibrated magnetometer X axis data (signed)
    • BYTE 111-112 (CY): calibrated magnetometer Y axis data (signed)
    • BYTE 113-114 (CZ): calibrated magnetometer Z axis data (signed)
    • BYTE 115-124 ???
    • BYTE 125 (NS): number of satellites
    • BYTE 126 ???
    • BYTE 127-128 (SN): sequence number, increases with every message

0x0A8

Example:

55 BB 55 BB 0F 00 F1 59 4E 39 82 E9 F5 00 12 48 3C B0 E3

0x1FE

No Messages Found.


0x118

0410 Message- Compass Data

55 AA 55 AA 04 10 06 00 23 01 56 00 46 01 66 CC 66 CC
  • Header- 55 AA 55 AA
  • ID- 04 10
  • Length- 06 00
  • Payload
    • BYTE 5-6 (CX): compass X axis data (signed)
    • BYTE 7-8 (CY): compass Y axis data (signed)
    • BYTE 9-10 (CZ): compass Z axis data (signed)
  • Footer- 66 CC 66 CC

Decoded- 0x7F8- Phantom 2 Smart Battery

2209 Message- Firmware

55 AA 55 AA 22 09 00 00 66 CC 66 CC

2609 Message- Smart Battery Data:

55 AA 55 AA 26 09 23 00 50 14 50 14 0C 0C 4F 2D 29 FE 5E 3B 1F 01 14 00 BA 3C 14 0F 20 0F 1B 0F 28 FE 01 00 00 00 00 07 00 00 00 66 CC 66 CC
  • PAYLOAD
    • BYTE 9-10: 50 14 - design capacity (unsigned short, 5200mAh)
    • BYTE 11-12: 8E 13 - full capacity (unsigned short, 5003mAH)
    • BYTE 13-14: 2B 0C - current capacity (unsigned short, 3115mAh)
    • BYTE 15-16: CD 2D - voltage (unsigned short, 11725mV)
    • BYTE 17-18: 8D FE - current (signed short, -371mA)
    • BYTE 19: 5D - percentage of life (unsigned byte, 93%)
    • BYTE 20: 3E - percentage of charge (unsigned byte, 62%)
    • BYTE 21-22: E6 00 - temperature (signed short, 230 * 0.1 degrees Celsius)
    • BYTE 23-24: 15 00 - discharging times (unsigned short, 21)
    • BYTE 25-26: B9 19 - serial number (unsigned short, 6585)
    • BYTE 27-28: 11 0F - cell 1 (unsigned short, 3857mV)
    • BYTE 29-30: 5E 0F - cell 2 (unsigned short, 3934mV)
    • BYTE 31-32: 5E 0F - cell 3 (unsigned short, 3934mV)
    • BYTE 33-43: 47 FE 01 00 00 00 00 01 00 00 00 ??? (not sure yet)

phantom_2_can_bus.txt · Last modified: 2015/04/09 10:32 by admin