Swerve Localizer
class SwerveLocalizer @JvmOverloads constructor(val hardwareMap: HardwareMap, val cpr: Int, var inPerTick: Double, val imu: IMU, val kinematics: SwerveKinematics, driveEncoders: List<Encoder>, steeringEncoders: List<Encoder>, val initialPose: Pose2d = Pose2d.zero) : Localizer
Localizer based on swerve drive encoders and an IMU. This localizer is not recommended for use with dead wheels.
Parameters
hardware Map
hardware map
cpr
counts per revolution of the steering encoders
in Per Tick
inches per tick of the drive encoders
imu
IMU
kinematics
swerve kinematics
drive Encoders
drive encoders
steering Encoders
steering encoders
initial Pose
initial pose
Constructors
Link copied to clipboard
constructor(hardwareMap: HardwareMap, cpr: Int, inPerTick: Double, imu: IMU, kinematics: SwerveKinematics, driveNames: List<String> = listOf("lfDrive", "frDrive", "blDrive", "brDrive"), steeringNames: List<String> = listOf("lfSteering", "rfSteering", "lbSteering", "rbSteering"), driveDirections: List<DcMotorSimple.Direction> = driveNames.map { DcMotorSimple.Direction.FORWARD }, steeringDirections: List<DcMotorSimple.Direction> = steeringNames.map { 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(driveDirections: List<DcMotorSimple.Direction>, steeringDirections: List<DcMotorSimple.Direction>): SwerveLocalizer
Returns a new localizer with the given motor directions.
Link copied to clipboard
Returns a new localizer with the given initial pose.