Go to the documentation of this file.
11 namespace fusion_engine {
69 return "Timestamped on Reception";
71 return "Sender System Time";
75 return "Unrecognized";
83 stream <<
to_string(val) <<
" (" << (int)val <<
")";
132 uint8_t reserved[3] = {0};
226 return "Unrecognized";
234 stream <<
to_string(val) <<
" (" << (int)val <<
")";
289 uint8_t reserved[2] = {0};
333 uint8_t reserved[2] = {0};
395 uint8_t reserved[3] = {0};
440 uint8_t reserved[3] = {0};
static constexpr MessageType MESSAGE_TYPE
@ GPS_TIME
Message timestamped in GPS time, referenced to 1980/1/6.
SystemTimeSource
The source of a point_one::fusion_engine::messages::Timestamp used to represent the time of applicabi...
static constexpr uint8_t MESSAGE_VERSION
static constexpr uint8_t MESSAGE_VERSION
static constexpr MessageType MESSAGE_TYPE
MessageType
Identifiers for the defined output message types.
@ INVALID
Timestamp not valid.
SystemTimeSource measurement_time_source
The source for measurement_time.
GearType gear
The transmission gear currently in use, or direction of motion, if available.
Differential wheel speed measurement (MessageType::WHEEL_SPEED_MEASUREMENT, version 1....
static constexpr MessageType MESSAGE_TYPE
@ TIMESTAMPED_ON_RECEPTION
Message timestamped in system time, generated when received by the device.
@ VEHICLE_TICK_MEASUREMENT
VehicleTickMeasurement
@ VEHICLE_SPEED_MEASUREMENT
VehicleSpeedMeasurement
The time of applicability for an incoming sensor measurement.
double accel_std_mps2[3]
Corrected vehicle x/y/z acceleration standard deviation (in meters/second^2), resolved in the body fr...
static constexpr MessageType MESSAGE_TYPE
@ NEUTRAL
The vehicle is in neutral.
MeasurementTimestamps timestamps
Measurement timestamps, if available.
Differential wheel encoder tick measurement (MessageType::WHEEL_TICK_MEASUREMENT, version 1....
float vehicle_speed_mps
The current vehicle speed estimate (in m/s).
The base class for all message payloads.
IMU sensor measurement data (MessageType::IMU_MEASUREMENT, version 1.0).
@ IMU_MEASUREMENT
IMUMeasurement
@ SENDER_SYSTEM_TIME
Message timestamp was generated from a monotonic clock of an external system.
@ WHEEL_SPEED_MEASUREMENT
WheelSpeedMeasurement
@ REVERSE
The vehicle is in reverse.
double gyro_rps[3]
Corrected vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame.
Timestamp p1_time
The P1 time corresponding with the measurement time of applicability, if available.
MeasurementTimestamps timestamps
Measurement timestamps, if available.
static constexpr uint8_t MESSAGE_VERSION
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
GearType gear
The transmission gear currently in use, or direction of motion, if available.
float front_left_speed_mps
The front left wheel speed (in m/s).
float front_right_speed_mps
The front right wheel speed (in m/s).
uint32_t rear_right_wheel_ticks
The rear right wheel ticks.
GearType
The current transmission gear used by the vehicle.
GearType gear
The transmission gear currently in use, or direction of motion, if available.
Timestamp measurement_time
The measurement time of applicability, if available, in a user-specified time base.
float rear_right_speed_mps
The rear right wheel speed (in m/s).
uint32_t tick_count
The current encoder tick count.
float rear_left_speed_mps
The rear left wheel speed (in m/s).
static constexpr MessageType MESSAGE_TYPE
@ WHEEL_TICK_MEASUREMENT
WheelTickMeasurement
static constexpr uint8_t MESSAGE_VERSION
bool is_signed
true if the wheel speeds are signed (positive forward, negative reverse), or false if the values are ...
MeasurementTimestamps timestamps
Measurement timestamps, if available.
Singular wheel encoder tick measurement, representing vehicle body speed (MessageType::VEHICLE_TICK_M...
uint32_t front_left_wheel_ticks
The front left wheel ticks.
Vehicle body speed measurement (MessageType::VEHICLE_SPEED_MEASUREMENT, version 1....
@ P1_TIME
Message timestamped in P1 time.
std::ostream & operator<<(std::ostream &stream, ConfigType type)
ConfigType stream operator.
@ FORWARD
The vehicle is in a forward gear.
Point One FusionEngine output message common definitions.
@ PARK
The vehicle is parked.
Generic timestamp representation.
uint32_t rear_left_wheel_ticks
The rear left wheel ticks.
double accel_mps2[3]
Corrected vehicle x/y/z acceleration (in meters/second^2), resolved in the body frame.
const char * to_string(ConfigType type)
Get a human-friendly string name for the specified ConfigType.
GearType gear
The transmission gear currently in use, or direction of motion, if available.
double gyro_std_rps[3]
Corrected vehicle x/y/z rate of rotation standard deviation (in radians/second), resolved in the body...
bool is_signed
true if the wheel speeds are signed (positive forward, negative reverse), or false if the values are ...
@ UNKNOWN
The transmission gear is not known, or does not map to a supported GearType.
MeasurementTimestamps timestamps
Measurement timestamps, if available.
static constexpr uint8_t MESSAGE_VERSION
uint32_t front_right_wheel_ticks
The front right wheel ticks.