Go to the documentation of this file.
12 namespace fusion_engine {
70 return "Hardware I/O";
78 return "Unrecognized";
86 stream <<
to_string(val) <<
" (" << (int)val <<
")";
132 return "Timestamped on Reception";
134 return "Sender System Time";
138 return "Unrecognized";
146 stream <<
to_string(val) <<
" (" << (int)val <<
")";
210 uint8_t reserved[2] = {0};
244 static constexpr uint8_t MESSAGE_VERSION = 0;
252 uint8_t reserved[6] = {0};
257 int16_t temperature = INT16_MAX;
263 int32_t accel[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
269 int32_t gyro[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
286 static constexpr uint8_t MESSAGE_VERSION = 0;
295 double accel_mps2[3] = {NAN, NAN, NAN};
301 double accel_std_mps2[3] = {NAN, NAN, NAN};
307 double gyro_rps[3] = {NAN, NAN, NAN};
313 double gyro_std_rps[3] = {NAN, NAN, NAN};
329 static constexpr uint8_t MESSAGE_VERSION = 0;
337 uint8_t reserved[6] = {0};
342 int16_t temperature = INT16_MAX;
348 int32_t accel[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
354 int32_t gyro[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
398 return "Unrecognized";
406 stream <<
to_string(val) <<
" (" << (int)val <<
")";
436 static constexpr uint8_t MESSAGE_VERSION = 0;
443 static constexpr uint8_t FLAG_SIGNED = 0x1;
455 int32_t front_left_speed = INT32_MAX;
461 int32_t front_right_speed = INT32_MAX;
467 int32_t rear_left_speed = INT32_MAX;
473 int32_t rear_right_speed = INT32_MAX;
487 uint8_t reserved[2] = {0};
515 static constexpr uint8_t MESSAGE_VERSION = 0;
522 static constexpr uint8_t FLAG_SIGNED = 0x1;
541 uint8_t reserved = 0;
544 float front_left_speed_mps = NAN;
547 float front_right_speed_mps = NAN;
550 float rear_left_speed_mps = NAN;
553 float rear_right_speed_mps = NAN;
570 static constexpr uint8_t MESSAGE_VERSION = 0;
577 static constexpr uint8_t FLAG_SIGNED = 0x1;
589 int32_t front_left_speed = INT32_MAX;
595 int32_t front_right_speed = INT32_MAX;
601 int32_t rear_left_speed = INT32_MAX;
607 int32_t rear_right_speed = INT32_MAX;
621 uint8_t reserved[2] = {0};
653 static constexpr uint8_t MESSAGE_VERSION = 0;
660 static constexpr uint8_t FLAG_SIGNED = 0x1;
672 int32_t vehicle_speed = INT32_MAX;
686 uint8_t reserved[2] = {0};
713 static constexpr uint8_t MESSAGE_VERSION = 0;
720 static constexpr uint8_t FLAG_SIGNED = 0x1;
742 uint8_t reserved = 0;
745 float vehicle_speed_mps = NAN;
763 static constexpr uint8_t MESSAGE_VERSION = 0;
770 static constexpr uint8_t FLAG_SIGNED = 0x1;
782 int32_t vehicle_speed = INT32_MAX;
796 uint8_t reserved[2] = {0};
826 static constexpr uint8_t MESSAGE_VERSION = 0;
838 uint32_t front_left_wheel_ticks = 0;
844 uint32_t front_right_wheel_ticks = 0;
850 uint32_t rear_left_wheel_ticks = 0;
856 uint32_t rear_right_wheel_ticks = 0;
867 uint8_t reserved[3] = {0};
890 static constexpr uint8_t MESSAGE_VERSION = 0;
902 uint32_t front_left_wheel_ticks = 0;
908 uint32_t front_right_wheel_ticks = 0;
914 uint32_t rear_left_wheel_ticks = 0;
920 uint32_t rear_right_wheel_ticks = 0;
931 uint8_t reserved[3] = {0};
964 static constexpr uint8_t MESSAGE_VERSION = 0;
976 uint32_t tick_count = 0;
987 uint8_t reserved[3] = {0};
1010 static constexpr uint8_t MESSAGE_VERSION = 0;
1022 uint32_t tick_count = 0;
1033 uint8_t reserved[3] = {0};
1053 static constexpr uint8_t MESSAGE_VERSION = 0;
1062 float front_left_speed_mps = NAN;
1065 float front_right_speed_mps = NAN;
1068 float rear_left_speed_mps = NAN;
1071 float rear_right_speed_mps = NAN;
1086 bool is_signed =
true;
1088 uint8_t reserved[2] = {0};
1104 static constexpr uint8_t MESSAGE_VERSION = 0;
1113 float vehicle_speed_mps = NAN;
1128 bool is_signed =
true;
1130 uint8_t reserved[2] = {0};
1161 static constexpr uint8_t MESSAGE_VERSION = 0;
1175 uint8_t reserved[3] = {0};
1194 float ypr_deg[3] = {NAN, NAN, NAN};
1199 float ypr_std_deg[3] = {NAN, NAN, NAN};
1204 float baseline_distance_m = NAN;
1209 float baseline_distance_std_m = NAN;
1229 static constexpr uint8_t MESSAGE_VERSION = 0;
1243 uint8_t reserved[3] = {0};
1258 float relative_position_enu_m[3] = {NAN, NAN, NAN};
1264 float position_std_enu_m[3] = {NAN, NAN, NAN};
1286 static constexpr uint8_t MESSAGE_VERSION = 0;
1288 #if !defined(_MSC_VER)
1298 #if defined(_MSC_VER)
1303 uint8_t system_time_cs_bytes[5] = {0};
1312 uint8_t reserved[1] = {0};
1315 uint16_t data_type = 0;
1326 "InputDataWrapperMessage does not match expected packed size.");
@ RAW_VEHICLE_SPEED_OUTPUT
RawVehicleSpeedOutput
@ GPS_TIME
Message timestamped in GPS time, referenced to 1980/1/6.
@ CAN
Sensor data captured from a vehicle CAN bus.
SystemTimeSource
The source of a point_one::fusion_engine::messages::Timestamp used to represent the time of applicabi...
Raw (uncorrected) dfferential wheel encoder tick output (MessageType::RAW_WHEEL_TICK_OUTPUT,...
(Deprecated) Differential wheel speed measurement (MessageType::DEPRECATED_WHEEL_SPEED_MEASUREMENT,...
MessageType
Identifiers for the defined output message types.
Library portability helper definitions.
Raw (uncorrected) single wheel encoder tick output (MessageType::RAW_VEHICLE_TICK_OUTPUT,...
@ INVALID
Timestamp not valid.
SolutionType
Navigation solution type definitions.
P1_CONSTEXPR_FUNC const char * to_string(ConfigType type)
Get a human-friendly string name for the specified ConfigType.
Timestamp measurement_time
The measurement time of applicability, if available, in a user-specified time base.
@ RAW_VEHICLE_TICK_OUTPUT
RawVehicleTickOutput
@ DEPRECATED_WHEEL_SPEED_MEASUREMENT
DeprecatedWheelSpeedMeasurement
MeasurementDetails details
Measurement timestamp and additional information, if available.
Raw (uncorrected) vehicle body speed measurement output (MessageType::RAW_VEHICLE_SPEED_OUTPUT,...
@ SERIAL
Sensor data provided over a serial connection.
@ INPUT_DATA_WRAPPER
InputDataWrapperMessage
MeasurementDetails details
Measurement timestamp and additional information, if available.
@ RAW_WHEEL_SPEED_OUTPUT
RawWheelSpeedOutput
@ TIMESTAMPED_ON_RECEPTION
Message timestamped in system time, generated when received by the device.
MeasurementDetails details
Measurement timestamp and additional information, if available.
@ NEUTRAL
The vehicle is in neutral.
MeasurementDetails details
Measurement timestamp and additional information, if available.
Raw (uncorrected) dfferential wheel speed measurement output (MessageType::RAW_WHEEL_SPEED_OUTPUT,...
MeasurementDetails details
Measurement timestamp and additional information, if available.
Timestamp p1_time
The P1 time corresponding with the measurement time of applicability, if available.
@ DEPRECATED_VEHICLE_SPEED_MEASUREMENT
DeprecatedVehicleSpeedMeasurement
The base class for all message payloads.
Raw (uncorrected) IMU sensor measurement output (MessageType::RAW_IMU_OUTPUT, version 1....
SensorDataSource
The source of received sensor measurements, if known.
@ SENDER_SYSTEM_TIME
Message timestamp was generated from a monotonic clock of an external system.
MeasurementDetails details
Measurement timestamp and additional information, if available.
@ REVERSE
The vehicle is in reverse.
@ Invalid
Invalid, no position available.
GNSS signal and frequency type definitions.
@ GNSS_ATTITUDE_OUTPUT
GNSSAttitudeOutput
MeasurementDetails details
Measurement timestamp and additional information, if available.
@ RAW_GNSS_ATTITUDE_OUTPUT
RawGNSSAttitudeOutput
Timestamp p1_time
The time of the measurement, in P1 time (beginning at power-on).
@ RAW_IMU_OUTPUT
RawIMUOutput
GearType
The current transmission gear used by the vehicle.
Raw (uncorrected) GNSS attitude sensor measurement output (MessageType::RAW_GNSS_ATTITUDE_OUTPUT,...
IMU sensor measurement output with calibration and corrections applied (MessageType::IMU_OUTPUT,...
@ VEHICLE_SPEED_INPUT
VehicleSpeedInput
p1_ostream & operator<<(p1_ostream &stream, ConfigType type)
ConfigType stream operator.
MeasurementDetails details
Measurement timestamp and additional information, if available.
The time of applicability and additional information for an incoming sensor measurement.
@ NETWORK
Sensor data provided over a network connection.
@ WHEEL_SPEED_INPUT
WheelSpeedInput
@ UNKNOWN
Data source not known.
@ WHEEL_SPEED_OUTPUT
WheelSpeedOutput
@ RAW_WHEEL_TICK_OUTPUT
RawWheelTickOutput
#define P1_CONSTEXPR_FUNC
@ INTERNAL
Sensor data captured internal to the device (embedded IMU, GNSS receiver, etc.).
@ VEHICLE_SPEED_OUTPUT
VehicleSpeedOutput
@ VEHICLE_TICK_INPUT
VehicleTickInput
Timestamp p1_time
The time of the measurement, in P1 time (beginning at power-on).
MeasurementDetails details
Measurement timestamp and additional information, if available.
Timestamp p1_time
The time of the measurement, in P1 time (beginning at power-on).
(Deprecated) Vehicle body speed measurement (MessageType::DEPRECATED_VEHICLE_SPEED_MEASUREMENT,...
@ P1_TIME
Message timestamped in P1 time.
@ FORWARD
The vehicle is in a forward gear.
Point One FusionEngine output message common definitions.
@ PARK
The vehicle is parked.
Generic timestamp representation.
Vehicle body speed measurement output with calibration and corrections applied (MessageType::VEHICLE_...
@ HARDWARE_IO
Sensor data generated via hardware voltage signal (wheel tick, external event, etc....
@ UNKNOWN
The transmission gear is not known, or does not map to a supported GearType.
Differential wheel speed measurement output with calibration and corrections applied (MessageType::WH...
Multi-antenna GNSS attitude sensor measurement output with offset corrections applied (MessageType::G...
@ WHEEL_TICK_INPUT
WheelTickInput