Skip to content

Commit

Permalink
Revert "added ChoreoLib2025.json to git"
Browse files Browse the repository at this point in the history
This reverts commit 9e9de78
  • Loading branch information
jpothen8 committed Jan 18, 2025
1 parent 3f7fbe9 commit 9d03c72
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 59 deletions.
20 changes: 9 additions & 11 deletions src/main/kotlin/frc/team449/subsystems/drive/DriveSubsystem.kt
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,16 @@ import edu.wpi.first.math.geometry.Translation2d
import edu.wpi.first.math.kinematics.ChassisSpeeds
import edu.wpi.first.wpilibj2.command.Subsystem


/** A drivetrain that uses closed-loop velocity control. */
interface DriveSubsystem : Subsystem {

private val xController: PIDController
get() = PIDController(10.0, 0.0, 0.0)
private val yController: PIDController
get() = PIDController(10.0, 0.0, 0.0)
get()=PIDController(10.0, 0.0, 0.0)
private val headingController: PIDController
get() = PIDController(7.5, 0.0, 0.0)
get()= PIDController(7.5, 0.0, 0.0)

var heading: Rotation2d
get() = Rotation2d(MathUtil.angleModulus(this.pose.rotation.radians))
Expand All @@ -27,12 +28,12 @@ interface DriveSubsystem : Subsystem {

var pose: Pose2d

fun getPos(): Pose2d {
return Pose2d(pose.x, pose.y, heading)
fun getPose(): Pose2d {
return Pose2d(pose.x , pose.y , heading)
}
fun followTrajectory(sample: SwerveSample) {
// Get the current pose of the robot
val pose: Pose2d = getPos()
val pose: Pose2d = getPose();

// Generate the next speeds for the robot
val speeds: ChassisSpeeds = ChassisSpeeds(
Expand All @@ -47,15 +48,12 @@ interface DriveSubsystem : Subsystem {

fun driveFieldRelative(speeds: ChassisSpeeds)

/** Sets the drivetrain's desired speeds. */
fun set(desiredSpeeds: ChassisSpeeds){

}
/** Sets the drivetrain's desired speeds. */
fun set(desiredSpeeds: ChassisSpeeds)

/** Sets all the robot's drive motors to 0. */
fun stop(){

}
fun stop()

/**
* Used to simulate a drivetrain. Only one instance of this class should be made per drivetrain.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,10 +105,6 @@ open class DifferentialDrive(
this.poseEstimator.resetPosition(ahrs.heading, leftEncoder.position, rightEncoder.position, pose)
}

override fun driveFieldRelative(speeds: ChassisSpeeds) {
TODO("Not yet implemented")
}

override fun stop() {
this.set(ChassisSpeeds(0.0, 0.0, 0.0))
}
Expand Down
44 changes: 0 additions & 44 deletions vendordeps/ChoreoLib2025.json

This file was deleted.

0 comments on commit 9d03c72

Please sign in to comment.