Skip to content

Commit

Permalink
Merge pull request #7 from MOERobotics/houston
Browse files Browse the repository at this point in the history
Houston
  • Loading branch information
mailmindlin authored May 15, 2024
2 parents 8a3fbb5 + 5a8d0ca commit 6888f6e
Show file tree
Hide file tree
Showing 21 changed files with 456 additions and 96 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,4 +20,5 @@ public static class OperatorConstants {
}
public static Rotation2d collectorShoulder = Rotation2d.fromDegrees(83.6);
public static Rotation2d collectorWrist = Rotation2d.fromDegrees(-45);
public static double subShotSpeed = 2500;
}
17 changes: 11 additions & 6 deletions src/main/java/frc/robot/FortissiMOEContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ public class FortissiMOEContainer{
double maxRPS = 1.5*2*Math.PI;
double maxRPS2 = Math.PI;

double maxMPSSquared = 2;
double maxMPSSquared = 3;

Vision vision = new Vision();
private final SendableChooser<Command> m_chooser = new SendableChooser<>();
Expand Down Expand Up @@ -223,8 +223,8 @@ public class FortissiMOEContainer{

SmartDashboard.putNumber("Roll", pigeon.getRoll());
SmartDashboard.putNumber("Pitch", pigeon.getPitch());
pdh.setSwitchableChannel((collectorSubsystem.isCollected() && ((System.currentTimeMillis()/100)%2 == 0))
|| (shooterSubsystem.shooterAtSpeed() && shooterSubsystem.getDesiredTopSpeed() != 0 && collectorSubsystem.isCollected()));
pdh.setSwitchableChannel(((collectorSubsystem.isCollected() || collectorSubsystem.getCollectorAmps() > 20) && ((System.currentTimeMillis()/100)%2 == 0))
|| (shooterSubsystem.shooterAtSpeed() && shooterSubsystem.getDesiredTopSpeed() != 0 && (collectorSubsystem.isCollected() || collectorSubsystem.getCollectorAmps() > 20)));
});
//weirdest command ever - climbing & pdh logic

Expand Down Expand Up @@ -281,9 +281,10 @@ public FortissiMOEContainer() {
m_chooser.addOption("D Score Move", new doubleNoteAutos(swerveSubsystem,armSubsystem,shooterSubsystem,collectorSubsystem,0,0).DMoveAuto());
m_chooser.addOption("D Score Collect (DC5)", new doubleNoteAutos(swerveSubsystem,armSubsystem,shooterSubsystem,collectorSubsystem,0,0).DC5Auto());
m_chooser.addOption("4 Note Auto (CW2W1W3)", new tripleNoteAutos(swerveSubsystem,armSubsystem,shooterSubsystem,collectorSubsystem,0,0).CW1W2W3());
m_chooser.addOption("centerLine Auto", new doubleNoteAutos(swerveSubsystem, armSubsystem, shooterSubsystem, collectorSubsystem, 0, 0).DC5C4PassC3());
m_chooser.addOption("CenterLine Pass Auto (DC5C4PassC3)", new doubleNoteAutos(swerveSubsystem, armSubsystem, shooterSubsystem, collectorSubsystem, 0, 0).DC5C4PassC3());
m_chooser.addOption("driveForward", new doubleNoteAutos(swerveSubsystem, armSubsystem, shooterSubsystem, collectorSubsystem, 0, 0).rollOutAuto());
m_chooser.addOption("3 Note Centerline Auto (DC3C2)", new tripleNoteAutos(swerveSubsystem, armSubsystem, shooterSubsystem, collectorSubsystem, 0, 0).DC3C2());
m_chooser.addOption("2 Note Centerline Auto Obj Detect", new tripleNoteAutos(swerveSubsystem, armSubsystem, shooterSubsystem, collectorSubsystem, 0,0).DC3ObjDetect());
SmartDashboard.putData("chooser", m_chooser);
}

Expand Down Expand Up @@ -360,11 +361,15 @@ private void configureBindings() {
var driveToNote = new DriveToNoteCommand(
swerveSubsystem,
vision,
() -> Math.max(0, Math.hypot(driverJoystick.getRawAxis(0), driverJoystick.getRawAxis(1))-.05)*(maxMPS),
// () -> Math.max(0, Math.hypot(driverJoystick.getRawAxis(0), driverJoystick.getRawAxis(1))-.05)*(maxMPS),
() -> -driverJoystick.getRawAxis(1),
() -> -driverJoystick.getRawAxis(0),
() -> -driverJoystick.getRawAxis(2),
(rumblePercent) -> {
SmartDashboard.putNumber("JoyRumble", rumblePercent);
driverJoystick.setRumble(PS5Controller.RumbleType.kBothRumble, rumblePercent); //TODO: try different rumble types.
}
},
maxMPS
);
new JoystickButton(driverJoystick, 8).whileTrue(driveToNote);
// object detection note pickup button
Expand Down
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

import com.pathplanner.lib.pathfinding.Pathfinding;
import com.pathplanner.lib.pathfinding.LocalADStar;
import edu.wpi.first.wpilibj.DataLogManager;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand All @@ -22,16 +23,19 @@ public class Robot extends TimedRobot {
private void initRobotContainer(boolean force) {
if (m_robotContainer != null)
return;
if (force || DriverStation.getAlliance().isPresent())
if (force || DriverStation.getAlliance().isPresent()) {
// m_robotContainer = new SwerveBotContainer();
m_robotContainer = new FortissiMOEContainer();
m_robotContainer = new FortissiMOEContainer();
m_robotContainer.climber.clearStickyFaults();
}
}

@Override
public void robotInit() {
// m_robotContainer = new FortissiMOEContainer();
initRobotContainer(false);

DataLogManager.start();
DriverStation.startDataLog(DataLogManager.getLog());
}


Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/commands/AutoDriveToNoteCommand.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.commands;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
Expand Down Expand Up @@ -55,7 +56,10 @@ public void execute() {
updateTarget();
if (target == null){
idleLoopCount += 1;
return;
}
// Put the detection on NetworkTables, for debugging
subsystem.field.getObject("NoteTarget").setPose(new Pose2d(target, new Rotation2d()));
// Drive towards target
var robotPose = subsystem.getEstimatedPose();
var delta = target.minus(robotPose.getTranslation());
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/commands/Collect.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,11 @@ public void execute() {
if(speed<0){
finalSpeed=speed;
}
if (!shouldStop && speed>0 && ((index&&collector.isCollected())||!collector.isCollected())) { //collector in no note
if (!shouldStop && speed>0 && ((index&&collector.isCollected())||!collector.isCollected())) { //collecting in, we have no note
finalSpeed = speed;
timer.restart();
}
// Run backwards for a bit
if (collector.isCollected() && timer.get() <= .1 && speed > 0){
shouldStop = true;
finalSpeed = -speed;
Expand Down
47 changes: 31 additions & 16 deletions src/main/java/frc/robot/commands/DriveToNoteCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,28 +20,35 @@ public class DriveToNoteCommand extends Command {

private final Vision vision;
private final SwerveDrive subsystem;
private final DoubleSupplier speedSupplier;
private final Supplier<Double> xspdFunction,yspdFunction,turnspdFunction;
private final DoubleConsumer rumbleCallback;
private final double maxMPS;
private Timer timer;

private Translation2d target = null;
private int idleLoopCount = 0;
private final double Latency = 0.25;//Pose latency in seconds

public DriveToNoteCommand(SwerveDrive subsystem, Vision vision, DoubleSupplier speedSupplier) {
this(subsystem, vision, speedSupplier, null);
public DriveToNoteCommand(SwerveDrive subsystem, Vision vision, Supplier<Double> xspeed, Supplier<Double> yspeed,
Supplier<Double> turnspeed, double maxMPS) {
this(subsystem, vision, xspeed,yspeed,turnspeed, null, maxMPS);
}
public DriveToNoteCommand(SwerveDrive subsystem, Vision vision, DoubleSupplier speedSupplier, DoubleConsumer rumbleCallback){
this.speedSupplier = speedSupplier;
public DriveToNoteCommand(SwerveDrive subsystem, Vision vision, Supplier<Double> xspeed, Supplier<Double> yspeed,
Supplier<Double> turnspeed, DoubleConsumer rumbleCallback, double maxMPS){
xspdFunction = xspeed;
yspdFunction = yspeed;
turnspdFunction = turnspeed;
this.vision = vision;
this.subsystem = subsystem;
this.rumbleCallback = rumbleCallback;
this.maxMPS=maxMPS;
timer = new Timer();
addRequirements(subsystem);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
this.target = null;
idleLoopCount = 0;
timer.reset();
}

private void updateTarget() {
Expand All @@ -52,6 +59,14 @@ private void updateTarget() {
}

var detections = vision.detections();
if(detections.isEmpty()){
if(timer.get()>1) {//TODO: Update this value
detectionMaxThreshold = Double.POSITIVE_INFINITY;
target = null;
}
}else{
timer.reset();
}
for (var detection : detections){
var distance = detection.getNorm();
if (distance < detectionMaxThreshold){
Expand All @@ -67,28 +82,29 @@ private void updateTarget() {
public void execute() {
updateTarget();
if (target == null){
idleLoopCount += 1;

if (idleLoopCount >= 5 && rumbleCallback != null){
rumbleCallback.accept(1);
}
subsystem.setDesiredYaw(subsystem.getEstimatedPose().getRotation().getDegrees());
// idleLoopCount += 1;
//
// if (idleLoopCount >= 5 && rumbleCallback != null){
// rumbleCallback.accept(1);
// }
subsystem.driveAtSpeed(xspdFunction.get(), yspdFunction.get(), turnspdFunction.get(), true);
return;
}
// Put the detection on NetworkTables, for debugging
subsystem.field.getObject("NoteTarget").setPose(new Pose2d(target, new Rotation2d()));
// Drive towards target
var robotPose = subsystem.getEstimatedPose();
var delta = target.minus(robotPose.getTranslation());

var unitDelta = delta.div(delta.getNorm());//.times(speedSupplier.getAsDouble());

var robotAngle = unitDelta.getAngle();
if (delta.getNorm() <= Units.inchesToMeters(24)) robotAngle = robotPose.getRotation().times(1);
SmartDashboard.putNumber("robot Object Detection angle", robotAngle.getDegrees());
SmartDashboard.putNumber("robot Object Detection angle", robotAngle.getDegrees());
// var yawOffset = subsystem.getRotation2d().minus(robotPose.getRotation());
subsystem.setDesiredYaw(robotAngle.getDegrees());//Set absolute heading

var speedVal = speedSupplier.getAsDouble();
var speedVal = Math.max(0, Math.hypot(xspdFunction.get(), yspdFunction.get())-.05)*(maxMPS);
if (speedVal < .1) speedVal = 0;

subsystem.driveAtSpeed(robotAngle.getCos()*speedVal,
Expand All @@ -98,7 +114,6 @@ public void execute() {
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {

}

// Returns true when the command should end.
Expand Down
51 changes: 51 additions & 0 deletions src/main/java/frc/robot/commands/Intake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.CollectorSubsystem;

public class Intake extends Command {
private final double speed;
private CollectorSubsystem collector;
public Intake(CollectorSubsystem collector, double speed){
this.collector=collector;
this.speed=speed;
}


// Called when the command is initially scheduled.
@Override
public void initialize() {
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double finalSpeed = 0;
if(speed<0){
finalSpeed=speed;
}
if (speed>0 && !collector.isCollected()) { //collecting in, we have no note
finalSpeed = speed;
}
collector.updateCollectorSpeed(finalSpeed);
SmartDashboard.putBoolean("started collector", collector.getCollectorState());
SmartDashboard.putNumber("collector speed", finalSpeed);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
collector.stopCollector();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
if(collector.isCollected()){
return true;
}
return false;
}
}
50 changes: 50 additions & 0 deletions src/main/java/frc/robot/commands/PopNote.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.CollectorSubsystem;

public class PopNote extends Command {
private final double speed;
private Timer timer;

private CollectorSubsystem collector;
public PopNote(CollectorSubsystem collector, double speed){
this.collector=collector;
this.speed=speed;
timer = new Timer();
}


// Called when the command is initially scheduled.
@Override
public void initialize() {
timer.restart();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double finalSpeed = -speed;
collector.updateCollectorSpeed(finalSpeed);
SmartDashboard.putBoolean("started collector", collector.getCollectorState());
SmartDashboard.putNumber("collector speed", finalSpeed);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
collector.stopCollector();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
if(timer.get() >= .1 || !collector.isCollected()){
return true;
} else {
return false;
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ public class ShooterControllerCommand extends Command {
*/
public ShooterControllerCommand(ShooterSubsystem subsystem, Supplier <Double> desShoulder, Supplier<Boolean> on) {
this.subsystem = subsystem;
this.shooterSpeedTop = 5000;
this.shooterSpeedBottom = 5000;
this.shooterSpeedTop = 3500;
this.shooterSpeedBottom = 3500;
this.desShoulder = desShoulder;
onoff = on;
onState = 0;
Expand Down
Loading

0 comments on commit 6888f6e

Please sign in to comment.