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

Vision + Odometry Subsystem #2

Merged
merged 41 commits into from
Jan 26, 2024
Merged
Show file tree
Hide file tree
Changes from 40 commits
Commits
Show all changes
41 commits
Select commit Hold shift + click to select a range
45b881e
Add SwerveModule and comments for swerve
Keobkeig Jan 22, 2024
9495c7e
Add Field.java
anivanchen Jan 23, 2024
35ad4bb
Add VisionData.java
anivanchen Jan 23, 2024
49c526c
Add Fiducial.java
anivanchen Jan 23, 2024
cfab689
Add AprilTagCamera.java
anivanchen Jan 23, 2024
9ecb7ce
Ready for merge with odometry
Keobkeig Jan 23, 2024
bfd63af
Merge pull request #4 from StuyPulse/se/swerve
Keobkeig Jan 23, 2024
157d3b0
Update to wpilib 2024.2.1
BenG49 Jan 23, 2024
f136276
Add Cameras.java constants file
anivanchen Jan 23, 2024
10c0618
Make getLayoutAsDoubleArray more flexible
anivanchen Jan 23, 2024
b2a97ad
Add setFiducialLayout & Add overloaded constructor
anivanchen Jan 23, 2024
1f52046
Rename getTimeStamp
anivanchen Jan 23, 2024
861e91c
Add Vision.java
anivanchen Jan 23, 2024
7f8066a
Add Odometry.java
anivanchen Jan 23, 2024
0811dde
Fix uninitialized field error
anivanchen Jan 23, 2024
a6b7f69
Add singleton for odometry
Keobkeig Jan 23, 2024
2916132
Transform cameraPose to robotPose
anivanchen Jan 23, 2024
b9d7065
Merge pull request #7 from StuyPulse/se/swerve
anivanchen Jan 23, 2024
bc52ea2
Add stale data check
anivanchen Jan 23, 2024
96a0e18
Expose required methods
anivanchen Jan 23, 2024
900e1eb
Add swerve method calls
anivanchen Jan 23, 2024
7cddcdb
Add SwerveDrive, Odometry, Vision to robotcontainer
anivanchen Jan 23, 2024
f84f383
Add Limelight.java
anivanchen Jan 23, 2024
c4f6380
Add Limelight interface to Cameras
anivanchen Jan 23, 2024
f62b84f
Rename Vision to AprilTagVision
anivanchen Jan 23, 2024
306f9ea
Add NoteVision
anivanchen Jan 23, 2024
7731eca
Add getFPS method
anivanchen Jan 23, 2024
5aca825
Fix nullPointerException with placeholder cameras
anivanchen Jan 24, 2024
810885a
Merge SwerveDrive into Vision/Odometry (#8)
anivanchen Jan 24, 2024
f9e9f50
Add NoteVision to RobotContainer
anivanchen Jan 24, 2024
e54d33b
Add some docs
anivanchen Jan 24, 2024
e13cfa0
Add more documentationn
anivanchen Jan 24, 2024
9c4aaba
Complete requested changes
anivanchen Jan 24, 2024
fc81252
Update new VisionData call
anivanchen Jan 24, 2024
48a29ff
Expand one liners
anivanchen Jan 24, 2024
e56081b
Se/swerve (#10)
BenG49 Jan 24, 2024
cd641af
Fix CANCoder ports
BenG49 Jan 26, 2024
edd666d
Use default current limit
BenG49 Jan 26, 2024
0b27ad5
Use between wheel distances for WIDTH and LENGTH
BenG49 Jan 26, 2024
15a31ca
final variables in SwerveDrive
BenG49 Jan 26, 2024
fd1061f
Merge branch 'main' into se/vision-odometry
BenG49 Jan 26, 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
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1"
id "edu.wpi.first.GradleRIO" version "2024.2.1"
id "com.diffplug.spotless" version "6.22.0"
}

Expand Down
8 changes: 8 additions & 0 deletions src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@

import com.stuypulse.robot.commands.auton.DoNothingAuton;
import com.stuypulse.robot.constants.Ports;
import com.stuypulse.robot.subsystems.odometry.Odometry;
import com.stuypulse.robot.subsystems.swerve.SwerveDrive;
import com.stuypulse.robot.subsystems.vision.AprilTagVision;
import com.stuypulse.robot.subsystems.vision.NoteVision;
import com.stuypulse.stuylib.input.Gamepad;
import com.stuypulse.stuylib.input.gamepads.AutoGamepad;

Expand All @@ -21,6 +25,10 @@ public class RobotContainer {
public final Gamepad operator = new AutoGamepad(Ports.Gamepad.OPERATOR);

// Subsystem
SwerveDrive swerve = SwerveDrive.getInstance();
Odometry odometry = Odometry.getInstance();
AprilTagVision vision = AprilTagVision.getInstance();
NoteVision noteVision = NoteVision.getInstance();

// Autons
private static SendableChooser<Command> autonChooser = new SendableChooser<>();
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
package com.stuypulse.robot.commands.swerve;

import com.stuypulse.robot.constants.Settings;
import com.stuypulse.robot.constants.Settings.Driver.Drive;
import com.stuypulse.robot.constants.Settings.Driver.Turn;
import com.stuypulse.robot.subsystems.swerve.SwerveDrive;
import com.stuypulse.stuylib.input.Gamepad;
import com.stuypulse.stuylib.math.SLMath;
import com.stuypulse.stuylib.streams.numbers.IStream;
import com.stuypulse.stuylib.streams.numbers.filters.RateLimit;
import com.stuypulse.stuylib.streams.vectors.VStream;
import com.stuypulse.stuylib.streams.vectors.filters.VDeadZone;
import com.stuypulse.stuylib.streams.vectors.filters.VLowPassFilter;
import com.stuypulse.stuylib.streams.vectors.filters.VRateLimit;

import edu.wpi.first.wpilibj2.command.Command;

public class SwerveDriveDrive extends Command {

private SwerveDrive swerve;

private VStream speed;
private IStream turn;

private final Gamepad driver;

public SwerveDriveDrive(Gamepad driver) {
this.driver = driver;

swerve = SwerveDrive.getInstance();

speed = VStream.create(driver::getLeftStick)
.filtered(
new VDeadZone(Drive.DEADBAND),
x -> x.clamp(1),
x -> Settings.vpow(x, Drive.POWER.get()),
x -> x.mul(Drive.MAX_TELEOP_SPEED.get()),
new VRateLimit(Drive.MAX_TELEOP_ACCEL.get()),
new VLowPassFilter(Drive.RC.get())
);

turn = IStream.create(driver::getRightX)
.filtered(
x -> SLMath.deadband(x, Turn.DEADBAND.get()),
x -> SLMath.spow(x, Turn.POWER.get()),
x -> x * Turn.MAX_TELEOP_TURNING.get(),
new RateLimit(Turn.RC.get())
);

addRequirements(swerve);
}

@Override
public void execute() {
swerve.drive(speed.get(), turn.get());
}
}
50 changes: 50 additions & 0 deletions src/main/java/com/stuypulse/robot/constants/Cameras.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
package com.stuypulse.robot.constants;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;

/**
* This interface stores information about each camera.
*/
public interface Cameras {

public interface Limelight {
String [] LIMELIGHTS = {
"limelight"
};

int[] PORTS = { 5800, 5801, 5802, 5803, 5804, 5805 };

Pose3d [] POSITIONS = new Pose3d[] {
new Pose3d(
new Translation3d(Units.inchesToMeters(0), 0, Units.inchesToMeters(0)),
new Rotation3d(0, Math.toRadians(0), Math.toRadians(0))
)
};
}

public CameraConfig[] APRILTAG_CAMERAS = new CameraConfig[] {
new CameraConfig("samera0", new Pose3d(new Translation3d(), new Rotation3d())),
new CameraConfig("samera1", new Pose3d(new Translation3d(), new Rotation3d()))
};

public static class CameraConfig {
private String name;
private Pose3d location;

public CameraConfig(String name, Pose3d location) {
this.name = name;
this.location = location;
}

public String getName() {
return name;
}

public Pose3d getLocation() {
return location;
}
}
}
87 changes: 87 additions & 0 deletions src/main/java/com/stuypulse/robot/constants/Field.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
package com.stuypulse.robot.constants;

import java.util.ArrayList;

import com.stuypulse.robot.util.Fiducial;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;

import edu.wpi.first.math.util.Units;

/**
* This interface stores information about the field elements.
*/
public interface Field {

public final double FIDUCIAL_SIZE = Units.inchesToMeters(6.125);
double NOTE_LENGTH = Units.inchesToMeters(14.0);

Fiducial FIDUCIALS[] = {
// 2024 Field Fiducial Layout
new Fiducial(1, new Pose3d(new Translation3d(Units.inchesToMeters(593.68), Units.inchesToMeters(9.68), Units.inchesToMeters(53.38)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(120)))),
new Fiducial(2, new Pose3d(new Translation3d(Units.inchesToMeters(637.21), Units.inchesToMeters(34.79), Units.inchesToMeters(53.38)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(120)))),
new Fiducial(3, new Pose3d(new Translation3d(Units.inchesToMeters(652.73), Units.inchesToMeters(196.17), Units.inchesToMeters(57.13)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(180)))),
new Fiducial(4, new Pose3d(new Translation3d(Units.inchesToMeters(652.73), Units.inchesToMeters(218.42), Units.inchesToMeters(57.13)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(180)))),
new Fiducial(5, new Pose3d(new Translation3d(Units.inchesToMeters(578.77), Units.inchesToMeters(323.0), Units.inchesToMeters(53.38)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(270)))),
new Fiducial(6, new Pose3d(new Translation3d(Units.inchesToMeters(72.5), Units.inchesToMeters(323.0), Units.inchesToMeters(53.38)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(270)))),
new Fiducial(7, new Pose3d(new Translation3d(Units.inchesToMeters(-1.5), Units.inchesToMeters(218.42), Units.inchesToMeters(57.13)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(0)))),
new Fiducial(8, new Pose3d(new Translation3d(Units.inchesToMeters(-1.5), Units.inchesToMeters(196.17), Units.inchesToMeters(57.13)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(0)))),
new Fiducial(9, new Pose3d(new Translation3d(Units.inchesToMeters(14.02), Units.inchesToMeters(34.79), Units.inchesToMeters(53.38)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(60)))),
new Fiducial(10, new Pose3d(new Translation3d(Units.inchesToMeters(57.54), Units.inchesToMeters(9.68), Units.inchesToMeters(53.38)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(60)))),
new Fiducial(11, new Pose3d(new Translation3d(Units.inchesToMeters(468.69), Units.inchesToMeters(146.19), Units.inchesToMeters(52.0)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(300)))),
new Fiducial(12, new Pose3d(new Translation3d(Units.inchesToMeters(468.69), Units.inchesToMeters(177.10), Units.inchesToMeters(52.0)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(60)))),
new Fiducial(13, new Pose3d(new Translation3d(Units.inchesToMeters(441.74), Units.inchesToMeters(161.62), Units.inchesToMeters(52.0)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(180)))),
new Fiducial(14, new Pose3d(new Translation3d(Units.inchesToMeters(209.48), Units.inchesToMeters(161.62), Units.inchesToMeters(52.0)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(0)))),
new Fiducial(15, new Pose3d(new Translation3d(Units.inchesToMeters(182.73), Units.inchesToMeters(177.10), Units.inchesToMeters(52.0)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(120)))),
new Fiducial(16, new Pose3d(new Translation3d(Units.inchesToMeters(182.73), Units.inchesToMeters(146.19), Units.inchesToMeters(52.0)), new Rotation3d(Units.degreesToRadians(0), Units.degreesToRadians(0), Units.degreesToRadians(240)))),
};

public static boolean isValidFiducial(int fid) {
for(Fiducial fiducial : FIDUCIALS) {
if (fiducial.getFID() == fid) {
return true;
}
}
return false;
}

public static Fiducial[] getFiducialLayout(int... fids) {
ArrayList<Fiducial> fiducials = new ArrayList<Fiducial>();

for (int fid : fids) {
for (Fiducial fiducial : FIDUCIALS) {
if (fiducial.getFID() == fid) {
fiducials.add(fiducial);
}
}
}

Fiducial[] fiducials_array = new Fiducial[fiducials.size()];
return fiducials.toArray(fiducials_array);
}

public static double[] getLayoutAsDoubleArray(Fiducial[] fiducials) {
double[] layout = new double[fiducials.length * 7];
for (int i = 0; i < fiducials.length; i++) {
layout[i * 7 + 0] = fiducials[i].getFID();
layout[i * 7 + 1] = fiducials[i].getLocation().getX();
layout[i * 7 + 2] = fiducials[i].getLocation().getY();
layout[i * 7 + 3] = fiducials[i].getLocation().getZ();
layout[i * 7 + 4] = fiducials[i].getLocation().getRotation().getX();
layout[i * 7 + 5] = fiducials[i].getLocation().getRotation().getY();
layout[i * 7 + 6] = fiducials[i].getLocation().getRotation().getZ();
}
return layout;
}

public static Fiducial getFiducial(int fid) {
for (Fiducial fiducial : FIDUCIALS) {
if (fiducial.getFID() == fid) {
return fiducial;
}
}
return null;
}
}
8 changes: 6 additions & 2 deletions src/main/java/com/stuypulse/robot/constants/Motors.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;

import com.revrobotics.CANSparkMax;
import static com.revrobotics.CANSparkMax.IdleMode;

Expand All @@ -21,9 +22,12 @@
* - The Open Loop Ramp Rate
*/
public interface Motors {

/** Classes to store all of the values a motor needs */

public interface Swerve {
public CANSparkMaxConfig DRIVE_CONFIG = new CANSparkMaxConfig(false, IdleMode.kBrake);
public CANSparkMaxConfig TURN_CONFIG = new CANSparkMaxConfig(false, IdleMode.kBrake);
}

public static class TalonSRXConfig {
public final boolean INVERTED;
public final NeutralMode NEUTRAL_MODE;
Expand Down
26 changes: 26 additions & 0 deletions src/main/java/com/stuypulse/robot/constants/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,30 @@ public interface Gamepad {
int OPERATOR = 1;
int DEBUGGER = 2;
}

public interface Swerve {
public interface FrontRight {
int DRIVE = 10;
int TURN = 11;
int ENCODER = 1;
}

public interface FrontLeft {
int DRIVE = 12;
int TURN = 13;
int ENCODER = 2;
}

public interface BackLeft{
int DRIVE = 14;
int TURN = 15;
int ENCODER = 3;
}

public interface BackRight {
int DRIVE = 16;
int TURN = 17;
int ENCODER = 4;
}
}
}
Loading