Skip to content

Commit

Permalink
final comp 1 edits
Browse files Browse the repository at this point in the history
  • Loading branch information
NotNotTy committed Mar 5, 2024
1 parent f89d6aa commit 4987a8a
Show file tree
Hide file tree
Showing 9 changed files with 150 additions and 14 deletions.
11 changes: 7 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,13 +55,13 @@ public static final class SwerveConstants {
public static final double voltageComp = 12.0;

/* Swerve Current Limiting */
public static final int angleContinuousCurrentLimit = 32;
public static final int angleCurrentThreshold = 25;
public static final int angleContinuousCurrentLimit = 35;
public static final int angleCurrentThreshold = 40;
public static final double angleCurrentThresholdTime = 0.1;
public static final boolean angleEnableCurrentLimit = true;

public static final int driveContinuousCurrentLimit = 32; //original threshold: 80
public static final int driveCurrentThreshold = 25;
public static final int driveContinuousCurrentLimit = 35; //original threshold: 80
public static final int driveCurrentThreshold = 60;
public static final double driveCurrentThresholdTime = 0.1;
public static final boolean driveEnableCurrentLimit = true;

Expand Down Expand Up @@ -211,6 +211,9 @@ public static class IntakeConstants{

// Shooter constants
public static class ShooterConstants{
public static final String leftSpeedKey = "Left Speed";
public static final String rightSpeedKey = "Right Speed";

public static final int shooterLeftID = 11;
public static final int shooterRightID = 12;
public static double shooterLeftSpeedSpeaker = -.65;
Expand Down
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
package frc.robot;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -44,6 +45,12 @@ public void robotInit() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();
if (!Preferences.containsKey(Constants.ShooterConstants.leftSpeedKey)){
Preferences.setDouble(Constants.ShooterConstants.leftSpeedKey, Constants.ShooterConstants.shooterLeftSpeedSpeaker);
}
if (!Preferences.containsKey(Constants.ShooterConstants.rightSpeedKey)){
Preferences.setDouble(Constants.ShooterConstants.rightSpeedKey, Constants.ShooterConstants.shooterRightSpeedSpeaker);
}
}

/**
Expand Down
19 changes: 19 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
import frc.robot.commands.DriveCommands.DefaultDrive;
import frc.robot.commands.DriveCommands.FieldOrientedDrive;
import frc.robot.commands.DriveCommands.LeaveZone;
import frc.robot.commands.DriveCommands.TurnWhenLeft;
import frc.robot.commands.DriveCommands.TurnWhenRight;
import frc.robot.commands.IntakeCommands.AutoIntake;
import frc.robot.commands.IntakeCommands.IntakeDown;
import frc.robot.commands.IntakeCommands.IntakeUp;
Expand Down Expand Up @@ -64,6 +66,8 @@ public class RobotContainer {
private final AlignSpeaker m_alignSpeaker = new AlignSpeaker(m_poseEstimator, m_traj, m_vision);
private final MoveToNote m_justMove = new MoveToNote(m_drivetrain, m_vision);
private final LeaveZone m_leaveZone = new LeaveZone(m_drivetrain);
private final TurnWhenLeft m_TurnWhenLeft = new TurnWhenLeft(m_drivetrain);
private final TurnWhenRight m_TurnWhenRight = new TurnWhenRight(m_drivetrain);

// Drive command
private final DefaultDrive m_defaultDrive = new DefaultDrive( m_drivetrain,
Expand Down Expand Up @@ -111,6 +115,19 @@ public class RobotContainer {
// m_autoShootSpeaker
// .andThen(m_trajectoryConfig.followPathGui("Leave Zone Subwoofer"))
// );
// private final SequentialCommandGroup shootandTurnLeft = new SequentialCommandGroup(
// m_autoShootSpeaker
// .andThen(m_TurnWhenLeft)
// .andThen(m_leaveZone)
// );

// private final SequentialCommandGroup shootAndTurnRight = new SequentialCommandGroup(
// m_autoShootSpeaker
// .andThen(m_TurnWhenRight)
// .andThen(m_leaveZone)
// );



private boolean isFieldOriented = true;

Expand All @@ -125,6 +142,8 @@ private void configureShuffleBoardBindings(){
m_chooser.addOption("Run on Fly", m_runOnTheFly);
m_chooser.addOption("Move to Note", m_moveToNote);
m_chooser.addOption("Leave Zone", m_leaveZone);
m_chooser.addOption("Turn when Left (TESTING ONLY)", m_TurnWhenLeft);

//m_chooser.addOption("Score Speaker", scoreSpeaker);
//m_chooser.addOption("Score Amp", scoreAmp);
//m_chooser.addOption("Auto Intake", autoIntake);
Expand Down
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -111,9 +111,10 @@ public SwerveModulePosition getPosition() {
/* Sets the speed of the swerve module. If it's openLoop, then it takes in a percentage, otherwise, it calculates and runs a PID */
private void setSpeed(SwerveModuleState desiredState, boolean isOpenLoop) {
if (isOpenLoop) {
//driveDutyCycle.Output = desiredState.speedMetersPerSecond / Constants.SwerveConstants.maxSpeed;
double percentOutput = desiredState.speedMetersPerSecond / Constants.SwerveConstants.maxSpeed;
driveMotor.set(percentOutput);
driveDutyCycle.Output = desiredState.speedMetersPerSecond / Constants.SwerveConstants.maxSpeed;
driveMotor.setControl(driveDutyCycle);
//double percentOutput = desiredState.speedMetersPerSecond / Constants.SwerveConstants.maxSpeed;
//driveMotor.set(percentOutput);
} else {
//creating a feedforwad with a desired velocity
driveVelocity.Velocity = Conversions.MPSToRPS(desiredState.speedMetersPerSecond, Constants.SwerveConstants.wheelCircumference);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,13 @@
package frc.robot.commands.DriveCommands;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Drivetrain;

public class LeaveZone extends Command {
private final Drivetrain m_drivetrain;
private Timer timer = new Timer();
/** Creates a new LeaveZone. */
public LeaveZone(Drivetrain d) {
m_drivetrain = d;
Expand All @@ -20,6 +22,8 @@ public LeaveZone(Drivetrain d) {
// Called when the command is initially scheduled.
@Override
public void initialize() {
timer.reset();
timer.start();
m_drivetrain.driveRobotRelative(new Translation2d(), 0, true);
}

Expand All @@ -32,12 +36,14 @@ public void execute() {
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
timer.stop();
timer.reset();
m_drivetrain.driveRobotRelative(new Translation2d(), 0, true);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
return timer.get() >= 3;
}
}
44 changes: 44 additions & 0 deletions src/main/java/frc/robot/commands/DriveCommands/TurnWhenLeft.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.DriveCommands;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Drivetrain;

public class TurnWhenLeft extends Command {
/** Creates a new TurnWhenLeft. */
private final Drivetrain m_drivetrain;
public TurnWhenLeft(Drivetrain d) {
m_drivetrain = d;
addRequirements(d);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
m_drivetrain.zeroGyro();
m_drivetrain.driveRobotRelative(new Translation2d(), 0, true);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_drivetrain.driveRobotRelative(new Translation2d(0, 0), -Math.PI / 4, true);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_drivetrain.driveRobotRelative(new Translation2d(), 0, true);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return m_drivetrain.getNavxAngle().getDegrees() <= -40;
}
}
44 changes: 44 additions & 0 deletions src/main/java/frc/robot/commands/DriveCommands/TurnWhenRight.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands.DriveCommands;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Drivetrain;

public class TurnWhenRight extends Command {
/** Creates a new TurnWhenLeft. */
private final Drivetrain m_drivetrain;
public TurnWhenRight(Drivetrain d) {
m_drivetrain = d;
addRequirements(d);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
m_drivetrain.zeroGyro();
m_drivetrain.driveRobotRelative(new Translation2d(), 0, true);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_drivetrain.driveRobotRelative(new Translation2d(0, 0), Math.PI / 4, true);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_drivetrain.driveRobotRelative(new Translation2d(), 0, true);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return m_drivetrain.getNavxAngle().getDegrees() <= 40;
}
}
1 change: 1 addition & 0 deletions src/main/java/frc/robot/subsystems/PoseEstimator.java
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ public void updateEachPoseEstimator(PhotonPoseEstimator poseEstimator, int camID
poseEstimator.update().ifPresent(estimatedRobotPose -> {
System.out.println(1);
var estimatedPose = estimatedRobotPose.estimatedPose;
System.out.println(estimatedRobotPose.targetsUsed.size());

// m_DrivePoseEstimator.addVisionMeasurement(estimatedPose.toPose2d(), FIELD_LENGTH_METERS);

Expand Down
23 changes: 17 additions & 6 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.ctre.phoenix.motorcontrol.TalonSRXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;

import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
Expand All @@ -15,12 +16,16 @@ public class Shooter extends SubsystemBase {
private static final double DEADZONE = 0.05;
private TalonSRX m_ShooterMotorLeft;
private TalonSRX m_ShooterMotorRight;
private double speed;

private double realLeftSpeed = Constants.ShooterConstants.shooterLeftSpeedSpeaker;
private double realRightSpeed = Constants.ShooterConstants.shooterRightSpeedSpeaker;
static Shooter instance = null;
/** Creates a new Shooter. */
public Shooter() {
m_ShooterMotorLeft = new TalonSRX(Constants.ShooterConstants.shooterLeftID);
m_ShooterMotorRight = new TalonSRX(Constants.ShooterConstants.shooterRightID);
// Preferences.initDouble(Constants.ShooterConstants.leftSpeedKey, realLeftSpeed);
Preferences.initDouble(Constants.ShooterConstants.rightSpeedKey, realRightSpeed);
}

// Retrieve instance of shooter
Expand Down Expand Up @@ -58,11 +63,17 @@ public void periodic() {
SmartDashboard.putNumber("current left", m_ShooterMotorLeft.getSupplyCurrent());
SmartDashboard.putNumber("current right", m_ShooterMotorRight.getSupplyCurrent());

SmartDashboard.putNumber("Speed Left Speaker", Constants.ShooterConstants.shooterLeftSpeedSpeaker);
SmartDashboard.putNumber("Speed Right Speaker", Constants.ShooterConstants.shooterRightSpeedSpeaker);
SmartDashboard.putNumber("Speed Left Amp", Constants.ShooterConstants.shooterLeftSpeedAmp);
SmartDashboard.putNumber("Speed Right Amp", Constants.ShooterConstants.shooterRightSpeedAmp);
SmartDashboard.putNumber("Outtake speed", Constants.IntakeConstants.rollerSpeedOuttake);

Constants.ShooterConstants.shooterLeftSpeedSpeaker = Preferences.getDouble(Constants.ShooterConstants.leftSpeedKey, realLeftSpeed);
Constants.ShooterConstants.shooterRightSpeedSpeaker = Preferences.getDouble(Constants.ShooterConstants.rightSpeedKey, realRightSpeed);



// SmartDashboard.putNumber("Speed Left Speaker", Constants.ShooterConstants.shooterLeftSpeedSpeaker);
// SmartDashboard.putNumber("Speed Right Speaker", Constants.ShooterConstants.shooterRightSpeedSpeaker);
// SmartDashboard.putNumber("Speed Left Amp", Constants.ShooterConstants.shooterLeftSpeedAmp);
// SmartDashboard.putNumber("Speed Right Amp", Constants.ShooterConstants.shooterRightSpeedAmp);
// SmartDashboard.putNumber("Outtake speed", Constants.IntakeConstants.rollerSpeedOuttake);

Constants.ShooterConstants.shooterLeftSpeedSpeaker = SmartDashboard.getNumber("Speed Left Speaker", Constants.ShooterConstants.shooterLeftSpeedSpeaker);
Constants.ShooterConstants.shooterRightSpeedSpeaker = SmartDashboard.getNumber("Speed Right Speaker", Constants.ShooterConstants.shooterRightSpeedSpeaker);
Expand Down

0 comments on commit 4987a8a

Please sign in to comment.