ThreeDeadWheelLocalizer

class ThreeDeadWheelLocalizer @JvmOverloads constructor(val hardwareMap: HardwareMap, var inPerTick: Double, val par0Name: String = "par0", val par1Name: String = "par1", val perpName: String = "perp", var par0YTicks: Double = 0.0, var par1YTicks: Double = 1.0, var perpXTicks: Double = 0.0, val par0Direction: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, val par1Direction: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, val perpDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, val initialPose: Pose2d = Pose2d.zero) : Localizer

Localizer based on three dead wheels.

Parameters

hardwareMap

hardware map

inPerTick

inches per tick

par0Name

name of the first parallel encoder

par1Name

name of the second parallel encoder

perpName

name of the perpendicular encoder

par0YTicks

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

par1YTicks

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

perpXTicks

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

par0Direction

direction of the first parallel encoder

par1Direction

direction of the second parallel encoder

perpDirection

direction of the perpendicular encoder

initialPose

initial pose

Constructors

Link copied to clipboard
constructor(hardwareMap: HardwareMap, inPerTick: Double, par0Name: String = "par0", par1Name: String = "par1", perpName: String = "perp", par0YTicks: Double = 0.0, par1YTicks: Double = 1.0, perpXTicks: Double = 0.0, par0Direction: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, par1Direction: 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
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
val par0Direction: DcMotorSimple.Direction
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
val par1Direction: 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(par0Direction: DcMotorSimple.Direction, par1Direction: DcMotorSimple.Direction, perpDirection: DcMotorSimple.Direction): ThreeDeadWheelLocalizer

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(par0YTicks: Double, par1YTicks: Double, perpXTicks: Double): ThreeDeadWheelLocalizer

Returns a new localizer with the given encoder locations.

Link copied to clipboard
fun withNames(par0Name: String, par1Name: String, perpName: String): ThreeDeadWheelLocalizer

Returns a new localizer with the given encoder names.