TwoDeadWheelLocalizer

class TwoDeadWheelLocalizer @JvmOverloads constructor(val hardwareMap: HardwareMap, val imu: IMU, var inPerTick: Double, val parName: String, val perpName: String, var parYTicks: Double = 0.0, var perpXTicks: Double = 0.0, val parDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, val perpDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, val initialPose: Pose2d = Pose2d.zero) : Localizer

Localizer based on two dead wheels and an IMU.

Parameters

hardwareMap

hardware map

imu

IMU

inPerTick

inches per tick

parName

name of the parallel encoder

perpName

name of the perpendicular encoder

parYTicks

y-position of the parallel encoder (in tick units)

perpXTicks

x-position of the perpendicular encoder (in tick units)

parDirection

direction of the parallel encoder

perpDirection

direction of the perpendicular encoder

initialPose

initial pose

Constructors

Link copied to clipboard
constructor(hardwareMap: HardwareMap, imu: IMU, inPerTick: Double, parName: String, perpName: String, parYTicks: Double = 0.0, perpXTicks: Double = 0.0, parDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, perpDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, initialPose: Pose2d = Pose2d.zero)

Properties

Link copied to clipboard
val hardwareMap: HardwareMap
Link copied to clipboard
val imu: IMU
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
val parDirection: DcMotorSimple.Direction
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
val perpDirection: DcMotorSimple.Direction
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
open override var pose: Pose2d

The current robot pose.

Link copied to clipboard
open override val poseHistory: MutableList<Pose2d>

A list of recent poses.

Link copied to clipboard
open override var vel: PoseVelocity2d

The current robot velocity.

Functions

Link copied to clipboard
open override fun update(): PoseVelocity2d

Updates the localizer and returns the new velocity.

Link copied to clipboard
fun withDirections(parDirection: DcMotorSimple.Direction, perpDirection: DcMotorSimple.Direction): TwoDeadWheelLocalizer

Returns a new localizer with the given encoder directions.

Link copied to clipboard

Returns a new localizer with the given initial pose.

Link copied to clipboard
fun withLocations(parYTicks: Double, perpXTicks: Double): TwoDeadWheelLocalizer

Returns a new localizer with the given encoder locations.

Link copied to clipboard
fun withNames(parName: String, perpName: String): TwoDeadWheelLocalizer

Returns a new localizer with the given encoder names.