Skip to content

Commit

Permalink
WIP Subsystem Auto Default Commands
Browse files Browse the repository at this point in the history
  • Loading branch information
frc1987 committed Mar 26, 2024
1 parent 2d3d205 commit e7fce64
Show file tree
Hide file tree
Showing 6 changed files with 185 additions and 8 deletions.
11 changes: 8 additions & 3 deletions src/main/deploy/pathplanner/paths/GKC Source J.path
Original file line number Diff line number Diff line change
Expand Up @@ -130,14 +130,19 @@
"rotateFast": false
},
{
"waypointRelativePos": 0.25,
"rotationDegrees": -54.62053968292776,
"waypointRelativePos": 0.2,
"rotationDegrees": -45.0,
"rotateFast": true
},
{
"waypointRelativePos": 5,
"rotationDegrees": 0,
"rotateFast": false
},
{
"waypointRelativePos": 0.30000000000000004,
"rotationDegrees": -40.409814436728226,
"rotateFast": false
}
],
"constraintZones": [
Expand Down Expand Up @@ -320,7 +325,7 @@
],
"globalConstraints": {
"maxVelocity": 4.75,
"maxAcceleration": 3.25,
"maxAcceleration": 3.5,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 360.0
},
Expand Down
11 changes: 6 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.commands.control.AimLockWrist;
import frc.robot.commands.control.AimLockWristAuto;
import frc.robot.commands.control.Climb;
import frc.robot.commands.control.GoHome;
import frc.robot.commands.control.IdleShooter;
Expand All @@ -46,6 +45,9 @@
import frc.robot.commands.control.StopAll;
import frc.robot.commands.control.amp.FireRevAmp;
import frc.robot.commands.control.amp.PrepRevAmp;
import frc.robot.commands.control.auto.AutoAimLockWrist;
import frc.robot.commands.control.auto.AutoIdleShooter;
import frc.robot.commands.control.auto.InstantShoot;
import frc.robot.commands.control.note.IntakeNoteSequence;
import frc.robot.commands.control.note.IntakeNoteSequenceAuto;
import frc.robot.commands.control.note.LobNote;
Expand Down Expand Up @@ -467,10 +469,9 @@ public void configureNamedCommands() {
new DriveToNoteAuto(DRIVETRAIN, INTAKE_PHOTON, SHOOTER, INTAKE, WRIST, ELEVATOR)));
NamedCommands.registerCommand("OverrideRotationSpeakerEnable", new InstantCommand(() -> aimAtTargetAuto = true));
NamedCommands.registerCommand("OverrideRotationSpeakerDisable", new InstantCommand(() -> aimAtTargetAuto = false));
NamedCommands.registerCommand("DefaultWrist", new AimLockWrist(WRIST, SHOOTER, ELEVATOR, SPEAKER_LIMELIGHT));
NamedCommands.registerCommand("DefaultShooter", new IdleShooter(SHOOTER, SPEAKER_LIMELIGHT));
NamedCommands.registerCommand("InstantShoot", new InstantCommand(
() -> SHOOTER.setFeederVoltage(8.0)));
NamedCommands.registerCommand("DefaultWrist", new AutoAimLockWrist(WRIST));
NamedCommands.registerCommand("DefaultShooter", new AutoIdleShooter(SHOOTER));
NamedCommands.registerCommand("InstantShoot", new InstantShoot(SHOOTER));
NamedCommands.registerCommand(
"IntakeNoteAuto", new IntakeNoteSequenceAuto(SHOOTER, INTAKE, WRIST, ELEVATOR)); //new InstantCommand(() -> aimAtTargetAuto = true)).andThen()
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
// 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.control.auto;

import edu.wpi.first.math.proto.Wpimath;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Wrist;
import frc.robot.util.Util;

public class AutoAimLockWrist extends Command {
private final Wrist wrist;

/** Creates a new AimLockWrist. */
public AutoAimLockWrist(Wrist wrist) {
this.wrist = wrist;
addRequirements(wrist);
// Use addRequirements() here to declare subsystem dependencies.
}

// 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 degrees = Util.getInterpolatedWristAngle();
// TODO find actual values, prevent wrist collision when the elevator is all the way down.
if (degrees > 10.0 && degrees < 35.0) {
return;
}
wrist.setDegrees(degrees);
}

@Override
public void end(boolean interrupted) {}

@Override
public boolean isFinished() {
return false;
}
}
55 changes: 55 additions & 0 deletions src/main/java/frc/robot/commands/control/auto/AutoIdleShooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
// 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.control.auto;

import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.math.filter.Debouncer.DebounceType;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.RobotContainer;
import frc.robot.constants.Constants;
import frc.robot.subsystems.Shooter;
import frc.robot.util.Util;

public class AutoIdleShooter extends Command {

private static final double VALID_SHOT_DEBOUNCE_TIME = 0.2;

/** Creates a new IdleShooter. */
private final Shooter shooter;

// private final Debouncer validShotDebouncer;

public AutoIdleShooter(Shooter shooter) {
addRequirements(shooter);
this.shooter = shooter;
// this.validShotDebouncer = new Debouncer(VALID_SHOT_DEBOUNCE_TIME, DebounceType.kFalling);
// Use addRequirements() here to declare subsystem dependencies.
}

// 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() {
// if (shooter.isCenterBroken() && validShotDebouncer.calculate(Util.isValidShot(SPEAKER_LIMELIGHT))) {
shooter.setRPMShoot(Constants.Shooter.SHOOTER_IDLE_RPM_CLOSE);
// } else {
// shooter.stopShooter();
// }
}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
48 changes: 48 additions & 0 deletions src/main/java/frc/robot/commands/control/auto/InstantShoot.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// 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.control.auto;

import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.math.filter.Debouncer.DebounceType;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Shooter;

public class InstantShoot extends Command {

static private final double SHOT_DEBOUNCE_TIME = 0.06;

private final Shooter m_shooter;
private Debouncer m_shotDebouncer;

/** Creates a new InstantShoot. */
public InstantShoot(final Shooter shooter) {
// Use addRequirements() here to declare subsystem dependencies.
m_shooter = shooter;
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
m_shotDebouncer = new Debouncer(SHOT_DEBOUNCE_TIME, DebounceType.kFalling);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_shooter.setFeederVoltage(8.0);
}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return !m_shotDebouncer.calculate(m_shooter.isCenterBroken());
}
}
23 changes: 23 additions & 0 deletions src/main/java/frc/robot/util/Util.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,18 @@ public static double getDistance(String limelight) {
// return 0.0;
}

// TODO flex on alliance tag pose
public static double getDistanceToSpeaker() {
return new Pose3d(RobotContainer.get().getPose())
.getTranslation()
.getDistance(
TAG_4_POSE
.transformBy(
new Transform3d(
new Translation3d(0, 0, -TAG_4_POSE.getZ()), new Rotation3d()))
.getTranslation());
}

public static Rotation2d getRotationToAllianceSpeaker(Pose2d opose) {
// return
// opose.getTranslation().minus(Util.getAllianceSpeakerCenter().getTranslation().toTranslation2d()).getAngle();
Expand All @@ -89,13 +101,24 @@ public static double getInterpolatedWristAngle(String limelight) {
.value;
}

public static double getInterpolatedWristAngle() {
return Constants.DISTANCE_TO_WRISTANGLE_RELATIVE_SPEAKER.getInterpolated(
new InterpolatingDouble(Util.getDistanceToSpeaker()))
.value;
}

public static boolean isValidShot(String limelight) {
double dist = Util.getDistance(limelight);
if (dist > 2.25 && dist < 5.25) {
return true;
} else return false;
}

public static boolean isValidShot() {
double dist = Util.getDistanceToSpeaker();
return dist > 2.25 && dist < 5.25;
}

public static double squareValue(double value) {
return Math.copySign(Math.pow(value, 2), value);
}
Expand Down

0 comments on commit e7fce64

Please sign in to comment.