Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

PR for vision branch - working note detection and new drive method. #62

Merged
merged 28 commits into from
Mar 21, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
c3e3518
added the drive to note position code back
SJJCoding Feb 6, 2024
d38721f
Implemented limelight get to distance command, should be able to run …
SJJCoding Feb 7, 2024
3112274
forgor to commit all the files in the last push
SJJCoding Feb 7, 2024
66ddf50
fixed limelight subsystem from gunga selling
SJJCoding Feb 10, 2024
e7f48bd
Merge remote-tracking branch 'upstream/main'
SJJCoding Feb 10, 2024
f7ffce4
implemented jonah rotation method
SJJCoding Feb 10, 2024
686d8dd
fixed command stuff and hopefully better turning methods
SJJCoding Feb 14, 2024
e75a199
Merge remote-tracking branch 'upstream/main'
SJJCoding Feb 21, 2024
42f8b9f
Cleaned up simpleDrive
SJJCoding Feb 22, 2024
0f9e8bc
Merge branch 'robototes:main' into main
SJJCoding Feb 22, 2024
f8ad4b8
Fixed the majority of PR comments
SJJCoding Feb 23, 2024
3c77ece
Merge branch 'main' of https://github.com/SJJCoding/Crescendo2024
SJJCoding Feb 23, 2024
8673859
Update src/main/java/frc/team2412/robot/subsystems/LimelightSubsystem…
SJJCoding Feb 23, 2024
ae0af8f
oscillation issue probably fixed
SJJCoding Feb 23, 2024
fa4def3
working turning method, fixed drivepower
SJJCoding Feb 24, 2024
456417f
Cleaned up a bunch of logic, removed the need for a DriveCommand or s…
SJJCoding Feb 25, 2024
5384c13
Some more PR related changes
SJJCoding Feb 25, 2024
189f119
Removed the old drive and turn power curves due to redundancy and re …
SJJCoding Feb 25, 2024
f781926
Majority of PR comments fixed
SJJCoding Feb 29, 2024
1d88e45
Merge branch 'main' into main
SJJCoding Mar 12, 2024
f57e583
spotlessapply
SJJCoding Mar 12, 2024
d68609d
Merge branch 'main' of https://github.com/SJJCoding/Crescendo2024
SJJCoding Mar 12, 2024
f34c970
fixed pr comments (again)
SJJCoding Mar 19, 2024
6dc22cc
Merge branch 'main' into main
SJJCoding Mar 19, 2024
e30a7bf
spotlessapply maybe
SJJCoding Mar 20, 2024
cfc6016
Merge branch 'main' of https://github.com/SJJCoding/Crescendo2024
SJJCoding Mar 20, 2024
1e6874b
removed redundant methods from limelightsubsystem
SJJCoding Mar 20, 2024
73b94f7
more cleanup
SJJCoding Mar 20, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 21 additions & 2 deletions src/main/java/frc/team2412/robot/Controls.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@ public static class ControlConstants {

private final CommandXboxController driveController;
private final CommandXboxController codriveController;
// leaving this code in in case we need to test outside of auto
// private final Trigger getWithinDistanceTrigger;

// Intake
private final Trigger driveIntakeInButton;
Expand All @@ -59,6 +61,9 @@ public static class ControlConstants {
public Controls(Subsystems s) {
driveController = new CommandXboxController(CONTROLLER_PORT);
codriveController = new CommandXboxController(CODRIVER_CONTROLLER_PORT);
// not sure what drive team wants (or if the trigger is even needed since we are only using the
// command in auto)
// getWithinDistanceTrigger = driveController.start();
this.s = s;

launcherAmpPresetButton = codriveController.x();
Expand All @@ -84,6 +89,12 @@ public Controls(Subsystems s) {
if (DRIVEBASE_ENABLED) {
bindDrivebaseControls();
}
// leaving this code in in case we need to test outside of auto
/*
if (LIMELIGHT_ENABLED) {
bindLimelightControls();
}
*/
if (LAUNCHER_ENABLED) {
bindLauncherControls();
}
Expand Down Expand Up @@ -116,9 +127,9 @@ private void bindDrivebaseControls() {
driveController::getLeftY,
driveController::getLeftX,
() -> Rotation2d.fromRotations(driveController.getRightX())));
driveController.start().onTrue(new InstantCommand(s.drivebaseSubsystem::resetGyro));
SJJCoding marked this conversation as resolved.
Show resolved Hide resolved
driveController.rightStick().onTrue(new InstantCommand(s.drivebaseSubsystem::toggleXWheels));
// driveController x
driveController.start().onTrue(new InstantCommand(s.drivebaseSubsystem::resetGyro));
// driveController
// .back()
// .onTrue(
// new InstantCommand(
Expand All @@ -127,6 +138,14 @@ private void bindDrivebaseControls() {
// new Pose2d(new Translation2d(1.3, 5.55), new Rotation2d(180)))));
}

// leaving this code in in case we need to test outside of auto
/*
public void bindLimelightControls() {
getWithinDistanceTrigger.whileTrue(
new DriveToNoteCommand(s.drivebaseSubsystem, s.limelightSubsystem));
}
*/

// intake controls
private void bindIntakeControls() {
// CommandScheduler.getInstance()
Expand Down
8 changes: 7 additions & 1 deletion src/main/java/frc/team2412/robot/Subsystems.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,13 @@
import frc.team2412.robot.subsystems.DrivebaseSubsystem;
import frc.team2412.robot.subsystems.IntakeSubsystem;
import frc.team2412.robot.subsystems.LauncherSubsystem;
import frc.team2412.robot.subsystems.LimelightSubsystem;
import frc.team2412.robot.util.DrivebaseWrapper;

public class Subsystems {
public static class SubsystemConstants {

private static final boolean IS_COMP = Robot.getInstance().isCompetition();

public static final boolean APRILTAGS_ENABLED = true;
public static final boolean LIMELIGHT_ENABLED = false;
public static final boolean CLIMB_ENABLED = false;
Expand All @@ -26,6 +26,7 @@ public static class SubsystemConstants {
public final DrivebaseWrapper drivebaseWrapper;
public final DrivebaseSubsystem drivebaseSubsystem;
public final LauncherSubsystem launcherSubsystem;
public final LimelightSubsystem limelightSubsystem;
public final IntakeSubsystem intakeSubsystem;
public final AprilTagsProcessor apriltagsProcessor;

Expand All @@ -48,6 +49,11 @@ public Subsystems() {
} else {
launcherSubsystem = null;
}
if (LIMELIGHT_ENABLED) {
limelightSubsystem = new LimelightSubsystem();
} else {
limelightSubsystem = null;
}
SJJCoding marked this conversation as resolved.
Show resolved Hide resolved
if (INTAKE_ENABLED) {
intakeSubsystem = new IntakeSubsystem();
} else {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
package frc.team2412.robot.commands.drivebase;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.Command;
import frc.team2412.robot.subsystems.DrivebaseSubsystem;
import frc.team2412.robot.subsystems.LimelightSubsystem;

public class DriveToNoteCommand extends Command {

private final DrivebaseSubsystem drivebaseSubsystem;
private final LimelightSubsystem limelightSubsystem;

// limelight placement might be different so this multiplier is convenient
private final double INVERT_DRIVE_DIRECTION = -1.0;

public DriveToNoteCommand(
DrivebaseSubsystem drivebaseSubsystem, LimelightSubsystem limelightSubsystem) {
this.drivebaseSubsystem = drivebaseSubsystem;
this.limelightSubsystem = limelightSubsystem;
addRequirements(drivebaseSubsystem);
}

@Override
public void execute() {
if (limelightSubsystem.hasTargets()) {
Translation2d move =
new Translation2d(
INVERT_DRIVE_DIRECTION
* Units.inchesToMeters(limelightSubsystem.getDistanceFromTargetInches()),
0.0);
Rotation2d turn =
new Rotation2d()
.fromDegrees(2 * INVERT_DRIVE_DIRECTION * limelightSubsystem.getHorizontalOffset());
drivebaseSubsystem.drive(move, turn, false);
}
}

@Override
public boolean isFinished() {
return (limelightSubsystem.isWithinDistance() || !limelightSubsystem.hasTargets());
SJJCoding marked this conversation as resolved.
Show resolved Hide resolved
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -173,8 +173,7 @@ public void drive(Translation2d translation, Rotation2d rotation, boolean fieldO
// if we're requesting the robot to stay still, lock wheels in X formation
if (translation.getNorm() == 0 && rotation.getRotations() == 0 && xWheelsEnabled) {
swerveDrive.lockPose();
}
if (rotationSetpoint != null) {
} else if (rotationSetpoint != null) {
swerveDrive.drive(
translation.unaryMinus(), rotationSetpoint.getRadians(), fieldOriented, false);
} else {
Expand Down
112 changes: 112 additions & 0 deletions src/main/java/frc/team2412/robot/subsystems/LimelightSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
package frc.team2412.robot.subsystems;

import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import java.util.Map;

public class LimelightSubsystem extends SubsystemBase {

// POTENTIAL CONSTANTS
private GenericEntry GOAL_DISTANCE_FROM_NOTE;

// MEMBERS

final NetworkTable networkTable;

String currentPoseString;

// network tables

// CONSTRUCTOR !
public LimelightSubsystem() {

// camera stream at http://10.24.12.11:5800

// logging
currentPoseString = "";

networkTable = NetworkTableInstance.getDefault().getTable("limelight");
ShuffleboardTab limelightTab = Shuffleboard.getTab("Limelight");

// helpers
setPipeline();

limelightTab.addBoolean("hasTarget", this::hasTargets).withPosition(0, 0).withSize(1, 1);
limelightTab
.addDouble("Horizontal Offset", this::getHorizontalOffset)
.withPosition(1, 0)
.withSize(1, 1);
limelightTab
.addDouble("Vertical Offset", this::getVerticalOffset)
.withPosition(2, 0)
.withSize(1, 1);
limelightTab
.addDouble("Distance From Note", this::getDistanceFromTargetInches)
.withPosition(3, 0)
.withSize(1, 1);
limelightTab
.addString("Current Pose ", this::getCurrentPoseString)
.withPosition(0, 1)
.withSize(4, 1);
GOAL_DISTANCE_FROM_NOTE =
limelightTab
.addPersistent("Goal distance", 20.0)
.withWidget(BuiltInWidgets.kNumberSlider)
.withPosition(4, 0)
.withSize(2, 1)
.withProperties(Map.of("Min", 0.0, "Max", 30.0))
.getEntry();
}

private void setPipeline() {
networkTable.getEntry("pipeline").setNumber(0);
}

// METHODS

public boolean hasTargets() {
return (networkTable.getEntry("tv").getDouble(0) != 0);
}

public double getHorizontalOffset() {
return networkTable.getEntry("tx").getDouble(0);
}

public double getVerticalOffset() {
return networkTable.getEntry("ty").getDouble(0);
}

public double getBoxWidth() {
return networkTable.getEntry("tlong").getDouble(0);
}
// TODO re-measure distances to make this right
public double getDistanceFromTargetInches() {

// focal length = (P x D) / W
double focal_length = 559.0394;

// distance = (W x F) / P
// returns inches for testing purposes, will divide by 39.3700787 to return meters
if (hasTargets()) {
return (14 * focal_length) / getBoxWidth();
} else {
return 0.0;
}
}

public String getCurrentPoseString() {
return currentPoseString;
}

public boolean isWithinDistance() {
return (getDistanceFromTargetInches() <= GOAL_DISTANCE_FROM_NOTE.getDouble(20.0));
}

SJJCoding marked this conversation as resolved.
Show resolved Hide resolved
@Override
public void periodic() {}
}
Loading