Go to the documentation of this file.
12 namespace fusion_engine {
70 return "Hardware I/O";
78 return "Unrecognized";
87 stream <<
to_string(val) <<
" (" << (int)val <<
")";
133 return "Timestamped on Reception";
135 return "Sender System Time";
139 return "Unrecognized";
148 stream <<
to_string(val) <<
" (" << (int)val <<
")";
212 uint8_t reserved[2] = {0};
246 static constexpr uint8_t MESSAGE_VERSION = 0;
254 uint8_t reserved[6] = {0};
259 int16_t temperature = INT16_MAX;
265 int32_t accel[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
271 int32_t gyro[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
288 static constexpr uint8_t MESSAGE_VERSION = 0;
297 double accel_mps2[3] = {NAN, NAN, NAN};
303 double accel_std_mps2[3] = {NAN, NAN, NAN};
309 double gyro_rps[3] = {NAN, NAN, NAN};
315 double gyro_std_rps[3] = {NAN, NAN, NAN};
331 static constexpr uint8_t MESSAGE_VERSION = 0;
339 uint8_t reserved[6] = {0};
344 int16_t temperature = INT16_MAX;
350 int32_t accel[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
356 int32_t gyro[3] = {INT32_MAX, INT32_MAX, INT32_MAX};
400 return "Unrecognized";
409 stream <<
to_string(val) <<
" (" << (int)val <<
")";
439 static constexpr uint8_t MESSAGE_VERSION = 0;
446 static constexpr uint8_t FLAG_SIGNED = 0x1;
458 int32_t front_left_speed = INT32_MAX;
464 int32_t front_right_speed = INT32_MAX;
470 int32_t rear_left_speed = INT32_MAX;
476 int32_t rear_right_speed = INT32_MAX;
490 uint8_t reserved[2] = {0};
518 static constexpr uint8_t MESSAGE_VERSION = 0;
525 static constexpr uint8_t FLAG_SIGNED = 0x1;
544 uint8_t reserved = 0;
547 float front_left_speed_mps = NAN;
550 float front_right_speed_mps = NAN;
553 float rear_left_speed_mps = NAN;
556 float rear_right_speed_mps = NAN;
573 static constexpr uint8_t MESSAGE_VERSION = 0;
580 static constexpr uint8_t FLAG_SIGNED = 0x1;
592 int32_t front_left_speed = INT32_MAX;
598 int32_t front_right_speed = INT32_MAX;
604 int32_t rear_left_speed = INT32_MAX;
610 int32_t rear_right_speed = INT32_MAX;
624 uint8_t reserved[2] = {0};
656 static constexpr uint8_t MESSAGE_VERSION = 0;
663 static constexpr uint8_t FLAG_SIGNED = 0x1;
675 int32_t vehicle_speed = INT32_MAX;
689 uint8_t reserved[2] = {0};
716 static constexpr uint8_t MESSAGE_VERSION = 0;
723 static constexpr uint8_t FLAG_SIGNED = 0x1;
745 uint8_t reserved = 0;
748 float vehicle_speed_mps = NAN;
766 static constexpr uint8_t MESSAGE_VERSION = 0;
773 static constexpr uint8_t FLAG_SIGNED = 0x1;
785 int32_t vehicle_speed = INT32_MAX;
799 uint8_t reserved[2] = {0};
829 static constexpr uint8_t MESSAGE_VERSION = 0;
841 uint32_t front_left_wheel_ticks = 0;
847 uint32_t front_right_wheel_ticks = 0;
853 uint32_t rear_left_wheel_ticks = 0;
859 uint32_t rear_right_wheel_ticks = 0;
870 uint8_t reserved[3] = {0};
893 static constexpr uint8_t MESSAGE_VERSION = 0;
905 uint32_t front_left_wheel_ticks = 0;
911 uint32_t front_right_wheel_ticks = 0;
917 uint32_t rear_left_wheel_ticks = 0;
923 uint32_t rear_right_wheel_ticks = 0;
934 uint8_t reserved[3] = {0};
967 static constexpr uint8_t MESSAGE_VERSION = 0;
979 uint32_t tick_count = 0;
990 uint8_t reserved[3] = {0};
1013 static constexpr uint8_t MESSAGE_VERSION = 0;
1025 uint32_t tick_count = 0;
1036 uint8_t reserved[3] = {0};
1056 static constexpr uint8_t MESSAGE_VERSION = 0;
1065 float front_left_speed_mps = NAN;
1068 float front_right_speed_mps = NAN;
1071 float rear_left_speed_mps = NAN;
1074 float rear_right_speed_mps = NAN;
1089 bool is_signed =
true;
1091 uint8_t reserved[2] = {0};
1107 static constexpr uint8_t MESSAGE_VERSION = 0;
1116 float vehicle_speed_mps = NAN;
1131 bool is_signed =
true;
1133 uint8_t reserved[2] = {0};
1164 static constexpr uint8_t MESSAGE_VERSION = 0;
1178 uint8_t reserved[3] = {0};
1197 float ypr_deg[3] = {NAN, NAN, NAN};
1202 float ypr_std_deg[3] = {NAN, NAN, NAN};
1207 float baseline_distance_m = NAN;
1212 float baseline_distance_std_m = NAN;
1232 static constexpr uint8_t MESSAGE_VERSION = 0;
1246 uint8_t reserved[3] = {0};
1261 float relative_position_enu_m[3] = {NAN, NAN, NAN};
1267 float position_std_enu_m[3] = {NAN, NAN, NAN};
1289 static constexpr uint8_t MESSAGE_VERSION = 0;
1291 #if !defined(_MSC_VER)
1301 #if defined(_MSC_VER)
1306 uint8_t system_time_cs_bytes[5] = {0};
1315 uint8_t reserved[1] = {0};
1318 uint16_t data_type = 0;
1329 "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