Skip to content

Commit

Permalink
Merge branch 'limelight' into bangbot
Browse files Browse the repository at this point in the history
  • Loading branch information
stwiggy committed Mar 27, 2024
2 parents 48638f9 + 152c3a5 commit 8ef3910
Show file tree
Hide file tree
Showing 9 changed files with 304 additions and 79 deletions.
89 changes: 47 additions & 42 deletions src/main/java/org/carlmontrobotics/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -210,11 +210,11 @@ public static final class Drivetrainc {
// seconds it takes to go from 0 to 12 volts(aka MAX)
public static final double secsPer12Volts = 0.1;

// maxRCW is the angular velocity of the robot.
// Calculated by looking at one of the motors and treating it as a point mass moving around in a circle.
// Tangential speed of this point mass is maxSpeed and the radius of the circle is sqrt((wheelBase/2)^2 + (trackWidth/2)^2)
// Angular velocity = Tangential speed / radius
public static final double maxRCW = maxSpeed / swerveRadius;
// maxRCW is the angular velocity of the robot.
// Calculated by looking at one of the motors and treating it as a point mass moving around in a circle.
// Tangential speed of this point mass is maxSpeed and the radius of the circle is sqrt((wheelBase/2)^2 + (trackWidth/2)^2)
// Angular velocity = Tangential speed / radius
public static final double maxRCW = maxSpeed / swerveRadius;

public static final boolean[] reversed = {false, false, false, false};
// public static final boolean[] reversed = {true, true, true, true};
Expand Down Expand Up @@ -255,27 +255,27 @@ public static final class Drivetrainc {
public static final double[] kForwardAccels = {1.1047/2, 0.79422/2, 0.77114/2, 1.1003/2};
public static final double[] kBackwardAccels = kForwardAccels;

public static final double autoMaxSpeedMps = 0.35 * 4.4; // Meters / second
public static final double autoMaxAccelMps2 = mu * g; // Meters / seconds^2
public static final double autoMaxVolt = 10.0; // For Drivetrain voltage constraint in RobotPath.java
// The maximum acceleration the robot can achieve is equal to the coefficient of static friction times the gravitational acceleration
// a = mu * 9.8 m/s^2
public static final double autoCentripetalAccel = mu * g * 2;
public static final double autoMaxSpeedMps = 0.35 * 4.4; // Meters / second
public static final double autoMaxAccelMps2 = mu * g; // Meters / seconds^2
public static final double autoMaxVolt = 10.0; // For Drivetrain voltage constraint in RobotPath.java
// The maximum acceleration the robot can achieve is equal to the coefficient of static friction times the gravitational acceleration
// a = mu * 9.8 m/s^2
public static final double autoCentripetalAccel = mu * g * 2;

public static final boolean isGyroReversed = true;
public static final boolean isGyroReversed = true;

// PID values are listed in the order kP, kI, and kD
public static final double[] xPIDController = {4, 0.0, 0.0};
public static final double[] yPIDController = {4, 0.0, 0.0};
public static final double[] thetaPIDController = {0.05, 0.0, 0.001};
// PID values are listed in the order kP, kI, and kD
public static final double[] xPIDController = {4, 0.0, 0.0};
public static final double[] yPIDController = {4, 0.0, 0.0};
public static final double[] thetaPIDController = {0.1, 0.0, 0.00};

public static final SwerveConfig swerveConfig = new SwerveConfig(wheelDiameterMeters, driveGearing, mu, autoCentripetalAccel, kForwardVolts, kForwardVels, kForwardAccels, kBackwardVolts, kBackwardVels, kBackwardAccels, drivekP, drivekI, drivekD, turnkP, turnkI, turnkD, turnkS, turnkV, turnkA, turnZeroDeg, driveInversion, reversed, driveModifier, turnInversion);

public static final Transform limelightTransformForPoseEstimation = Transform.BOTPOSE_WPIBLUE;
//public static final Limelight.Transform limelightTransformForPoseEstimation = Transform.BOTPOSE_WPIBLUE;

//#endregion
//#endregion

//#region Ports
//#region Ports

public static final int driveFrontLeftPort = 11; //
public static final int driveFrontRightPort = 19; //
Expand All @@ -292,21 +292,21 @@ public static final class Drivetrainc {
public static final int canCoderPortBL = 2;
public static final int canCoderPortBR = 1;

//#endregion
//#endregion

//#region Command Constants
//#region Command Constants

public static double kNormalDriveSpeed = 1; // Percent Multiplier
public static double kNormalDriveRotation = 0.5; // Percent Multiplier
public static double kSlowDriveSpeed = 0.4; // Percent Multiplier
public static double kSlowDriveRotation = 0.250; // Percent Multiplier
public static double kAlignMultiplier = 1D/3D;
public static final double kAlignForward = 0.6;
public static double kNormalDriveSpeed = 1; // Percent Multiplier
public static double kNormalDriveRotation = 0.5; // Percent Multiplier
public static double kSlowDriveSpeed = 0.4; // Percent Multiplier
public static double kSlowDriveRotation = 0.250; // Percent Multiplier
public static double kAlignMultiplier = 1D/3D;
public static final double kAlignForward = 0.6;

public static final double wheelTurnDriveSpeed = 0.0001; // Meters / Second ; A non-zero speed just used to orient the wheels to the correct angle. This should be very small to avoid actually moving the robot.
public static final double wheelTurnDriveSpeed = 0.0001; // Meters / Second ; A non-zero speed just used to orient the wheels to the correct angle. This should be very small to avoid actually moving the robot.

public static final double[] positionTolerance = {Units.inchesToMeters(.5), Units.inchesToMeters(.5), 5}; // Meters, Meters, Degrees
public static final double[] velocityTolerance = {Units.inchesToMeters(1), Units.inchesToMeters(1), 5}; // Meters, Meters, Degrees/Second
public static final double[] positionTolerance = {Units.inchesToMeters(.5), Units.inchesToMeters(.5), 5}; // Meters, Meters, Degrees
public static final double[] velocityTolerance = {Units.inchesToMeters(1), Units.inchesToMeters(1), 5}; // Meters, Meters, Degrees/Second

//#endregion
//#region Subsystem Constants
Expand All @@ -329,22 +329,27 @@ public static final class Autoc {
//#endregion
}

public static final class Limelight {
public static final class Limelightc {
public static final String INTAKE_LL_NAME = "intake-limelight";
public static final String SHOOTER_LL_NAME = "shooter-limelight";

public static final double ERROR_TOLERANCE = 0.1;
public static final double HORIZONTAL_FOV_DEG = 0;
public static final double RESOLUTION_WIDTH = 640;
public static final double MOUNT_ANGLE_DEG = 46.2; //23.228
public static final double HEIGHT_FROM_GROUND_METERS = Units.inchesToMeters(9); //16.6
public static final double ARM_TO_OUTTAKE_OFFSET_DEG= 115;
public static final class Apriltag {
public static final int RED_SPEAKER_CENTER_TAG_ID = 4;
public static final int BLUE_SPEAKER_CENTER_TAG_ID = 7;
public static final double SPEAKER_CENTER_HEIGHT_METERS = Units.inchesToMeters(56.7); //88.125
}
public static final double ERROR_TOLERANCE_RAD = 0.1;
public static final double HORIZONTAL_FOV_DEG = 0;
public static final double RESOLUTION_WIDTH_PIX = 640;
public static final double MOUNT_ANGLE_DEG_SHOOTER = 25; //23.228
public static final double MOUNT_ANGLE_DEG_INTAKE = -22; //23.228
public static final double HEIGHT_FROM_GROUND_METERS_SHOOTER = Units.inchesToMeters(56); //16.6
public static final double HEIGHT_FROM_GROUND_METERS_INTAKE = Units.inchesToMeters(52); //16.6
public static final double ARM_TO_OUTTAKE_OFFSET_DEG= 115;
public static final double NOTE_HEIGHT = Units.inchesToMeters(0);
public static final double MIN_MOVEMENT_METERSPSEC = 0.5;
public static final double MIN_MOVEMENT_RADSPSEC = 0.5;
public static final class Apriltag {
public static final int RED_SPEAKER_CENTER_TAG_ID = 4;
public static final int BLUE_SPEAKER_CENTER_TAG_ID = 7;
public static final double SPEAKER_CENTER_HEIGHT_METERS = Units.inchesToMeters(56.7); //88.125
}
}

public static final class OI {
public static final class Driver {
Expand Down
11 changes: 6 additions & 5 deletions src/main/java/org/carlmontrobotics/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,11 @@
import org.json.simple.parser.JSONParser;
//199 files
import org.carlmontrobotics.subsystems.*;
import org.carlmontrobotics.subsystems.Led;
import org.carlmontrobotics.commands.*;

import static org.carlmontrobotics.Constants.OI;
import static org.carlmontrobotics.Constants.Armc.AMP_ANGLE_RAD;
import static org.carlmontrobotics.Constants.Armc.GROUND_INTAKE_POS;
import static org.carlmontrobotics.Constants.Armc.HANG_ANGLE_RAD;
import static org.carlmontrobotics.Constants.Armc.*;
import static org.carlmontrobotics.Constants.OI.Manipulator.*;

import edu.wpi.first.math.geometry.Pose2d;
Expand Down Expand Up @@ -64,7 +63,6 @@
import com.pathplanner.lib.path.PathPlannerPath;
import static com.pathplanner.lib.auto.AutoBuilder.*;
import com.pathplanner.lib.auto.AutoBuilder;
import org.carlmontrobotics.subsystems.Led;

//java
import java.util.function.DoubleSupplier;
Expand All @@ -84,6 +82,7 @@ public class RobotContainer {
private final Led led = new Led(intakeShooter);
private final Arm arm = new Arm();
private final Drivetrain drivetrain = new Drivetrain();
private final Limelight limelight = new Limelight(drivetrain);

/* These must be equal to the pathPlanner path names from the GUI! */
// Order matters - but the first one is index 1 on the physical selector - index 0 is reserved for null command.
Expand Down Expand Up @@ -145,7 +144,9 @@ private void setDefaultCommands() {
}
private void setBindingsDriver() {
new JoystickButton(driverController, Driver.resetFieldOrientationButton).onTrue(new InstantCommand(drivetrain::resetFieldOrientation));

new JoystickButton(driverController, 1).whileTrue(new AlignToApriltag(drivetrain)); //button A
new JoystickButton(driverController, 2).whileTrue(new AlignToNote(drivetrain)); //button b?
new JoystickButton(driverController, 3).whileTrue(new AutoMATICALLYGetNote(drivetrain, limelight)); //button x?
// new JoystickButton(driverController, OI.Driver.slowDriveButton).onTrue(new ParallelCommandGroup(
// new InstantCommand(()->drivetrain.setFieldOriented(false)),
// new PrintCommand("Setting to ROBOT ORIENTED!!\nRO\nRO\nRO\n"))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

package org.carlmontrobotics.commands;

import static org.carlmontrobotics.Constants.Limelight.*;
import static org.carlmontrobotics.Constants.Limelightc.*;
import org.carlmontrobotics.subsystems.Drivetrain;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.ProxyCommand;
Expand Down
59 changes: 47 additions & 12 deletions src/main/java/org/carlmontrobotics/commands/AlignToNote.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,20 +4,55 @@

package org.carlmontrobotics.commands;

import static org.carlmontrobotics.Constants.Limelight.*;
import org.carlmontrobotics.subsystems.Drivetrain;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.ProxyCommand;
import org.carlmontrobotics.subsystems.LimelightHelpers;

public class AlignToNote extends ProxyCommand {
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import static org.carlmontrobotics.Constants.Drivetrainc.*;
import static org.carlmontrobotics.Constants.Limelightc.INTAKE_LL_NAME;

public class AlignToNote extends Command {

public final TeleopDrive teleopDrive;
public final Drivetrain drivetrain;

public final PIDController rotationPID = new PIDController(thetaPIDController[0], thetaPIDController[1], thetaPIDController[2]);

public AlignToNote(Drivetrain drivetrain) {
this.drivetrain = drivetrain;
this.teleopDrive = (TeleopDrive) drivetrain.getDefaultCommand();

rotationPID.enableContinuousInput(-180, 180);
Rotation2d targetAngle = Rotation2d.fromDegrees(drivetrain.getHeading()).minus(Rotation2d.fromDegrees(LimelightHelpers.getTX(INTAKE_LL_NAME)));
rotationPID.setSetpoint(MathUtil.inputModulus(targetAngle.getDegrees(), -180, 180));
rotationPID.setTolerance(positionTolerance[2], velocityTolerance[2]);
SendableRegistry.addChild(this, rotationPID);
//SmartDashboard.pu

addRequirements(drivetrain);
}

@Override
public void execute() {
Rotation2d targetAngle = Rotation2d.fromDegrees(drivetrain.getHeading()).minus(Rotation2d.fromDegrees(LimelightHelpers.getTX(INTAKE_LL_NAME)));
rotationPID.setSetpoint(MathUtil.inputModulus(targetAngle.getDegrees(), -180, 180));
if (teleopDrive == null) drivetrain.drive(0, 0, rotationPID.calculate(drivetrain.getHeading()));
else {
double[] driverRequestedSpeeds = teleopDrive.getRequestedSpeeds();
drivetrain.drive(driverRequestedSpeeds[0], driverRequestedSpeeds[1], rotationPID.calculate(drivetrain.getHeading()));
}
}

public AlignToNote(Drivetrain dt) {
super(() -> {
Rotation2d fieldOrientedTargetAngle = Rotation2d.fromDegrees(LimelightHelpers.getTX(INTAKE_LL_NAME)).plus(Rotation2d.fromDegrees(dt.getHeading()));
return new RotateToFieldRelativeAngle(fieldOrientedTargetAngle, dt);
});
super.addRequirements(dt);
}
//REMINDER TO UPLOAD SHOOTER LIMELIGHT WITH THE PIPELINE MODEL :D
@Override
public boolean isFinished() {
return false;
// SmartDashboard.putBoolean("At Setpoint", rotationPID.atSetpoint());
// SmartDashboard.putNumber("Error", rotationPID.getPositionError());
// return rotationPID.atSetpoint();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
// 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 org.carlmontrobotics.commands;

import static org.carlmontrobotics.Constants.Limelightc.*;

import org.carlmontrobotics.Constants.*;
import org.carlmontrobotics.subsystems.*;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.ParallelRaceGroup;
import edu.wpi.first.wpilibj2.command.ProxyCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;

public class AutoMATICALLYGetNote extends Command {
/** Creates a new AutoMATICALLYGetNote. */
private Drivetrain dt;
//private IntakeShooter effector;
private Limelight ll;
private Timer timer = new Timer();

public AutoMATICALLYGetNote(Drivetrain dt, Limelight ll /*IntakeShooter effector*/) {
addRequirements(this.dt = dt);
addRequirements(this.ll = ll);
//addRequirements(this.effector = effector);
// Use addRequirements() here to declare subsystem dependencies.
}

@Override
public void initialize() {
timer.reset();
timer.start();
//new Intake().finallyDo(()->{this.end(false);});
SmartDashboard.putBoolean("end", false);
dt.setFieldOriented(false);
}

@Override
public void execute() {
double angleErrRad = Units.degreesToRadians(LimelightHelpers.getTX(Limelightc.INTAKE_LL_NAME));
double forwardDistErrMeters = ll.getDistanceToNote();
double strafeDistErrMeters = forwardDistErrMeters * Math.tan(angleErrRad);
// dt.drive(0,0,0);
dt.drive(Math.max(forwardDistErrMeters*2, MIN_MOVEMENT_METERSPSEC), Math.max(strafeDistErrMeters*2, MIN_MOVEMENT_METERSPSEC), Math.max(angleErrRad*2,MIN_MOVEMENT_RADSPSEC));
//180deg is about 6.2 rad/sec, min is .5rad/sec
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
dt.setFieldOriented(true);
SmartDashboard.putBoolean("end", true);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
//return timer.get() >= 0.5;
}
}
61 changes: 61 additions & 0 deletions src/main/java/org/carlmontrobotics/commands/MoveToNote.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
// 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 org.carlmontrobotics.commands;

import org.carlmontrobotics.Constants.Limelightc;
import org.carlmontrobotics.subsystems.Drivetrain;
import org.carlmontrobotics.subsystems.Limelight;
import org.carlmontrobotics.subsystems.LimelightHelpers;

import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;

public class MoveToNote extends Command {
private final Drivetrain dt;
private final Limelight ll;
private Timer timer = new Timer();
/** Creates a new MoveToNote. */
public MoveToNote(Drivetrain dt, Limelight ll) {
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(this.dt=dt);
addRequirements(this.ll=ll);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
new AlignToNote(dt);
timer.reset();
timer.start();
//new Intake().finallyDo(()->{this.end(false);});
SmartDashboard.putBoolean("end", false);
dt.setFieldOriented(false);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double radErr = Units.degreesToRadians(LimelightHelpers.getTX(Limelightc.INTAKE_LL_NAME));
double distErr = ll.getDistanceToNote(); //meters
double forwardErr = distErr * Math.cos(radErr);
// dt.drive(0,0,0);
dt.drive(Math.max(forwardErr*2, .5), 0, 0);
//180deg is about 6.2 rad/sec, min is .5rad/sec
}

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

// Returns true when the command should end.
@Override
public boolean isFinished() {
return timer.get() >= 0.5;
}
}
Loading

0 comments on commit 8ef3910

Please sign in to comment.