Skip to main content

GNSSInfoMessage Struct

Information about the GNSS data used in the PoseMessage with the corresponding timestamp (MessageType::GNSS_INFO, version 1.1). More...

Declaration

struct point_one::fusion_engine::messages::GNSSInfoMessage { ... }

Included Headers

Base struct

structMessagePayload

The base class for all message payloads. More...

Public Member Attributes Index

uint16_tbaseline_distance = INVALID_DISTANCE

The distance between the device and the GNSS corrections base station. More...

uint16_tcorrections_age = INVALID_AGE

The age of the most recently received GNSS corrections data (in 0.1 seconds). More...

floatgdop = NAN

The geometric dilution of precision (GDOP). More...

Timestampgps_time

The GPS time of the message, if available, referenced to 1980/1/6. More...

floatgps_time_std_sec = NAN

GPS time alignment standard deviation (in seconds). More...

floathdop = NAN

The horizontal dilution of precision (HDOP). More...

uint8_tleap_second = INVALID_LEAP_SECOND

The current UTC leap second (offset between UTC and GPS time), if known. More...

uint8_tnum_svs = 0

The number of satellites used in the current position solution. More...

Timestampp1_time

The time of the message, in P1 time (beginning at power-on). More...

floatpdop = NAN

The position dilution of precision (PDOP). More...

uint32_treference_station_id = INVALID_REFERENCE_STATION

The ID of the GNSS corrections base station, if used. More...

floatvdop = NAN

The vertical dilution of precision (VDOP). More...

Public Static Attributes Index

static constexpr uint16_tINVALID_AGE = 0xFFFF
static constexpr uint16_tINVALID_DISTANCE = 0xFFFF
static constexpr uint8_tINVALID_LEAP_SECOND = 0xFF
static constexpr uint32_tINVALID_REFERENCE_STATION = 0xFFFFFFFF
static constexpr MessageTypeMESSAGE_TYPE = MessageType::GNSS_INFO
static constexpr uint8_tMESSAGE_VERSION = 1

Description

Information about the GNSS data used in the PoseMessage with the corresponding timestamp (MessageType::GNSS_INFO, version 1.1).

info

The deprecated last_differential_time field was removed in version 1.1 of this message, and was replaced by the new leap_second, num_svs, corrections_age, and baseline_distance fields. Attempting to use those fields on version 0 messages will result in undefined behavior.

Definition at line 223 of file solution.h.

Public Member Attributes

baseline_distance

uint16_t point_one::fusion_engine::messages::GNSSInfoMessage::baseline_distance = INVALID_DISTANCE

The distance between the device and the GNSS corrections base station.

Stored in units of 10 meters: baseline_distance_m = baseline_distance * 10. Set to 0xFFFF if invalid.

Added in message version 1.

Definition at line 266 of file solution.h.

266 uint16_t baseline_distance = INVALID_DISTANCE;

corrections_age

uint16_t point_one::fusion_engine::messages::GNSSInfoMessage::corrections_age = INVALID_AGE

The age of the most recently received GNSS corrections data (in 0.1 seconds).

Set to 0xFFFF if invalid.

Added in message version 1.

Definition at line 257 of file solution.h.

257 uint16_t corrections_age = INVALID_AGE;

gdop

float point_one::fusion_engine::messages::GNSSInfoMessage::gdop = NAN

The geometric dilution of precision (GDOP).

Definition at line 275 of file solution.h.

275 float gdop = NAN;

gps_time

Timestamp point_one::fusion_engine::messages::GNSSInfoMessage::gps_time

The GPS time of the message, if available, referenced to 1980/1/6.

Definition at line 236 of file solution.h.

gps_time_std_sec

float point_one::fusion_engine::messages::GNSSInfoMessage::gps_time_std_sec = NAN

GPS time alignment standard deviation (in seconds).

Definition at line 284 of file solution.h.

284 float gps_time_std_sec = NAN;

hdop

float point_one::fusion_engine::messages::GNSSInfoMessage::hdop = NAN

The horizontal dilution of precision (HDOP).

Definition at line 279 of file solution.h.

279 float hdop = NAN;

leap_second

uint8_t point_one::fusion_engine::messages::GNSSInfoMessage::leap_second = INVALID_LEAP_SECOND

The current UTC leap second (offset between UTC and GPS time), if known.

Set to 0xFF if invalid.

Added in message version 1.

Definition at line 244 of file solution.h.

244 uint8_t leap_second = INVALID_LEAP_SECOND;

num_svs

uint8_t point_one::fusion_engine::messages::GNSSInfoMessage::num_svs = 0

The number of satellites used in the current position solution.

Definition at line 247 of file solution.h.

247 uint8_t num_svs = 0;

p1_time

Timestamp point_one::fusion_engine::messages::GNSSInfoMessage::p1_time

The time of the message, in P1 time (beginning at power-on).

Definition at line 233 of file solution.h.

pdop

float point_one::fusion_engine::messages::GNSSInfoMessage::pdop = NAN

The position dilution of precision (PDOP).

Definition at line 277 of file solution.h.

277 float pdop = NAN;

reference_station_id

uint32_t point_one::fusion_engine::messages::GNSSInfoMessage::reference_station_id = INVALID_REFERENCE_STATION

The ID of the GNSS corrections base station, if used.

Set to 0xFFFFFFFF if invalid.

Definition at line 272 of file solution.h.

272 uint32_t reference_station_id = INVALID_REFERENCE_STATION;

vdop

float point_one::fusion_engine::messages::GNSSInfoMessage::vdop = NAN

The vertical dilution of precision (VDOP).

Definition at line 281 of file solution.h.

281 float vdop = NAN;

Public Static Attributes

INVALID_AGE

constexpr uint16_t point_one::fusion_engine::messages::GNSSInfoMessage::INVALID_AGE = 0xFFFF
constexpr static

Definition at line 228 of file solution.h.

228 static constexpr uint16_t INVALID_AGE = 0xFFFF;

INVALID_DISTANCE

constexpr uint16_t point_one::fusion_engine::messages::GNSSInfoMessage::INVALID_DISTANCE = 0xFFFF
constexpr static

Definition at line 229 of file solution.h.

229 static constexpr uint16_t INVALID_DISTANCE = 0xFFFF;

INVALID_LEAP_SECOND

constexpr uint8_t point_one::fusion_engine::messages::GNSSInfoMessage::INVALID_LEAP_SECOND = 0xFF
constexpr static

Definition at line 227 of file solution.h.

227 static constexpr uint8_t INVALID_LEAP_SECOND = 0xFF;

INVALID_REFERENCE_STATION

constexpr uint32_t point_one::fusion_engine::messages::GNSSInfoMessage::INVALID_REFERENCE_STATION = 0xFFFFFFFF
constexpr static

Definition at line 230 of file solution.h.

230 static constexpr uint32_t INVALID_REFERENCE_STATION = 0xFFFFFFFF;

MESSAGE_TYPE

constexpr MessageType point_one::fusion_engine::messages::GNSSInfoMessage::MESSAGE_TYPE = MessageType::GNSS_INFO
constexpr static

Definition at line 224 of file solution.h.

224 static constexpr MessageType MESSAGE_TYPE = MessageType::GNSS_INFO;

MESSAGE_VERSION

constexpr uint8_t point_one::fusion_engine::messages::GNSSInfoMessage::MESSAGE_VERSION = 1
constexpr static

Definition at line 225 of file solution.h.

225 static constexpr uint8_t MESSAGE_VERSION = 1;

The documentation for this struct was generated from the following file:


Generated via doxygen2docusaurus 2.0.0 by Doxygen 1.9.8.