PoseMessage Struct
Platform pose solution: position, velocity, attitude (MessageType::POSE, version 1.2). More...
Declaration
Included Headers
Base struct
| struct | MessagePayload |
|
The base class for all message payloads. More... | |
Public Member Attributes Index
| float | aggregate_protection_level_m = NAN |
|
The estimated aggregate 3D protection level (in meters). More... | |
| uint8_t | flags = 0x0 |
|
A bitmask of flags associated with the pose data. More... | |
| Timestamp | gps_time |
|
The GPS time of the message, if available, referenced to 1980/1/6. More... | |
| float | horizontal_protection_level_m = NAN |
|
The estimated 2D horizontal protection level (in meters). More... | |
| double | lla_deg[3] = {NAN, NAN, NAN} |
|
The geodetic latitude, longitude, and altitude (in degrees/degrees/meters), expressed using the WGS-84 reference ellipsoid. More... | |
| Timestamp | p1_time |
|
The time of the message, in P1 time (beginning at power-on). More... | |
| float | position_std_enu_m[3] = {NAN, NAN, NAN} |
|
The position standard deviation (in meters), resolved with respect to the local ENU tangent plane: east, north, up. More... | |
| SolutionType | solution_type |
|
The type of this position solution. More... | |
| int16_t | undulation_cm = INVALID_UNDULATION |
|
The geoid undulation at the current location (in cm). More... | |
| double | velocity_body_mps[3] = {NAN, NAN, NAN} |
|
The platform velocity (in meters/second), resolved in the body frame. More... | |
| float | velocity_std_body_mps[3] = {NAN, NAN, NAN} |
|
The velocity standard deviation (in meters/second), resolved in the body frame. More... | |
| float | vertical_protection_level_m = NAN |
|
The estimated vertical protection level (in meters). More... | |
| double | ypr_deg[3] = {NAN, NAN, NAN} |
|
The platform attitude (in degrees), if known, described as intrinsic Euler-321 angles (yaw, pitch, roll) with respect to the local ENU tangent plane. More... | |
| float | ypr_std_deg[3] = {NAN, NAN, NAN} |
|
The attitude standard deviation (in degrees): yaw, pitch, roll. More... | |
Public Static Attributes Index
| static constexpr uint8_t | FLAG_STATIONARY = 0x01 |
|
Set if the device is stationary. More... | |
| static constexpr int16_t | INVALID_UNDULATION = INT16_MIN |
| static constexpr MessageType | MESSAGE_TYPE = MessageType::POSE |
| static constexpr uint8_t | MESSAGE_VERSION = 2 |
Description
Platform pose solution: position, velocity, attitude (MessageType::POSE, version 1.2).
All data is timestamped using Point One (P1) time, which is a monotonic timestamp referenced to the start of the device. Corresponding messages (GNSSInfoMessage, GNSSSatelliteMessage, etc.) may be associated using their p1_time values.
Definition at line 40 of file solution.h.
Public Member Attributes
aggregate_protection_level_m
|
The estimated aggregate 3D protection level (in meters).
Definition at line 162 of file solution.h.
flags
|
A bitmask of flags associated with the pose data.
Added in PoseMessage version 1.2.
Definition at line 62 of file solution.h.
gps_time
|
The GPS time of the message, if available, referenced to 1980/1/6.
Definition at line 52 of file solution.h.
horizontal_protection_level_m
|
The estimated 2D horizontal protection level (in meters).
Definition at line 164 of file solution.h.
lla_deg
The geodetic latitude, longitude, and altitude (in degrees/degrees/meters), expressed using the WGS-84 reference ellipsoid.
Datum/Epoch Considerations
When comparing two positions, it is very important to make sure they are compared using the same geodetic datum, defined at the same time (epoch). Failing to do so can cause very large unexpected differences since the ground moves in various directions over time due to motion of tectonic plates.
For example, the coordinates for a point on the ground in San Francisco expressed in the ITRF14 datum may differ by multiple meters from the coordinates for the same point expressed the NAD83 datum. Similarly, the coordinates for that location expressed in the ITRF14 2017 epoch (January 1, 2017) may differ by 12 cm or more when expressed using the ITRF14 2021 epoch (January 1, 2021).
The datum and epoch to which the position reported in this message is aligned depends on the current solution_type.
- SolutionType::AutonomousGPS / SolutionType::DGPS / SolutionType::PPP - Standalone solutions (i.e., no differential corrections) are aligned to the WGS-84 datum as broadcast live by GPS (aligns closely with the ITRF08/14 datums).
- SolutionType::RTKFloat / SolutionType::RTKFixed - When differential corrections are applied, the reference datum and epoch are defined by the corrections provider. Point One's Polaris Corrections Service produces corrections using the ITRF14 datum. See https://pointonenav.com/polaris for more details.
- SolutionType::Integrate - When the INS is dead reckoning in the absence of GNSS, vision, or other measurements anchored in absolute world coordinates, the position solution is defined in the same datum/epoch specified by the previous solution type (e.g., WGS-84 if previously standalone GNSS, i.e., SolutionType::AutonomousGPS).
Definition at line 122 of file solution.h.
p1_time
|
The time of the message, in P1 time (beginning at power-on).
Definition at line 49 of file solution.h.
position_std_enu_m
solution_type
|
The type of this position solution.
Definition at line 55 of file solution.h.
undulation_cm
|
The geoid undulation at the current location (in cm).
Geoid undulation is also frequently referred to as "geoid height". It is the height of the MSL geoid above the WGS-84 ellipsoid. Note that it is independent of the location of the receiver.
Receiver ellipsoid altitude reported in lla_deg (also frequently called "height above the ellipsoid") can be converted to a corresponding mean sea level (MSL) altitude ("height above the geoid" or "orthometric height") as follows:
\[
h_{orthometric} = h_{ellipsoid} - undulation
\]
Stored in units of 0.01 meters: undulation_m = undulation_cm * 0.01. Set to -32768 if invalid.
Added in PoseMessage version 1.1.
Definition at line 85 of file solution.h.
velocity_body_mps
velocity_std_body_mps
vertical_protection_level_m
|
The estimated vertical protection level (in meters).
Definition at line 166 of file solution.h.
ypr_deg
The platform attitude (in degrees), if known, described as intrinsic Euler-321 angles (yaw, pitch, roll) with respect to the local ENU tangent plane.
Set to NAN if attitude is not available.
The platform body axes are defined as +x forward, +y left, and +z up. A positive yaw is a left turn, positive pitch points the nose of the vehicle down, and positive roll is a roll toward the right. Yaw is measured from east in a counter-clockwise direction. For example, north is +90 degrees (i.e., heading = 90 - ypr_deg[0]).
Definition at line 142 of file solution.h.
ypr_std_deg
Public Static Attributes
FLAG_STATIONARY
| constexpr static |
Set if the device is stationary.
Definition at line 46 of file solution.h.
INVALID_UNDULATION
| constexpr static |
Definition at line 43 of file solution.h.
MESSAGE_TYPE
| constexpr static |
Definition at line 41 of file solution.h.
MESSAGE_VERSION
| constexpr static |
Definition at line 42 of file solution.h.
The documentation for this struct was generated from the following file:
Generated via doxygen2docusaurus 2.0.0 by Doxygen 1.9.8.