Skip to content

Commit 3e6db97

Browse files
Fixed crashing by removing phase correction. Added units to driveToPose.
Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
1 parent 8efd746 commit 3e6db97

File tree

5 files changed

+25
-14
lines changed

5 files changed

+25
-14
lines changed

simgui.json

+1
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,7 @@
6060
"/LiveWindow/Ungrouped/PIDController[1]": "PIDController",
6161
"/LiveWindow/Ungrouped/Pigeon 2 [13]": "Gyro",
6262
"/LiveWindow/Ungrouped/Scheduler": "Scheduler",
63+
"/SmartDashboard/Alerts": "Alerts",
6364
"/SmartDashboard/Encoders": "Alerts",
6465
"/SmartDashboard/Field": "Field2d",
6566
"/SmartDashboard/IMU": "Alerts",

src/main/java/frc/robot/RobotContainer.java

+19-1
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,11 @@
55
package frc.robot;
66

77
import com.pathplanner.lib.auto.NamedCommands;
8+
import edu.wpi.first.math.controller.ProfiledPIDController;
89
import edu.wpi.first.math.geometry.Pose2d;
910
import edu.wpi.first.math.geometry.Rotation2d;
1011
import edu.wpi.first.math.geometry.Translation2d;
12+
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
1113
import edu.wpi.first.wpilibj.DriverStation;
1214
import edu.wpi.first.wpilibj.Filesystem;
1315
import edu.wpi.first.wpilibj.RobotBase;
@@ -104,7 +106,6 @@ public RobotContainer()
104106
*/
105107
private void configureBindings()
106108
{
107-
108109
Command driveFieldOrientedDirectAngle = drivebase.driveFieldOriented(driveDirectAngle);
109110
Command driveFieldOrientedAnglularVelocity = drivebase.driveFieldOriented(driveAngularVelocity);
110111
Command driveRobotOrientedAngularVelocity = drivebase.driveFieldOriented(driveRobotOriented);
@@ -125,8 +126,25 @@ private void configureBindings()
125126

126127
if (Robot.isSimulation())
127128
{
129+
driveDirectAngleKeyboard.driveToPose(() -> new Pose2d(new Translation2d(9, 3),
130+
Rotation2d.fromDegrees(90)),
131+
new ProfiledPIDController(5,
132+
0,
133+
0,
134+
new Constraints(5,
135+
3)),
136+
new ProfiledPIDController(5,
137+
0,
138+
0,
139+
new Constraints(
140+
Math.toRadians(
141+
360),
142+
Math.toRadians(
143+
90))));
128144
driverXbox.start().onTrue(Commands.runOnce(() -> drivebase.resetOdometry(new Pose2d(3, 3, new Rotation2d()))));
129145
driverXbox.button(1).whileTrue(drivebase.sysIdDriveMotorCommand());
146+
driverXbox.button(2).whileTrue(Commands.runEnd(() -> driveDirectAngleKeyboard.driveToPoseEnabled(true),
147+
() -> driveDirectAngleKeyboard.driveToPoseEnabled(false)));
130148

131149
}
132150
if (DriverStation.isTest())

src/main/java/swervelib/SwerveInputStream.java

+5-5
Original file line numberDiff line numberDiff line change
@@ -273,9 +273,9 @@ public SwerveInputStream robotRelative(boolean enabled)
273273
* Drive to a given pose with the provided {@link ProfiledPIDController}s
274274
*
275275
* @param pose {@link Supplier<Pose2d>} for ease of use.
276-
* @param xPIDController PID controller for the X axis.
277-
* @param yPIDController PID controller for the Y axis.
278-
* @param omegaPIDController PID Controller for rotational axis.
276+
* @param xPIDController PID controller for the X axis, units are m/s.
277+
* @param yPIDController PID controller for the Y axis, units are m/s.
278+
* @param omegaPIDController PID Controller for rotational axis, units are rad/s.
279279
* @return self
280280
*/
281281
public SwerveInputStream driveToPose(Supplier<Pose2d> pose, ProfiledPIDController xPIDController,
@@ -292,8 +292,8 @@ public SwerveInputStream driveToPose(Supplier<Pose2d> pose, ProfiledPIDControlle
292292
* Drive to a given pose with the provided {@link ProfiledPIDController}s
293293
*
294294
* @param pose {@link Supplier<Pose2d>} for ease of use.
295-
* @param translation PID controller for the X and Y axis.
296-
* @param rotation PID Controller for rotational axis.
295+
* @param translation PID controller for the X and Y axis, units are m/s.
296+
* @param rotation PID Controller for rotational axis, units are rad/s.
297297
* @return self
298298
*/
299299
public SwerveInputStream driveToPose(Supplier<Pose2d> pose, ProfiledPIDController translation,

src/main/java/swervelib/motors/SparkFlexSwerve.java

-4
Original file line numberDiff line numberDiff line change
@@ -384,10 +384,6 @@ public void setMotorBrake(boolean isBrakeMode)
384384
public void setInverted(boolean inverted)
385385
{
386386
cfg.inverted(inverted);
387-
if (isDriveMotor)
388-
{
389-
cfg.encoder.inverted(inverted);
390-
}
391387
}
392388

393389
/**

src/main/java/swervelib/motors/SparkMaxSwerve.java

-4
Original file line numberDiff line numberDiff line change
@@ -383,10 +383,6 @@ public void setMotorBrake(boolean isBrakeMode)
383383
public void setInverted(boolean inverted)
384384
{
385385
cfg.inverted(inverted);
386-
if (isDriveMotor)
387-
{
388-
cfg.encoder.inverted(inverted);
389-
}
390386
}
391387

392388
/**

0 commit comments

Comments
 (0)