Skip to content

Commit

Permalink
Merge branch 'main' into autonomous-work
Browse files Browse the repository at this point in the history
  • Loading branch information
ReeledWarrior14 committed Mar 7, 2024
1 parent 655beb8 commit 6d16256
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 22 deletions.
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ public static final class IOConstants {
public static final int kDriverControllerPort = 0;
public static final int kOperatorControllerPort = 1;

public static final double kControllerDeadband = 0.05;
public static final double kControllerDeadband = 0.1;
public static final double kSlowModeScalar = 0.8;
}

Expand Down Expand Up @@ -117,7 +117,8 @@ public static final class IntakeConstants {
public static final class ShooterConstants {
public static final int kTopShooterMotorPort = 20;
public static final int kBottomShooterMotorPort = 35;
public static final double kShooterSpeed = 0.7;
public static final double kShooterSpeedTop = 0.75;
public static final double kShooterSpeedBottom = 0.9;
public static final double kShooterOff = 0;
}

Expand Down
24 changes: 12 additions & 12 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -94,18 +94,18 @@ public void periodic() {

m_field.setRobotPose(m_poseEstimator.getEstimatedPosition());

SmartDashboard.putNumber("gyro angle", m_gyro.getAngle());
SmartDashboard.putNumber("odometryX", m_poseEstimator.getEstimatedPosition().getX());
SmartDashboard.putNumber("odometryY", m_poseEstimator.getEstimatedPosition().getY());

// AdvantageScope Logging
double[] logData = {
m_frontLeft.getPosition().angle.getDegrees(), m_frontLeft.driveOutput,
m_frontRight.getPosition().angle.getDegrees(), m_frontRight.driveOutput,
m_rearLeft.getPosition().angle.getDegrees(), m_rearLeft.driveOutput,
m_rearRight.getPosition().angle.getDegrees(), m_rearRight.driveOutput,
};
SmartDashboard.putNumberArray("AdvantageScope Swerve States", logData);
// SmartDashboard.putNumber("gyro angle", m_gyro.getAngle());
// SmartDashboard.putNumber("odometryX", m_poseEstimator.getEstimatedPosition().getX());
// SmartDashboard.putNumber("odometryY", m_poseEstimator.getEstimatedPosition().getY());

// // AdvantageScope Logging
// double[] logData = {
// m_frontLeft.getPosition().angle.getDegrees(), m_frontLeft.driveOutput,
// m_frontRight.getPosition().angle.getDegrees(), m_frontRight.driveOutput,
// m_rearLeft.getPosition().angle.getDegrees(), m_rearLeft.driveOutput,
// m_rearRight.getPosition().angle.getDegrees(), m_rearRight.driveOutput,
// };
// SmartDashboard.putNumberArray("AdvantageScope Swerve States", logData);

setModuleStates(swerveModuleStates);
}
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,21 +27,21 @@ public class IntakeSubsystem extends SubsystemBase {

private DutyCycleEncoder m_armEncoder = new DutyCycleEncoder(IntakeConstants.kArmEncoderChannel);

//private Rev2mDistanceSensor m_distanceSensor = new Rev2mDistanceSensor(Port.kOnboard); // onboard I2C port;
private Rev2mDistanceSensor m_distanceSensor = new Rev2mDistanceSensor(Port.kMXP); // onboard I2C port;

private double m_intakeSpeed = 0;
private double m_armSetpoint = IntakeConstants.kIntakeRaisedAngle;

/** Creates a new IntakeSubsystem */
public IntakeSubsystem() {
//m_distanceSensor.setAutomaticMode(true);
m_distanceSensor.setAutomaticMode(true);

m_armEncoder.setPositionOffset(IntakeConstants.kArmEncoderOffset);
SmartDashboard.putNumber("arm", m_armEncoder.getAbsolutePosition());
m_armEncoder.setDistancePerRotation(360);

m_intakeMotor.setIdleMode(IdleMode.kBrake);
m_armMotor.setIdleMode(IdleMode.kCoast);
m_intakeMotor.setIdleMode(IdleMode.kCoast);
m_armMotor.setIdleMode(IdleMode.kBrake);

m_armPID.setTolerance(10);

Expand Down Expand Up @@ -97,7 +97,7 @@ public void stopIntake() {
* Gets distance from Rev 2m sensor
*/
public double getDistanceSensor() {
return 0;//m_distanceSensor.getRange();
return m_distanceSensor.getRange();
}

@Override
Expand All @@ -112,7 +112,7 @@ public void periodic() {

SmartDashboard.putNumber("Arm Angle", m_armEncoder.getDistance());
SmartDashboard.putBoolean("Have Note?", haveNote);
//SmartDashboard.putNumber("distance sensor", m_distanceSensor.getRange(Rev2mDistanceSensor.Unit.kInches));
SmartDashboard.putNumber("distance sensor", m_distanceSensor.getRange(Rev2mDistanceSensor.Unit.kInches));
SmartDashboard.putNumber("pid output", setMotorSpeed);
}

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ public void reset() {
public void setShootingSpeed(ShootSpeed speed) {
switch (speed) {
case Shooting:
m_topSpeed = ShooterConstants.kShooterSpeed;
m_bottomSpeed = ShooterConstants.kShooterSpeed;
m_topSpeed = ShooterConstants.kShooterSpeedTop;
m_bottomSpeed = ShooterConstants.kShooterSpeedBottom;
// System.out.println("shoot speed: " + ShooterConstants.kShooterSpeed);
break;
case Off:
Expand Down

0 comments on commit 6d16256

Please sign in to comment.