ANavS® Binary Solution Output Format

The sensor fusion solution provides two different output-streams for the position, attitude, velocity and many more states of solution and quality of solution.
By default it’s possible to configure the hardware to write to a file and/or to broadcast the solution per TCP on a customizable port (standardt-port: 6001). To stream the solution per WLAN or Ethernet, you need additionally to the defined port-number the IP-adress of your MSRTK Module, which is by default 192.168.42.1 (in case you are connected with WLAN-AP “ANavS_MSRTK_AP”).

The ANavS® sensor fusion framework provides two different protocols for the solution output, the standardized NMEA-Format and the proprietary binary protocol. In the following, the proprietary ANavS® binary protocol is described.

 

ANavS® Binary Protocol

The Binary Protocol is defined as follows:

Structure: Sync Char 1 Sync Char 2 Class ID Length Payload ChecksumA ChecksumB
Bytes: 1 Byte 1 Byte 1 Byte 1 Byte 2 Byte Length-Byte 1 Byte 1Byte

The endianness of Length and the following Payload is little endian. The payload is of Length. The checksum is calculated with the 16-Bit Fletcher algorithm over Class, ID, Length and Payload with modulo 256. The ANavS® binary protocol message can be identified by Sync Char 1 = 0xB5 (dec 181), Sync Char 2 = 0x62 (dec 98), Class = 0x02 (dec 2) and Id = 0xE0 (dec 224). In the following, the type double has 8 bytes. If a variable in the Payload is given in the NED frame, the variable has three components (hence 3 times the data type, e.g. 3*double), where the components are north, east and down. This also holds for the body frame, which is the fixed frame of the rover, and where the components are given in x, y and z.

The Payload is given as:

Size Scaling Name Unit Description
uint8 id Identifier of the system/the ANavS Position and Attitude Determination (PAD) solution.
uint16 resCode Result code bitfield, which keeps
the system status and information.
uint16 week Week number of the current epoch (epoch means Kalman filter state-update with GNSS, IMU or another sensor data).
double tow s Time of Week of the current epoch.
uint16 weekInit Week number of the epoch when the
system was started.
double towInit s Time of Week of the epoch when the
system was started.
int16 Reserved
double lat deg Latitude in WGS84.
double lon deg Longitude in WGS84.
double height m Height in WGS84 with geoid EGM96
double ECEF-X m X-position in ECEF-coordinate frame (WGS84).
double ECEF-Y m Y-position in ECEF-coordinate frame (WGS84).
double ECEF-Z m Z-position in ECEF-coordinate frame (WGS84).
3*double b m Baseline in NED frame spanned by the position given by lat, lon and height, and by the position of the reference station.
3*double bStdDev m Standard deviation of the baseline.
3*double vel m/s Velocity in NED frame.
3*double velStdDev m/s Standard deviation of the velocity.
3*double acc m/s² Acceleration in body frame.
3*double accStdDev m/s² Standard deviation of the acceleration.
3*double att deg Attitude/Euler angles (heading, pitch, roll).
3*double attStdDev deg Standard deviation of the attitude.
double accuracy m Estimated accuracy of the baseline.
double systemTime s System time of solution data output packet
5*double timingInfo s CPU-Load of used sensors. The sum (green line in the GUI) of elapsed time should not over 1 second (–> to slow processor).
First double: Elapsed time GNSS;
Second double: Elapsed time IMU;
Third double: Elapsed time Baro;
Fourth double: Elapsed time Odometry;
Fifth double: Overall elapsed time
5*double Reserved
double gnssReception Scalar, which indicates the GNSS signal reception. The value is between 0 and 20, where 20 is the best, i.e. very good conditions.
uint8 numSats Number of satellites.
Loop uint8 gnssId Identifier of the GNSS (GPS = 1, SBAS = 2, GLONASS = 4, Galileo = 8).
uint8 svId Identifier of the satellite (“PRN”)
double elev deg Elevation angle of the satellite.
double azim deg Azimuth angle of the satellite.
uint8 numRcv Number of GNSS receivers.
Loop uint8 rcvId Identifier of the receiver (unqiue within this system).
char[11] serial Serial number of the receiver (unique).
bool isRefStation Is true, if this receiver is a reference
station (stationary).
uint16 week Week number of the current epoch for this receiver. If the following tow is NaN, the weeknumber is not valid!
double tow s Time of week of the current epoch for this receiver. Can be NaN, if there are no measurements at this epoch (e.g. commonly for reference station).
double lat deg Latitude of this receiver. Only given if the receiver is a reference station, otherwise it is NaN.
double lon deg Longitude of this receiver. Only given if the receiver is a reference station, otherwise it is NaN.
double height m Height of this receiver. Only given if the receiver is a reference station, otherwise it is NaN.
3*double bodyPos m Receiver position in x, y and z (body frame).
3*double bodyMisalign m Misalignment of the receiver in x, y and z (body frame).
uint8 Reserved.
5*double sensorBufFillLvl % Sensor buffer filling level:
First double: GNSS
Second: IMU
Third: BARO
Fourth: ODO
Fifth: Raw
uint8 numSatsMeas Number of satellites for which measurements are available for this receiver.
Loop uint8 gnssId Identifier of the GNSS.
uint8 svId Identifier of the satellite.
uint8 freq Frequency band (currently that is 1 L1)).
uint16 locktime ms Carrier phase locktime counter
(maximum 64500ms).
uint8 cno dBHz Carrier-to-noise density ratio (signal
strength) [dB-Hz].
uint8 0.01*2^n prStdDev m Standard deviation of the
pseudorange measurement.
uint8 0.004 cpStdDev cycles Standard deviation of the carrier phase measurement.
uint8 0.002*2^n doStdDev Hz Standard deviation of the Doppler frequency.
uint8 trkStat Status bitfield of the tracking (see graphic below).
uint8 numBl Number of baselines spanned by a
receiver pair.
Loop uint8 rcvId1 Identifier of the receiver the baseline is pointing to.
uint8 rcvId2 Identifier of the receiver the baseline is pointing from.
bool isFixed Is true, if the ambiguities of the phase
measurements are fixed for this baseline.
uint8 gnssIdJointRefSat GNSS identifier of the joint reference satellite for the single and double differenced
measurements.
uint8 svIdJointRefSat Identifier of the reference satellite.
uint8 svIdGloRefSat Identifier of the GLONASS reference satellite.
uint8 svIdUnlSat Identifier of the GLONASS ultra narrowlane
satellite.
3*double aprioriBl m A priori baseline.
3*double stdDevAprioriBl m Standard deviation of the a priori baseline.
double aprioriLen m A priori baseline length.
double stdDevAprioriLen m Standard deviation of the a priori baseline length.
uint8 numFilter Number of filters.
Loop uint8 nameLen Bytes Length of the filtername.
char[nameLen] name Filtername.
uint32 params Bitfield of parameters (states, residuals), which are transmitted by the filter.
bool isActive Is true, if the filter is active.
Conditioned
on Bit 0, i.e. if Bit 0 is not set, this shall not be considered (no pointer increment, just leave out!).
6*double absPos deg and m Absolute position in latitude, longitude (both in deg) and height (in m) (first 3 doubles) and its standard deviation (latter 3 doubles).
Bit 1 2*double clkErr s Receiver clock error (first double) and its standard deviation (latter double).
Bit 2 uint8 rcvId1 Identifier of the receiver the baseline is pointing to.
uint8 rcvId2 Identifier of the receiver the baseline is pointing from.
6*double baseline m Baseline in NED frame (first 3 doubles) and
its standard deviation (latter 3 doubles).
Bit 3 6*double vel m/s Velocity in NED frame (first 3 doubles) and its standard deviation (latter 3 doubles).
Bit 4 6*double acc m/s² Acceleration in body frame (first 3 doubles) and its standard deviation (latter 3 doubles).
Bit 5 6*double accBias m/s² Accelerometer bias in body frame (first 3 doubles) and its standard deviation (latter 3 doubles).
Bit 6 6*double eulerAng deg Euler angles in heading, pitch and roll (first 3 doubles) and its standard deviation (latter 3 doubles).
Bit 7 6*double angRate deg/s Angular rate in heading, pitch and roll (first 3 doubles) and its standard deviation (latter 3 doubles).
Bit 8 6*double gyroBias deg/s Gyroscope bias (first 3 doubles) and its standard deviation (latter 3 doubles).
Bit 9 2*double tropoZenDel m Tropospheric zenith delay (first double) and its standard deviation (latter double). Currently not in use (Bit 9 is always 0).
Bit 10 2*double Accuracy m Accuracy of the baseline (first double) and its standard deviation (latter double). Currently not in use (Bit 10 is always 0).
Bit 11-17 7*double Reserved
uint8 numPhase Number of phase measurements.
Loop uint8 gnssId Identifier of the GNSS.
uint8 svId Identifier of the satellite.
uint8 freq Frequency band (currently that is 1 (L1)).
Bit 18 2*double ambiguities cycles Double difference ambiguities and std. dev.
Bit 19 2*double phaseMp m Phase multipath and std. dev.
Bit 20
2*double phaseRes m Phase residuals and std. dev.
uint8 numCode Number of code measurements.
Loop uint8 gnssId Identifier of the GNSS.
uint8 svId Identifier of the satellite.
uint8 freq Frequency band (currently that is 1 (L1)).
Bit 21
2*double codeMp m First double is code multipath, second its standard deviation.
Bit 22
2*double codeRes m First double is code residual, second its standard deviation.
uint8 numDoppler Number of Doppler measurements.
Loop uint8 gnssId Identifier of the GNSS.
uint8 svId Identifier of the satellite.
uint8 freq Frequency band (currently that is 1 (L1)).
Bit 23 2*double doRes Hz First double is Doppler residual, second is its standard deviation.

The payload contains loops and conditions. The number of loop iterations and the conditions depends on other payload data. For example, the number of satellites determines, how often the following color-coded data is repeated. For numSats = 2 and p being a pointer to numSats, the following data is given as

Address Type Name
p+1 uint8 gnssId1
p+2 uint8 svId1
p+3 double elev1
p+11 double azim1
p+19 uint8 gnssId2
p+20 uint8 svId2
p+21 double elev2
p+29 double azim2
p+37 uint8 numRcv

For numSats = 0, no satellite position data is transmitted and the next variable would be numRcv. If a condition is fulfilled the following color-coded data is transmitted. For example, if isActive is true, then at least the variables numPhase, numCode and numDoppler are transmitted. If isActive is false, then the end of the UBX message is reached. The bitfield params is also a condition, whose bits determine, whether the following data is transmitted.
Example: Let p being a pointer to isActive with isActive = true, Bit 0 of params is false and Bit 1 is true. Then, p+1 points to the receiver clock error clkErr and not to the absolute position absPos since Bit 0 is false.

The resCode bitfield is defined as

Bit Definition
0 Is set for GNSS update-epochs processed in the PAD-Software
1 Is set for IMU update-epochs processed in the PAD-Software
2 Is set for Barometer update-epochs processed in the PAD-Software
3 Is set for Odometrie update-epochs processed in the PAD-Software
4 Is set for Camera update-epochs processed in the PAD-Software
5 Is set for Steering update-epochs processed in the PAD-Software
6 Is set if the IMU is initialized/calibrated
7 Is set if the Multi-Sensor RTK-Filter is reset in the current epoch
8 Is set if RTK correction were received initially
9 to 10 State-definition for the Attitude Kalman-Filter:
00 -> No solution
01 -> Least-Squares solution
10 -> Float solution
11 -> Fixed solution
11 to 12 State-definition for the RTK-Position Kalman-Filter:
00 -> No solution
01 -> Least-Squares solution
10 -> Float solution
11 -> Fixed solution
13 Is set if the RTK-Position Kalman-Filter has only a float-solution
accuracy but enough satellites in view to try a RTK-refix (the vehicle
must be stationary for this try!)
14 Is set if state update is only a prediction step (without sensor data) in our sensor fusion filter. In this case, Bit 0-5 is set to zero.
15 Reserved

 

Extended Integrity Information

To extend the existing binary format with more integrity information, ANavS provides since version 5.1.72 an additional message with the following header:
Sync Char 1 = 0xB5 (dec 181), Sync Char 2 = 0x62 (dec 98), Class = 0x02 (dec 2) and Id = 0xE5 (dec 229).
The Message is activated via customer-code 10.

The Payload is given as:

Size Scaling Name Unit Description
uint16 week Week number of the current epoch
double tow s Time of Week of the current epoch
double cov_b_xx Covariance matrix of RTK solution (value xx)
double cov_b_xy Covariance matrix of RTK solution (value xy)
double cov_b_xz Covariance matrix of RTK solution (value xz)
double cov_b_yx Covariance matrix of RTK solution (value yx)
double cov_b_yy Covariance matrix of RTK solution (value yy)
double cov_b_yz Covariance matrix of RTK solution (value yz)
double cov_b_zx Covariance matrix of RTK solution (value zx)
double cov_b_zy Covariance matrix of RTK solution (value zy)
double cov_b_zz Covariance matrix of RTK solution (value zz)
double GDOP Dilution of Precision: GDOP
double PDOP Dilution of Precision: PDOP
double HDOP Dilution of Precision: HDOP
double VDOP Dilution of Precision: VDOP
double TDOP Dilution of Precision: TDOP
bool Flag No Movement True: Rover stand still, no movement detected with IMU –> RTK- and Attitude Fix is triggert, bias estimation of IMU also.
False: Rover is moving –> NO RTK- and Attitude Fix is triggert, NO bias estimation of IMU
double RTK-Fix Validation Difference of successfully fixed RTK-baseline to the next best candidate. Only if “Flag No Movement” is true, this value is relevant for integrity information of RTK baseline.
double Correction-Outage Time since last RTK correction-data arrived.