MecanumLocalizer

public final class MecanumLocalizer implements DeadReckoningLocalizer

Default localizer for mecanum drives based on the drive encoders.

Parameters

getWheelPositions

wheel positions in linear distance units

getWheelVelocities

lateral distance between pairs of wheels on different sides of the robot

wheelBase

distance between pairs of wheels on the same side of the robot

lateralMultiplier

lateral multiplier

Constructors

Link copied to clipboard
public MecanumLocalizer MecanumLocalizer(Function0<List<Double>> getWheelPositions, Function0<List<Double>> getWheelVelocities, Double trackWidth, Double wheelBase, Double lateralMultiplier)
public MecanumLocalizer MecanumLocalizer(Function0<List<Double>> getWheelPositions, Function0<List<Double>> getWheelVelocities, Double trackWidth, Double wheelBase)
public MecanumLocalizer MecanumLocalizer(Function0<List<Double>> getWheelPositions, Function0<List<Double>> getWheelVelocities, Double trackWidth)
public MecanumLocalizer MecanumLocalizer(Function0<List<Double>> getWheelPositions, Double trackWidth)

Properties

Link copied to clipboard
public final Function0<List<Double>> getWheelPositions
Link copied to clipboard
public final Function0<List<Double>> getWheelVelocities
Link copied to clipboard
private final Pose2d lastRobotPoseDelta

The last computed change in relative robot position.

Link copied to clipboard

Current robot pose estimate.

Link copied to clipboard
private final Pose2d poseVelocity

Current robot pose velocity (optional)

Functions

Link copied to clipboard

The last computed change in relative robot position.

Link copied to clipboard

Current robot pose estimate.

Link copied to clipboard

Current robot pose velocity (optional)

Link copied to clipboard
public Unit setPoseEstimate(Pose2d poseEstimate)

Current robot pose estimate.

Link copied to clipboard
public Unit update()

Completes a single localization update.