Platform pose solution: position, velocity, attitude (MessageType::POSE). More...
#include <point_one/fusion_engine/messages/solution.h>
Public Attributes | |
float | aggregate_protection_level_m = NAN |
The estimated aggregate 3D protection level (in meters). 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 WGS-84 geodetic latitude, longitude, and altitude (in degrees/meters). 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... | |
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... | |
Platform pose solution: position, velocity, attitude (MessageType::POSE).
Definition at line 29 of file solution.h.
float point_one::fusion_engine::messages::PoseMessage::aggregate_protection_level_m = NAN |
The estimated aggregate 3D protection level (in meters).
Definition at line 84 of file solution.h.
Timestamp point_one::fusion_engine::messages::PoseMessage::gps_time |
The GPS time of the message, if available, referenced to 1980/1/6.
Definition at line 34 of file solution.h.
float point_one::fusion_engine::messages::PoseMessage::horizontal_protection_level_m = NAN |
The estimated 2D horizontal protection level (in meters).
Definition at line 86 of file solution.h.
double point_one::fusion_engine::messages::PoseMessage::lla_deg[3] = {NAN, NAN, NAN} |
The WGS-84 geodetic latitude, longitude, and altitude (in degrees/meters).
Definition at line 44 of file solution.h.
Timestamp point_one::fusion_engine::messages::PoseMessage::p1_time |
The time of the message, in P1 time (beginning at power-on).
Definition at line 31 of file solution.h.
float point_one::fusion_engine::messages::PoseMessage::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.
Definition at line 50 of file solution.h.
SolutionType point_one::fusion_engine::messages::PoseMessage::solution_type |
The type of this position solution.
Definition at line 37 of file solution.h.
double point_one::fusion_engine::messages::PoseMessage::velocity_body_mps[3] = {NAN, NAN, NAN} |
The platform velocity (in meters/second), resolved in the body frame.
Set to NAN
if attitude is not available for the body frame transformation.
Definition at line 75 of file solution.h.
float point_one::fusion_engine::messages::PoseMessage::velocity_std_body_mps[3] = {NAN, NAN, NAN} |
The velocity standard deviation (in meters/second), resolved in the body frame.
Definition at line 81 of file solution.h.
float point_one::fusion_engine::messages::PoseMessage::vertical_protection_level_m = NAN |
The estimated vertical protection level (in meters).
Definition at line 88 of file solution.h.
double point_one::fusion_engine::messages::PoseMessage::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.
Set to NAN
if attitude is not available.
heading = 90.0 - ypr_deg[0]
). Definition at line 64 of file solution.h.
float point_one::fusion_engine::messages::PoseMessage::ypr_std_deg[3] = {NAN, NAN, NAN} |
The attitude standard deviation (in degrees): yaw, pitch, roll.
Definition at line 69 of file solution.h.