Two Dead Wheel Localizer
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
hardware Map
hardware map
imu
IMU
in Per Tick
inches per tick
par Name
name of the parallel encoder
perp Name
name of the perpendicular encoder
par YTicks
y-position of the parallel encoder (in tick units)
perp XTicks
x-position of the perpendicular encoder (in tick units)
par Direction
direction of the parallel encoder
perp Direction
direction of the perpendicular encoder
initial Pose
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
Functions
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
Returns a new localizer with the given encoder locations.
Link copied to clipboard
Returns a new localizer with the given encoder names.