Skip to content

Commit

Permalink
bump deps, fix indentation in DriveToNote, and add comments
Browse files Browse the repository at this point in the history
  • Loading branch information
mpatankar6 committed Nov 24, 2024
1 parent 24a4cd6 commit a37213d
Show file tree
Hide file tree
Showing 7 changed files with 73 additions and 72 deletions.
1 change: 0 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
import frc.robot.arm.Arm;
import frc.robot.arm.Arm.ArmSetpoints;
import frc.robot.climber.Climber;
import frc.robot.drivetrain.DriveToNote;
import frc.robot.drivetrain.DriveToPose;
import frc.robot.drivetrain.Drivetrain;
import frc.robot.drivetrain.WheelRadiusCharacterization;
Expand Down
61 changes: 29 additions & 32 deletions src/main/java/frc/robot/drivetrain/DriveToNote.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,52 +2,49 @@

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.intake.Intake;
import frc.robot.lights.Lights;
import frc.robot.vision.GamePieceDetection;

public class DriveToNote extends Command {
private Drivetrain m_drivetrain;
private Lights m_lights;
private GamePieceDetection m_gamePieceDetection;
private Drivetrain m_drivetrain;
private Lights m_lights;
private GamePieceDetection m_gamePieceDetection;

private PIDController m_thetaController;
private PIDController m_thetaController;

private double m_horizontalOffset;
private double m_verticalOffset;
private double m_horizontalOffset;

public DriveToNote(Drivetrain drivetrain, Lights lights, GamePieceDetection gamePieceDetection, Intake intake) {
m_drivetrain = drivetrain;
m_lights = lights;
m_gamePieceDetection = gamePieceDetection;
public DriveToNote(
Drivetrain drivetrain, Lights lights, GamePieceDetection gamePieceDetection, Intake intake) {
m_drivetrain = drivetrain;
m_lights = lights;
m_gamePieceDetection = gamePieceDetection;

m_thetaController = new PIDController(5.0, 0.0, 0.0);
m_thetaController = new PIDController(5.0, 0.0, 0.0);

m_horizontalOffset = m_gamePieceDetection.getHorizontalOffsetDeg();
m_verticalOffset = m_gamePieceDetection.getVerticalOffsetDeg();
m_horizontalOffset = m_gamePieceDetection.getHorizontalOffsetDeg();

m_thetaController.setTolerance(1);
}
m_thetaController.setTolerance(1);
}

@Override
public void initialize() {}
@Override
public void initialize() {}

@Override
public void execute() {
m_horizontalOffset = m_gamePieceDetection.getHorizontalOffsetDeg();
m_verticalOffset = m_gamePieceDetection.getVerticalOffsetDeg();
m_drivetrain.runVelocity(
new ChassisSpeeds(0.0, 0.0, m_thetaController.calculate(m_horizontalOffset, 0)));
// m_lights.setBlink(Color.kMidnightBlue);
}
@Override
public void execute() {
m_horizontalOffset = m_gamePieceDetection.getHorizontalOffsetDeg();
m_drivetrain.runVelocity(
new ChassisSpeeds(0.0, 0.0, m_thetaController.calculate(m_horizontalOffset, 0)));
// m_lights.setBlink(Color.kMidnightBlue);
}

@Override
public void end(boolean interrupted) {}
@Override
public void end(boolean interrupted) {}

@Override
public boolean isFinished() {
return false;
@Override
public boolean isFinished() {
return false;
}
}
}
13 changes: 7 additions & 6 deletions src/main/java/frc/robot/drivetrain/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ public class Drivetrain extends SubsystemBase {

private static final double kTrackwidthMeters = Units.inchesToMeters(20.75);
private static double kWheelbaseMeters = Units.inchesToMeters(15.75);
// @todo What order are these in? Is it Front Left then Clockwise

// Front left, front right, back left, back right
private static final Translation2d[] m_modulePositions =
new Translation2d[] {
new Translation2d(kTrackwidthMeters / 2.0, kWheelbaseMeters / 2.0),
Expand Down Expand Up @@ -159,7 +159,8 @@ public void periodic() {
SwerveModulePosition[] newModulePositions = new SwerveModulePosition[m_modules.length];
SwerveModulePosition[] moduleDeltas = new SwerveModulePosition[4];
for (int moduleIndex = 0; moduleIndex < m_modules.length; moduleIndex++) {
newModulePositions[moduleIndex] = m_modules[moduleIndex].getOdometryPositions()[updateIndex];
newModulePositions[moduleIndex] =
m_modules[moduleIndex].getOdometryPositions()[updateIndex];
moduleDeltas[moduleIndex] =
new SwerveModulePosition(
newModulePositions[moduleIndex].distanceMeters
Expand All @@ -172,7 +173,8 @@ public void periodic() {
if (m_imuInputs.connected) {
m_gyroRotation = m_imuInputs.odometryYawPositions[updateIndex];
} else {
//when does this code run? Was this added when we had the pidgeon issue at worlds?
// When the gyro is not connected, we can simulate the robot's heading using the module
// states through the rotational component of the derived chassis speeds
final Twist2d twist = swerveKinematics.toTwist2d(moduleDeltas);
m_gyroRotation = m_gyroRotation.plus(new Rotation2d(twist.dtheta));
}
Expand Down Expand Up @@ -247,8 +249,7 @@ public Command joystickDrive(
* drive, no path following)
*/
public Command blankDrive() {
return this.run(() ->
runVelocity(new ChassisSpeeds(0.0, 0.0, 0.0)));
return this.run(() -> runVelocity(new ChassisSpeeds(0.0, 0.0, 0.0)));
}

public Command zeroGyro() {
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/vision/Vision.java
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,10 @@ public void periodic() {
.ifPresent(
tagPose ->
m_lastDetectionTimeIds.put(
target.getFiducialId(), Timer.getFPGATimestamp())); //shouldn't this be the timestamp of capture on the photonvision processor and not our timestamp
target.getFiducialId(),
// The timestamp used here is not important, as it is only used
// for visualization purposes.
Timer.getFPGATimestamp()));
});
m_allEstimatedPosesToLog.add(estimatedPose);
m_newVisionUpdates.add(
Expand Down
11 changes: 6 additions & 5 deletions vendordeps/ChoreoLib.json
Original file line number Diff line number Diff line change
@@ -1,18 +1,19 @@
{
"fileName": "ChoreoLib.json",
"name": "ChoreoLib",
"version": "2024.1.3",
"version": "2024.2.3",
"uuid": "287cff6e-1b60-4412-8059-f6834fb30e30",
"frcYear": "2024",
"mavenUrls": [
"https://SleipnirGroup.github.io/ChoreoLib/dep"
"https://lib.choreo.autos/dep",
"https://repo1.maven.org/maven2"
],
"jsonUrl": "https://SleipnirGroup.github.io/ChoreoLib/dep/ChoreoLib.json",
"jsonUrl": "https://lib.choreo.autos/dep/ChoreoLib.json",
"javaDependencies": [
{
"groupId": "com.choreo.lib",
"artifactId": "ChoreoLib-java",
"version": "2024.2.2"
"version": "2024.2.3"
},
{
"groupId": "com.google.code.gson",
Expand All @@ -25,7 +26,7 @@
{
"groupId": "com.choreo.lib",
"artifactId": "ChoreoLib-cpp",
"version": "2024.2.2",
"version": "2024.2.3",
"libName": "ChoreoLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
6 changes: 3 additions & 3 deletions vendordeps/PathplannerLib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2024.2.7",
"version": "2024.2.8",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2024.2.7"
"version": "2024.2.8"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2024.2.7",
"version": "2024.2.8",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
Loading

0 comments on commit a37213d

Please sign in to comment.