-
Notifications
You must be signed in to change notification settings - Fork 13
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #62 from SJJCoding/main
PR for vision branch - working note detection and new drive method.
- Loading branch information
Showing
5 changed files
with
185 additions
and
5 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
44 changes: 44 additions & 0 deletions
44
src/main/java/frc/team2412/robot/commands/drivebase/DriveToNoteCommand.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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()); | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
112 changes: 112 additions & 0 deletions
112
src/main/java/frc/team2412/robot/subsystems/LimelightSubsystem.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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)); | ||
} | ||
|
||
@Override | ||
public void periodic() {} | ||
} |