Skip to content

Commit 3929014

Browse files
committed
fixed problems
1 parent 1e741ac commit 3929014

File tree

3 files changed

+13
-7
lines changed

3 files changed

+13
-7
lines changed

src/main/java/frc/robot/commands/Drive.java

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,13 +64,20 @@ public void initialize() {
6464
public void execute() {
6565
double x = xSupplier.getAsDouble();
6666
double y = ySupplier.getAsDouble();
67+
double rotation = rotationSupplier.getAsDouble();
68+
boolean fieldRelative = fieldRelativeSupplier.getAsBoolean();
69+
6770
if (shouldMirror.getAsBoolean()) {
6871
x *= -1;
6972
y *= -1;
7073
}
71-
use the following variables to drive the swerve using swerve.drive
74+
swerve.drive(x, y, rotation, fieldRelative);
75+
76+
//use the following variables to drive the swerve using swerve.drive
77+
7278
}
7379

80+
7481
@Override
7582
public void end(boolean interrupted) {
7683
swerve.drive(0, 0, 0, false);

src/main/java/frc/robot/subsystems/Claw.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,7 @@ public class Claw extends SubsystemBase {
1111

1212
public Claw() {
1313

14-
set claw can id
15-
claw = new Neo(/*can id goes here*/);
14+
claw = new Neo(1);
1615
claw.restoreFactoryDefaults();
1716

1817
claw.setSmartCurrentLimit(30);

src/main/java/frc/robot/subsystems/Swerve.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
1515
import edu.wpi.first.math.kinematics.SwerveModulePosition;
1616
import edu.wpi.first.math.kinematics.SwerveModuleState;
17+
import edu.wpi.first.wpilibj.Timer;
1718
import frc.robot.util.ADIS16470_IMU;
1819
import edu.wpi.first.wpilibj2.command.Command;
1920
import edu.wpi.first.wpilibj2.command.SubsystemBase;
@@ -98,8 +99,9 @@ public Swerve() {
9899
@Override
99100
public void periodic() {
100101

101-
Update the poseEstimator using the current timestamp (from DriverUI.java), the gyro angle, and the current module states
102+
//Update the poseEstimator using the current timestamp (from DriverUI.java), the gyro angle, and the current module states
102103

104+
poseEstimator.updateWithTime(Timer.getFPGATimestamp(), getGyroAngle(), getModulePositions());
103105
if (FieldConstants.IS_SIMULATION) {
104106

105107
for (MAXSwerveModule mod : swerveModules) {
@@ -148,9 +150,7 @@ public void drive(double xSpeed, double ySpeed, double rotSpeed, boolean fieldRe
148150
rotSpeed *= (DriveConstants.DYNAMIC_MAX_ANGULAR_SPEED * speedMultiplier);
149151

150152
SwerveModuleState[] swerveModuleStates =
151-
DriveConstants.DRIVE_KINEMATICS.toSwerveModuleStates(
152-
153-
);
153+
DriveConstants.DRIVE_KINEMATICS.toSwerveModuleStates(new ChassisSpeeds(xSpeed, ySpeed, rotSpeed));
154154

155155
setModuleStates(swerveModuleStates);
156156
}

0 commit comments

Comments
 (0)