point_one::fusion_engine::messages::VehicleTickMeasurement Struct Reference

Singular wheel encoder tick measurement, representing vehicle body speed (MessageType::VEHICLE_TICK_MEASUREMENT, version 1.0). More...

#include <point_one/fusion_engine/messages/measurements.h>

Inheritance diagram for point_one::fusion_engine::messages::VehicleTickMeasurement:
point_one::fusion_engine::messages::MessagePayload

Public Attributes

GearType gear = GearType::UNKNOWN
 The transmission gear currently in use, or direction of motion, if available. More...
 
uint32_t tick_count = 0
 The current encoder tick count. More...
 
MeasurementTimestamps timestamps
 Measurement timestamps, if available. More...
 

Static Public Attributes

static constexpr MessageType MESSAGE_TYPE
 
static constexpr uint8_t MESSAGE_VERSION = 0
 

Detailed Description

Singular wheel encoder tick measurement, representing vehicle body speed (MessageType::VEHICLE_TICK_MEASUREMENT, version 1.0).

This message may be used to convey a single encoder tick count received by software (e.g., vehicle CAN bus), or captured in hardware from an external voltage pulse, which represents the along-track speed of the vehicle (forward/backward). The interpretation of the tick count values varies by vehicle. To use wheel encoder data, you ust first configure the device by issuing a SetConfigMessage message containing either a WheelConfig or HardwareTickConfig payload describing the vehicle sensor configuration.

Some platforms may support an additional, optional voltage signal used to indicate direction of motion. Alternatively, when receiving CAN data from a vehicle, direction may be conveyed explicitly in a CAN message, or may be indicated based on the current transmission gear setting.

Definition at line 417 of file measurements.h.

Member Data Documentation

◆ gear

GearType point_one::fusion_engine::messages::VehicleTickMeasurement::gear = GearType::UNKNOWN

The transmission gear currently in use, or direction of motion, if available.

Set to GearType::FORWARD or GearType::REVERSE where vehicle direction information is available externally.

Definition at line 438 of file measurements.h.

◆ MESSAGE_TYPE

constexpr MessageType point_one::fusion_engine::messages::VehicleTickMeasurement::MESSAGE_TYPE
staticconstexpr
Initial value:

Definition at line 418 of file measurements.h.

◆ MESSAGE_VERSION

constexpr uint8_t point_one::fusion_engine::messages::VehicleTickMeasurement::MESSAGE_VERSION = 0
staticconstexpr

Definition at line 420 of file measurements.h.

◆ tick_count

uint32_t point_one::fusion_engine::messages::VehicleTickMeasurement::tick_count = 0

The current encoder tick count.

The interpretation of these ticks is defined outside of this message.

Definition at line 429 of file measurements.h.

◆ timestamps

MeasurementTimestamps point_one::fusion_engine::messages::VehicleTickMeasurement::timestamps

Measurement timestamps, if available.

See Sensor Measurement Message Definitions.

Definition at line 423 of file measurements.h.


The documentation for this struct was generated from the following file:
@ VEHICLE_TICK_MEASUREMENT
VehicleTickMeasurement