Skip to content
15 changes: 13 additions & 2 deletions src/main/java/frc/robot/Orchestrator.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,23 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.indexer.Indexer;
import frc.robot.subsystems.shooter.Shooter;
import frc.robot.subsystems.shooter.ShooterConstants;

import frc.robot.subsystems.vision.Vision;

public class Orchestrator {
private final Indexer indexer;
private final Shooter shooter;
private final Vision vision;
private final Drive drive;

public Orchestrator(Indexer indexer, Shooter shooter) {
public Orchestrator(Indexer indexer, Shooter shooter, Vision vision, Drive drive) {
this.indexer = indexer;
this.shooter = shooter;
this.vision = vision;
this.drive = drive;
}

public Command spinUp(BooleanSupplier fastMode) {
Expand Down Expand Up @@ -51,6 +56,12 @@ public Command shootCycle(BooleanSupplier fastMode) {
.repeatedly());
}

public Command rotateToTag() {
return Commands.sequence(
drive.toAprilTag(vision.getYaw())
).repeatedly();
}

public Command reverseAll() {
return Commands.parallel(shooter.reverse(), indexer.reverse());
}
Expand Down
10 changes: 6 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ public class RobotContainer {
private final Vision vision;
private final Indexer indexer = new Indexer(new IndexerIOSparkMax());
private final Shooter shooter = new Shooter(new ShooterIOSparkMax());
private final Orchestrator orchestrator = new Orchestrator(indexer, shooter);
private final Orchestrator orchestrator;
private final CommandXboxController driverController = new CommandXboxController(0);
private boolean fastMode = false;
private final Trigger fastModeTrigger = new Trigger(() -> fastMode);
Expand All @@ -45,6 +45,7 @@ public RobotContainer() {
// Configure the trigger bindings
drive = new Drive(new DriveIOSparkMax());
vision = new Vision(new VisionIOPhotonVision("VGA_USB_Camera"){});
orchestrator = new Orchestrator(indexer, shooter, vision, drive);
configureBindings();
}

Expand All @@ -67,9 +68,9 @@ private void configureBindings() {
() -> driverController.getHID()
.setRumble(edu.wpi.first.wpilibj.GenericHID.RumbleType.kBothRumble, 0.0)
));
drive.setDefaultCommand(drive.arcadeDrive(
driverController::getLeftY,
driverController::getRightY));
drive.setDefaultCommand(drive.arcadeDrive(
driverController::getLeftY,
driverController::getRightY));

driverController
.rightTrigger()
Expand All @@ -85,6 +86,7 @@ private void configureBindings() {
.rightBumper()
.onTrue(orchestrator.shootOnce(() -> fastMode))
.onFalse(orchestrator.stopAll());
driverController.x().whileTrue(orchestrator.rotateToTag());
}

/**
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import edu.wpi.first.wpilibj2.command.Commands;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;

import org.littletonrobotics.junction.Logger;

public class Drive extends SubsystemBase {
Expand All @@ -30,4 +31,12 @@ public Command arcadeDrive(DoubleSupplier speedX, DoubleSupplier rotation) {
io.setVoltageRight(speeds.right * 7);
}, this);
}

public Command toAprilTag(double yaw) {
return Commands.run(
() -> {
io.rotateToTag(yaw);
}, this
);
}
}
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/DriveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

public class DriveConstants {


public static final double PID_P = 0.0;
public static final double PID_I = 0.0;
public static final double PID_D = 0.0;

}
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/subsystems/drive/DriveIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,5 @@ default void setVelocityRadPerSecL(double leftVelocityRadPerSec){}

default void setVelocityRadPerSecR(double rightVelocityRadPerSec){}



default public void rotateToTag(double yaw) {}
}
15 changes: 14 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/DriveIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,12 @@

import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.SparkBase;
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkLowLevel;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.config.SparkBaseConfig;
import com.revrobotics.spark.config.SparkMaxConfig;
import edu.wpi.first.math.controller.PIDController;
import java.lang.Math;

public class DriveIOSparkMax implements DriveIO{
private final SparkMax leftLeader;
Expand All @@ -17,6 +18,7 @@ public class DriveIOSparkMax implements DriveIO{
private final RelativeEncoder leftLeaderEncoder;
private final RelativeEncoder rightLeaderEncoder;

private final PIDController pidController;

public DriveIOSparkMax(){
leftLeader = new SparkMax(3, SparkLowLevel.MotorType.kBrushless);
Expand Down Expand Up @@ -51,6 +53,9 @@ public DriveIOSparkMax(){
.voltageCompensation(12)
.smartCurrentLimit(60)
.follow(5, false);

pidController = new PIDController(DriveConstants.PID_P, DriveConstants.PID_I, DriveConstants.PID_D);

leftLeader.configure(LeftLeaderConfig, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters);
leftFollower.configure(LeftFollowerConfig, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters);
rightLeader.configure(RightLeaderConfig, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters);
Expand Down Expand Up @@ -88,4 +93,12 @@ public void setVelocityRadPerSecR(double rightVelocityRadPerSec){
rightLeader.set(rightVelocityRadPerSec);
}

@Override
public void rotateToTag(double yaw) {
var newVelocity = pidController.calculate(yaw, 0);
newVelocity = Math.max(-1, newVelocity);
newVelocity = Math.min(1, newVelocity);
leftLeader.set(newVelocity);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You’re going to have to figure out a constant that turns the degree value into a range of -1 and 1 as motor.set only accepts that range. Multiple the constant and the PID output to get your ‘velocity’

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've just clamped it for now, I think we'll need to create a function for PID to properly work. I'll work on that.

rightLeader.set(-newVelocity);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkLimitSwitch;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/subsystems/vision/Vision.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
package frc.robot.subsystems.vision;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import org.littletonrobotics.junction.Logger;

Expand Down