Mecanum Drive Localizer
class MecanumDriveLocalizer @JvmOverloads constructor(val hardwareMap: HardwareMap, var inPerTick: Double, val imu: IMU, val kinematics: MecanumKinematics, val leftFront: Encoder, val leftBack: Encoder, val rightFront: Encoder, val rightBack: Encoder, val initialPose: Pose2d = Pose2d.zero) : Localizer
Localizer based on mecanum drive encoders and an IMU. This localizer is not recommended for use with dead wheels.
Parameters
hardware Map
hardware map
in Per Tick
inches per tick
imu
IMU
kinematics
mecanum kinematics
left Front
left front encoder
left Back
left back encoder
right Front
right front encoder
right Back
right back encoder
initial Pose
initial pose
Constructors
Link copied to clipboard
constructor(hardwareMap: HardwareMap, inPerTick: Double, imu: IMU, kinematics: MecanumKinematics, lfName: String = "leftFront", lbName: String = "leftBack", rfName: String = "rightFront", rbName: String = "rightBack", lfDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, lbDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, rfDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, rbDirection: DcMotorSimple.Direction = DcMotorSimple.Direction.FORWARD, initialPose: Pose2d = Pose2d.zero)
Creates a new localizer.
Properties
Functions
Link copied to clipboard
Returns a new localizer with the given motors.
Link copied to clipboard
fun withDirections(lfDirection: DcMotorSimple.Direction, lbDirection: DcMotorSimple.Direction, rfDirection: DcMotorSimple.Direction, rbDirection: DcMotorSimple.Direction): MecanumDriveLocalizer
Returns a new localizer with the given motor directions.
Link copied to clipboard
Returns a new localizer with the given initial pose.