Skip to content

Commit

Permalink
make dcmp changes
Browse files Browse the repository at this point in the history
  • Loading branch information
KPatel008 committed Apr 4, 2024
1 parent ebb820b commit 464657b
Show file tree
Hide file tree
Showing 16 changed files with 4,529 additions and 4,223 deletions.
2,968 changes: 1,539 additions & 1,429 deletions ChoreoProject.chor

Large diffs are not rendered by default.

831 changes: 420 additions & 411 deletions src/main/deploy/choreo/3PieceSourceSide.1.traj

Large diffs are not rendered by default.

621 changes: 315 additions & 306 deletions src/main/deploy/choreo/3PieceSourceSide.2.traj

Large diffs are not rendered by default.

729 changes: 396 additions & 333 deletions src/main/deploy/choreo/3PieceSourceSide.3.traj

Large diffs are not rendered by default.

667 changes: 338 additions & 329 deletions src/main/deploy/choreo/3PieceSourceSide.4.traj

Large diffs are not rendered by default.

2,824 changes: 1,457 additions & 1,367 deletions src/main/deploy/choreo/3PieceSourceSide.traj

Large diffs are not rendered by default.

8 changes: 4 additions & 4 deletions src/main/deploy/pathplanner/paths/CenterNoteToBottomNote.path
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@
},
{
"anchor": {
"x": 2.7506156436814293,
"y": 6.922939429924444
"x": 2.7272273347965497,
"y": 6.911245275482004
},
"prevControl": {
"x": 1.8301230761922098,
"y": 6.563970167686302
"x": 1.8067347673073302,
"y": 6.552276013243862
},
"nextControl": null,
"isLocked": false,
Expand Down
8 changes: 4 additions & 4 deletions src/main/deploy/pathplanner/paths/Centerline 1 to Shot.path
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@
},
{
"anchor": {
"x": 2.71,
"y": 5.55
"x": 2.8909454969907094,
"y": 5.5430292057165325
},
"prevControl": {
"x": 7.211301936709776,
"y": 7.058691480664211
"x": 7.392247433700485,
"y": 7.051720686380744
},
"nextControl": null,
"isLocked": false,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,13 @@
"waypoints": [
{
"anchor": {
"x": 2.7506156436814293,
"y": 6.922939429924444
"x": 2.7272273347965497,
"y": 6.911245275482004
},
"prevControl": null,
"nextControl": {
"x": 3.4091098039710737,
"y": 7.225831448054944
"x": 3.385721495086194,
"y": 7.214137293612504
},
"isLocked": false,
"linkedName": "WallSpike"
Expand Down
19 changes: 11 additions & 8 deletions src/main/java/frc/robot/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -87,9 +87,11 @@ public Command threePieceSourceSide() {
return Commands.sequence(
resetPose("3PieceSourceSide"),
aimAndShoot(),
intake().deadlineWith(getPathFollowingCommand("3PieceSourceSide.1")),
intake().raceWith(getPathFollowingCommand("3PieceSourceSide.1")),
getPathFollowingCommand("3PieceSourceSide.2"),
aimAndShoot(),
intake().deadlineWith(getPathFollowingCommand("3PieceSourceSide.2")),
intake().raceWith(getPathFollowingCommand("3PieceSourceSide.3")),
getPathFollowingCommand("3PieceSourceSide.4"),
aimAndShoot())
.withInterruptBehavior(InterruptionBehavior.kCancelIncoming)
.withName("Three Piece Source Side");
Expand All @@ -115,12 +117,13 @@ private Command toggleShootingWhileMoving() {
private Command getPathFollowingCommand(
String trajectoryName, ChoreoControlFunction controlFunction) {
return Choreo.choreoSwerveCommand(
Choreo.getTrajectory(trajectoryName),
PoseEstimation.getInstance()::getPose,
controlFunction,
m_drivetrain::runVelocity,
Constants.onRedAllianceSupplier,
m_drivetrain);
Choreo.getTrajectory(trajectoryName),
PoseEstimation.getInstance()::getPose,
controlFunction,
m_drivetrain::runVelocity,
Constants.onRedAllianceSupplier,
m_drivetrain)
.andThen(Commands.waitSeconds(3.0));
}

private Command getPathFollowingCommand(String trajectoryName) {
Expand Down
6 changes: 5 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,10 @@ public Robot() {
.onFalse(m_arm.holdSetpoint());
m_driverController.rightBumper().whileTrue(Superstructure.spit(m_shooter, m_feeder, m_intake));
m_operatorController.leftStick().onTrue(m_arm.goToSetpoint(ArmSetpoints.kClimb));
m_operatorController.rightStick().onTrue(m_arm.goToSetpoint(ArmSetpoints.kStash));
m_operatorController
.rightStick()
.whileTrue(m_arm.goToSetpoint(ArmSetpoints.kStash))
.onFalse(m_arm.goToSetpoint(ArmSetpoints.kStowed));
m_driverController.b().onTrue(m_arm.goToSetpoint(ArmSetpoints.kTrap));
m_driverController.b().whileTrue(Commands.parallel(m_climber.windWinch()));
m_driverController
Expand All @@ -259,6 +262,7 @@ public Robot() {
.onTrue(Commands.parallel(m_arm.aimWrist(2.083), m_shooter.runShooter()))
.onFalse(m_arm.goToSetpoint(ArmSetpoints.kStowed));

m_driverController.povDown().whileTrue(m_feeder.feed().alongWith(m_intake.spit()));
m_operatorController.y().whileTrue(m_shooter.runShooter());
m_operatorController
.leftBumper()
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/arm/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -305,7 +305,7 @@ public Command wristStaticCharacterization() {

public enum ArmSetpoints {
kStowed(-0.548, 2.485, 0.15, 0.0),
kAmp(1.49 + 0.0873, Units.degreesToRadians(230), 0.0, 0.0),
kAmp(1.49 + 0.0873, Units.degreesToRadians(228), 0.0, 0.0),
kClimb(1.633, -2.371, 0.0, 0.0),
kTrap(Units.degreesToRadians(53.0), Units.degreesToRadians(80.0), 0.0, 0.0),
kStash(Units.degreesToRadians(10.0), Units.degreesToRadians(170.0), 0.0, 0.0);
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/intake/IntakeIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,8 @@ public class IntakeIOInputs {
public double centeringBagMotorsAppliedVolts = 0.0;
public double centeringBagMotorsCurrentAmps = 0.0;

public boolean allMotorsConnected = false;
public boolean rollerMotorsConnected = false;
public boolean centeringMotorConnected = false;
}

public default void updateInputs(IntakeIOInputs inputs) {}
Expand Down
52 changes: 29 additions & 23 deletions src/main/java/frc/robot/intake/IntakeIOSparkMAX.java
Original file line number Diff line number Diff line change
@@ -1,68 +1,74 @@
package frc.robot.intake;

import com.revrobotics.CANSparkMax;
import com.revrobotics.REVLibError;
import com.revrobotics.RelativeEncoder;
import edu.wpi.first.math.util.Units;

public class IntakeIOSparkMAX implements IntakeIO {

private final CANSparkMax topRollerMotor, bottomRollerMotor, centeringMotors;
private final CANSparkMax m_topRollerMotor, m_bottomRollerMotor, m_centeringMotors;
private final RelativeEncoder m_topRollerEncoder, m_bottomRollerEncoder;

public IntakeIOSparkMAX() {
topRollerMotor = new CANSparkMax(5, CANSparkMax.MotorType.kBrushless);
bottomRollerMotor = new CANSparkMax(6, CANSparkMax.MotorType.kBrushless);
centeringMotors = new CANSparkMax(8, CANSparkMax.MotorType.kBrushed);
m_topRollerMotor = new CANSparkMax(5, CANSparkMax.MotorType.kBrushless);
m_bottomRollerMotor = new CANSparkMax(6, CANSparkMax.MotorType.kBrushless);
m_centeringMotors = new CANSparkMax(8, CANSparkMax.MotorType.kBrushed);

m_topRollerEncoder = topRollerMotor.getEncoder();
m_bottomRollerEncoder = bottomRollerMotor.getEncoder();
m_topRollerEncoder = m_topRollerMotor.getEncoder();
m_bottomRollerEncoder = m_bottomRollerMotor.getEncoder();

topRollerMotor.restoreFactoryDefaults();
bottomRollerMotor.restoreFactoryDefaults();
m_topRollerMotor.restoreFactoryDefaults();
m_bottomRollerMotor.restoreFactoryDefaults();

topRollerMotor.setSmartCurrentLimit(40);
bottomRollerMotor.setSmartCurrentLimit(40);
centeringMotors.setSmartCurrentLimit(40);
m_topRollerMotor.setSmartCurrentLimit(40);
m_bottomRollerMotor.setSmartCurrentLimit(40);
m_centeringMotors.setSmartCurrentLimit(40);
}

@Override
public void updateInputs(IntakeIOInputs inputs) {
inputs.topRollerVelocityRpm =
Units.rotationsPerMinuteToRadiansPerSecond(m_topRollerEncoder.getVelocity());
inputs.topRollerAppliedVolts =
topRollerMotor.getAppliedOutput() * topRollerMotor.getBusVoltage();
inputs.topRollerCurrentAmps = topRollerMotor.getOutputCurrent();
m_topRollerMotor.getAppliedOutput() * m_topRollerMotor.getBusVoltage();
inputs.topRollerCurrentAmps = m_topRollerMotor.getOutputCurrent();

inputs.bottomRollerVelocityRpm =
Units.rotationsPerMinuteToRadiansPerSecond(m_bottomRollerEncoder.getVelocity());
inputs.bottomRollerAppliedVolts =
bottomRollerMotor.getAppliedOutput() * bottomRollerMotor.getBusVoltage();
inputs.bottomRollerCurrentAmps = bottomRollerMotor.getOutputCurrent();
m_bottomRollerMotor.getAppliedOutput() * m_bottomRollerMotor.getBusVoltage();
inputs.bottomRollerCurrentAmps = m_bottomRollerMotor.getOutputCurrent();

inputs.centeringBagMotorsAppliedVolts =
centeringMotors.getAppliedOutput() * centeringMotors.getBusVoltage();
inputs.bottomRollerCurrentAmps = centeringMotors.getOutputCurrent();
m_centeringMotors.getAppliedOutput() * m_centeringMotors.getBusVoltage();
inputs.bottomRollerCurrentAmps = m_centeringMotors.getOutputCurrent();

inputs.rollerMotorsConnected =
m_topRollerMotor.getLastError() == REVLibError.kOk
&& m_bottomRollerMotor.getLastError() == REVLibError.kOk;
inputs.centeringMotorConnected = m_centeringMotors.getLastError() == REVLibError.kOk;
}

@Override
public void setFrontRollersVoltage(double volts) {
topRollerMotor.setVoltage(volts);
m_topRollerMotor.setVoltage(volts);
}

@Override
public void setBackRollersVoltage(double volts) {
bottomRollerMotor.setVoltage(volts);
m_bottomRollerMotor.setVoltage(volts);
}

@Override
public void setCenteringMotorsVoltage(double volts) {
centeringMotors.setVoltage(volts);
m_centeringMotors.setVoltage(volts);
}

@Override
public void stopRollers() {
topRollerMotor.stopMotor();
bottomRollerMotor.stopMotor();
centeringMotors.stopMotor();
m_topRollerMotor.stopMotor();
m_bottomRollerMotor.stopMotor();
m_centeringMotors.stopMotor();
}
}
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/intake/IntakeIOTalonFX.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.intake;

import com.ctre.phoenix.ErrorCode;
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.can.BaseTalon;
Expand Down Expand Up @@ -65,7 +66,7 @@ public IntakeIOTalonFX() {

@Override
public void updateInputs(IntakeIOInputs inputs) {
inputs.allMotorsConnected =
inputs.rollerMotorsConnected =
BaseStatusSignal.refreshAll(
m_topRollerVelocitySignal,
m_topRollerAppliedVoltageSignal,
Expand All @@ -74,6 +75,7 @@ public void updateInputs(IntakeIOInputs inputs) {
m_bottomRollerAppliedVoltageSignal,
m_bottomRollerCurrentSignal)
.isOK();
inputs.centeringMotorConnected = m_centeringMotors.getLastError() == ErrorCode.OK;

inputs.topRollerVelocityRpm = m_topRollerVelocitySignal.getValue() * 60.0;
inputs.topRollerAppliedVolts = m_topRollerAppliedVoltageSignal.getValue();
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ public class Shooter extends SubsystemBase {
public static final double kFarShotVelocityRpm = 5800.0;
private final double kTrapShot = 400.0;
private final double kAmpShot = 5000.0;
private final double kReadyToShootToleranceRps = 3.0;
private final double kReadyToShootToleranceRps = 5.0;

// Denominator for gains here are in rotations
public static final double topRollerkS = 0.15945;
Expand Down

0 comments on commit 464657b

Please sign in to comment.