X-Star Log Viewer
X-Star Log Details
Table of Contents
How to pull the logs from the X-Star
ATSP - Vehicle attitude setpoint
LPOS - Local position estimate
LPSP - Local position setpoint
GPOS - Global position estimate
GVSP - Global velocity setpoint
How to pull the logs from the X-Star
- Connect microUSB->USB cable to jack in the front of your X-Star and place near your PC
- Power up RC, App then X-Star.
- go to Flight Control Settings > Advanced Settings
- Android-> Click on "Read" next to Read Flight Data
- IOS->Click on "Enter" next to Flight Data Recorder
Your bird will start chirping….
- Connect the USB cable to your PC
- Copy the files to another drive.
- Unmount the X-Star from the computer
- Disconnect the X-Star and power it down.
Once you open a log you can save as the following:
KML/KMZ Google Earth
Output Formats
GPX file viewers:
http://www.maplorer.com/view_gpx.html
Log Details
Many of the format description were found from the MAVLink documentation and my not be to the Autel customized set, I made adjustments to these as I found differences and tried to be consistent in highlighting the Autel specifics in Orange.
ATT - Vehicle attitude
PX4: ATT, "fffffffffffff", "qw,qx,qy,qz,Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"
Autel: ATT, fffffffff, Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ
Field Name |
Type |
Description |
time_boot_ms |
uint32_t |
Timestamp (milliseconds since system boot) |
roll |
float |
Roll angle (rad, -pi..+pi) |
pitch |
float |
Pitch angle (rad, -pi..+pi) |
yaw |
float |
Yaw angle (rad, -pi..+pi) |
rollspeed |
float |
Roll angular speed (rad/s) |
pitchspeed |
float |
Pitch angular speed (rad/s) |
yawspeed |
float |
Yaw angular speed (rad/s) |
|
|
|
ATSP - Vehicle attitude setpoint
PX4: ATSP, "ffffffff", "RollSP,PitchSP,YawSP,ThrustSP,qw,qx,qy,qz"
Autel: ATSP, ffff, RollSP,PitchSP,YawSP,ThrustSP
IMU - IMU sensors
PX4: IMU, "ffffffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,tA,tG,tM"
Autel: IMU, ffffffffff, AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ,Temprature
MavLInk: http://mavlink.org/messages/common#RAW_IMU
The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.
Field Name |
Description |
time_usec |
Timestamp (microseconds since UNIX epoch or microseconds since system boot) |
xacc |
X acceleration (raw) |
yacc |
Y acceleration (raw) |
zacc |
Z acceleration (raw) |
xgyro |
Angular speed around X axis (raw) |
ygyro |
Angular speed around Y axis (raw) |
zgyro |
Angular speed around Z axis (raw) |
xmag |
X Magnetic field (raw) |
ymag |
Y Magnetic field (raw) |
zmag |
Z Magnetic field (raw) |
SENS - Other sensors
PX4: SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"
Autel: SENS, fffff, BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt
LPOS - Local position estimate
PX4: LPOS, "ffffffffLLfBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,GFlg,EPH,EPV"
Autel: LPOS, fffffffffffBffff, X,Y,Z,Dist,DistR,VX,VY,VZ,AX,AY,AZ,GFlg,SOfS,BOfS,CSnr,CSnrF
LPSP - Local position setpoint
PX4: LPSP, "ffffffffff", "X,Y,Z,Yaw,VX,VY,VZ,AX,AY,AZ"
Autel: LPSP, ffff, X,Y,Z,Yaw
GPS - GPS position
PX4: GPS, "QBffLLfffffBHHH", "GPSTime,Fix,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog,nSat,SNR,N,J"
Autel: GPS, QBffLLffffB, GPSTime,Fix,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,nSat
Mavlink: http://mavlink.org/messages/common#GPS_RAW_INT
GPSTime |
Timestamp (microseconds since UNIX epoch (1/1/1970) |
fix |
0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. |
lat |
Latitude (WGS84), in degrees * 1E7 |
lon |
Longitude (WGS84), in degrees * 1E7 |
alt |
Altitude (AMSL, NOT WGS84), in meters (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. |
eph |
GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX |
epv |
GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX |
veln |
GPS ground speed (m/s). (N)orth, (E)ast, (D)own |
|
|
nSat |
Number of satellites visible. If unknown, set to 255 |
ATTC - Attitude controls
PX4: ATTC, "ffff","Roll,Pitch,Yaw,Thrust"
Autel: ATTC, ffff, Roll,Pitch,Yaw,Thrust
STAT - Vehicle state
PX4: STAT, "BBBBB","MainState,NavState,ArmS,Failsafe,IsRotWing"
Autel: STAT, BBBfB, Main,Nav,Arm,Load,RCLost
RC - RC input channels
PX4: RC, "ffffffffffffBBBL","C0,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,RSSI,CNT,Lost,Drop"
Autel: RC, ffffffffBB, Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count,SignalLost
Autel RC
· Ch0 – Move Left/Right (roll)
· Ch1 - Move Forward/Back (pitch)
· Ch2 - Orientation (rotate CW/CCW) (yaw)
· Ch3 - Elevation (throttle)
· Ch4 = gimbal angle. Range = (-1) forward to (+1) down 90 degrees
· Ch5 – Assist Mode (Button Functions)
o -1 = no action
o - 0.5765957 = start
o - 0.1510638 = Takeoff/Land
o + 0.5723404 = Pause
o + 0.1468085 = Go Home
· RC.Ch6 - Flight mode (GPS/IOC/ATTI): 0 for ATTI, -1 for GPS and 1 for IOC
· RC.Ch7 - N/A (We're leaving this channel for future use.)
· Count – number of channels
· SignalLost (0 = has signal, 1=lost signal)
OUTn - (actuator_0 output)
PX4: OUT, "ffffffff","Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"
Autel: OUT0, ffffffff, Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7
ARSP - Attitude rate setpoint
PX4: ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"
Autel: ARSP, fff, RollRateSP,PitchRateSP,YawRateSP
FLOW - Optical flow
PX4: FLOW, "BffffffLLHhB", "ID,RawX,RawY,RX,RY,RZ,Dist,TSpan,DtSonar,FrmCnt,GT,Qlty"
Autel: FLOW, fffffhfBBHQII, RawX, RawY, Gx, Gy,Gz,Gtemp,GD,Q,id,Count,TS,Tspan,Tsince
http://mavlink.org/messages/common#OPTICAL_FLOW
http://mavlink.org/messages/common#OPTICAL_FLOW_RAD
BATT - Battery
PX4: BATT, "ffffffB", "V,VFilt,C,CFilt,Discharged,Remaining,Warning"
Autel: BATT, ffff, V,VFilt,Curr,Capacity
http://mavlink.org/messages/common#BATTERY_STATUS
V = Battery voltage of cells, in volts (1 = 1 volt).
VFilt = ? matches V for Autel
Curr = Battery current, (load) (-1 = 1 mAh),
Capacity – remaining current, (Battery Level ) in mAh (-1 = 1 mAh)
GPOS - Global position estimate
PX4: GPOS, "LLfffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV,TALT"
Autel: GPOS, LLffffff, Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV
GVSP - Global velocity setpoint
PX4: GVSP, "fff", "VX,VY,VZ"
Autel: GVSP, fff, VX,VY,VZ
PWR - Power
PX4: PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"
Autel: PWR, fffBBBBB, Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC
In FMT but No Log Items
DBUG – Debug (Autel Only)
PX4: N/A
Autel: DBUG, fffffffffffff, F1,F2,F3,F4,F5,F6,F7,F8,F9,F10,F11,F12,F13
F7 = magnetic interference
F8 = (0 for no interference and 1 for yes)
TIME
The system time is the time of the master clock, typically the computer clock of the main onboard computer.
Autel: TIME, Q, StartTime
PX4: N/A
MavLink: http://mavlink.org/messages/common#SYSTEM_TIME
time_unix_usec |
uint64_t |
Timestamp of the master clock in microseconds since UNIX epoch. |
time_boot_ms |
uint32_t |
Timestamp of the component clock since boot time in milliseconds. |
HOME
The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitly set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.
Autel: HOME, ffLLf, X,Y,Lat,Lon,Alt
http://mavlink.org/messages/common#HOME_POSITION
x |
float |
Local X position of this position in the local coordinate frame my log shows as 0 |
y |
float |
Local Y position of this position in the local coordinate frame my log shows as 0 |
latitude |
int32_t |
Latitude (WGS84), in degrees * 1E7 |
longitude |
int32_t |
Longitude (WGS84, in degrees * 1E7 |
altitude |
int32_t |
Altitude (AMSL), in meters * 1000 (positive for up) |
Format string codes
o b : int8_t
o B : uint8_t
o h : int16_t
o H : uint16_t
o i : int32_t
o I : uint32_t
o f : float
o n : char[4]
o N : char[16]
o Z : char[64]
o c : int16_t * 100
o C : uint16_t * 100
o e : int32_t * 100
o E : uint32_t * 100
o L : int32_t latitude/longitude
o M : uint8_t flight mode
o q : int64_t
o Q : uint64_t