Skip to content

Commit

Permalink
Merge branch 'dev' into manip+wrist-inverted
Browse files Browse the repository at this point in the history
  • Loading branch information
Mason-Lam authored Sep 29, 2023
2 parents 2c7058f + 9a16e28 commit fd2feb0
Show file tree
Hide file tree
Showing 12 changed files with 478 additions and 75 deletions.
Empty file modified gradlew
100644 → 100755
Empty file.
154 changes: 138 additions & 16 deletions src/main/java/frc/team3128/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@

import java.util.ArrayList;
import java.util.HashMap;
import java.util.List;

import com.pathplanner.lib.PathConstraints;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.numbers.N1;
Expand All @@ -16,9 +20,10 @@
import frc.team3128.common.hardware.camera.Camera;

import frc.team3128.common.swerveNeo.SwerveModuleConstants;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
Expand All @@ -33,7 +38,54 @@ public static class ConversionConstants {
public static final double FALCON_NUpS_TO_RPM = 60 / FALCON_ENCODER_RESOLUTION; // sensor units per second to rpm
}

public static class TrajectoryConstants {
public static final Rotation2d HEADING_0 = Rotation2d.fromDegrees(180);

public static final Translation2d POINT_1 = new Translation2d(12.7, 6.75);
public static final Rotation2d HEADING_1 = Rotation2d.fromDegrees(180);
public static final double CONDITION_1 = 12.7;

public static final List<Translation2d>POINT_2 = new ArrayList<Translation2d>() {
{
add(POINT_2A);
add(POINT_2B);
}
};
public static final Translation2d POINT_2A = new Translation2d(5.6, 4.6);
public static final Translation2d POINT_2B = new Translation2d(5.6, 0.8);
public static final Rotation2d HEADING_2 = Rotation2d.fromDegrees(180);
public static final double CONDITION_2 = 5.6;

public static final List<Translation2d>POINT_3 = new ArrayList<Translation2d>() {
{
add(POINT_3A);
add(POINT_3B);
}
};
public static final Translation2d POINT_3A = new Translation2d(2.8, 0.8);
public static final Translation2d POINT_3B = new Translation2d(2.8, 4.6);
public static final Rotation2d HEADING_3 = Rotation2d.fromDegrees(180);
public static final double CONDITION_3 = 2.25;

public static final Rotation2d HEADING_4A = Rotation2d.fromDegrees(135);
public static final Rotation2d HEADING_4B = Rotation2d.fromDegrees(-135);

public static final Pose2d[] END_POINTS = new Pose2d[]{
new Pose2d(1.90,0.5,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,1.05,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,1.65,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,2.15,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,2.75,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,3.3,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,3.85,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,4.45,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,4.89,Rotation2d.fromDegrees(180))
};
}

public static class AutoConstants {
public static final PathConstraints pathConstraints = new PathConstraints(SwerveConstants.maxSpeed, SwerveConstants.maxAcceleration);

public static final Pose2d PICKUP_1 = new Pose2d(5.9, 0.95, Rotation2d.fromDegrees(0));
public static final Pose2d PICKUP_2 = new Pose2d(7.1, 2.28, Rotation2d.fromDegrees(45));
public static final Pose2d PICKUP_3 = new Pose2d(7.1, 3.3, Rotation2d.fromDegrees(-45));
Expand All @@ -46,6 +98,11 @@ public static class AutoConstants {
public static final Pose2d ClimbSetupOutsideBot = new Pose2d(5.6, 2.9, Rotation2d.fromDegrees(180));
public static final Pose2d ClimbSetupOutsideTop = new Pose2d(5.6, 3.3, Rotation2d.fromDegrees(180));

public static final double ANGLE_THRESHOLD = 3;
public static final double VELOCITY_THRESHOLD = 8;
public static final double RAMP_THRESHOLD = 8;
public static final double DRIVE_SPEED = Units.inchesToMeters(15);

public static final Pose2d[] STARTING_POINTS = new Pose2d[] {
new Pose2d(1.85 ,0.5, Rotation2d.fromDegrees(180)),
new Pose2d(1.85 ,1.05, Rotation2d.fromDegrees(180)),
Expand All @@ -58,6 +115,24 @@ public static class AutoConstants {
new Pose2d(1.85 ,5, Rotation2d.fromDegrees(180))
};

public static final Pose2d[] SCORES = new Pose2d[]{
new Pose2d(1.90,0.5,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,1.05,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,1.65,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,2.15,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,2.75,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,3.3,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,3.85,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,4.45,Rotation2d.fromDegrees(180)),
new Pose2d(1.90,4.89,Rotation2d.fromDegrees(180))
};

public static final Pose2d[][] SCORES_GRID = new Pose2d[][] {
new Pose2d[] {SCORES[0], SCORES[3], SCORES[6]},
new Pose2d[] {SCORES[1], SCORES[4], SCORES[7]},
new Pose2d[] {SCORES[2], SCORES[5], SCORES[8]}
};

public static final double BALANCE_FF = 0.3;
}

Expand All @@ -67,8 +142,8 @@ public static class SwerveConstants {

/* Drivetrain Constants */
public static final double bumperLength = Units.inchesToMeters(5);
public static final double trackWidth = Units.inchesToMeters(26); //Hand measure later
public static final double wheelBase = Units.inchesToMeters(26); //Hand measure later
public static final double trackWidth = Units.inchesToMeters(20.75); //Hand measure later
public static final double wheelBase = Units.inchesToMeters(20.75); //Hand measure later
public static final double robotLength = bumperLength + trackWidth;
public static final double wheelDiameter = Units.inchesToMeters(4);
public static final double wheelCircumference = wheelDiameter * Math.PI;
Expand All @@ -85,7 +160,8 @@ public static class SwerveConstants {
new Translation2d(-wheelBase / 2.0, -trackWidth / 2.0));

/* Swerve Current Limiting */
public static final int currentLimit = 40;
public static final int angleLimit = 15; //30
public static final int driveLimit = 25; //40;

public static final int angleContinuousCurrentLimit = 25;
public static final int anglePeakCurrentLimit = 40;
Expand Down Expand Up @@ -158,7 +234,7 @@ public static class SwerveConstants {
public static final TrapezoidProfile.Constraints CONSTRAINTS = new TrapezoidProfile.Constraints(maxSpeed, maxAcceleration);

/* Motor Inverts */
public static final boolean driveMotorInvert = false;
public static final boolean driveMotorInvert = true;
public static final boolean angleMotorInvert = true;

/* Angle Encoder Invert */
Expand All @@ -175,7 +251,7 @@ public static final class Mod0 {
public static final int driveMotorID = 1;
public static final int angleMotorID = 2;
public static final int canCoderID = 20;
public static final double angleOffset = -162.25;//-157.763671875+180; // -156.357421875;//-46.5 + 90; //104.5;//19.599609375; // 19.51171875;//-51.85546875; // 37.35; // degrees
public static final double angleOffset = -9.9;
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}
Expand All @@ -185,7 +261,7 @@ public static final class Mod1 {
public static final int driveMotorID = 3;
public static final int angleMotorID = 4;
public static final int canCoderID = 21;
public static final double angleOffset = -50.36;//129.375; //126.38671875000001; //23.466 + 90;//-132.25;//311.66015625 - 360; //132.5390625; //311.8359375; //10.45; // degrees
public static final double angleOffset = -64.072;
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}
Expand All @@ -195,7 +271,7 @@ public static final class Mod2 {
public static final int driveMotorID = 5;
public static final int angleMotorID = 6;
public static final int canCoderID = 22;
public static final double angleOffset = -65.74;//-69.697265625+180; //-72.0703125;//-70.751953125; //-70.75; //109.51171875; //38.75; // degrees
public static final double angleOffset = -70.137;
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}
Expand All @@ -205,7 +281,7 @@ public static final class Mod3 {
public static final int driveMotorID = 7;
public static final int angleMotorID = 8;
public static final int canCoderID = 23;
public static final double angleOffset = 124.27;//-54.31640625; //-52.91015625; //-52.9; //306.2109375; //307.6171875; // 58.88; // degrees
public static final double angleOffset = -108.633;
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, angleOffset);
}
Expand All @@ -222,6 +298,10 @@ public static class VisionConstants {
new Transform2d(new Translation2d(Units.inchesToMeters(-5.75),
Units.inchesToMeters(11.5)), Rotation2d.fromDegrees(180)));

public static final PIDController xController = new PIDController(1, 0, 0);
public static final PIDController yController = new PIDController(1, 0, 0);
public static final PIDController rController = new PIDController(1, 0, 0);

public static final double SCREEN_WIDTH = 320;
public static final double SCREEN_HEIGHT = 240;

Expand Down Expand Up @@ -448,19 +528,40 @@ public static class FieldConstants{
new Translation2d(cableBumpOuterX, chargingStationRightY)
};


public static Pose2d allianceFlip(Pose2d pose) {
if (DriverStation.getAlliance() == Alliance.Red) {
return flip(pose);
}
return pose;
}

public static Translation2d allianceFlip(Translation2d translation) {
if (DriverStation.getAlliance() == Alliance.Red) {
return flipTranslation(translation);
}
return translation;
}

public static Rotation2d allianceFlip(Rotation2d rotation) {
if (DriverStation.getAlliance() == Alliance.Red) {
return flipRotation(rotation);
}
return rotation;
}

public static Pose2d flip(Pose2d pose) {
double angle = 180 - pose.getRotation().getDegrees();
return new Pose2d(
FIELD_X_LENGTH - pose.getX(),
pose.getY(),
Rotation2d.fromDegrees(angle));
return new Pose2d(flipTranslation(pose.getTranslation()), flipRotation(pose.getRotation()));
}

public static Translation2d flipTranslation(Translation2d translation) {
return new Translation2d (
FIELD_X_LENGTH - translation.getX(),
translation.getY()
);
}

public static Rotation2d flipRotation(Rotation2d rotation) {
return Rotation2d.fromDegrees(MathUtil.inputModulus(180 - rotation.getDegrees(), -180, 180));
}
}

Expand Down Expand Up @@ -549,8 +650,29 @@ public static class ManipulatorConstants{
public static final double ABSOLUTE_THRESHOLD = 20;
}

public static class ElevatorConstants {
public static final int ELV1_ID = 11;
public static final int ELV2_ID = 12;

public static final double kP = 6;
public static final double kI = 0;
public static final double kD = 0;

public static final double kS = 0.475;
public static final double kV = 0;
public static final double kG = 0.625;

public static final double MIN_DIST = 5; //Ask Charlie
public static final double MAX_DIST = 55; //Ask Charlie

public static final double GEAR_RATIO = 12.5;
public static final double SPOOL_CIRCUMFERENCE = 3 * Math.PI;

public static final int CURRENT_LIMIT = 80;
}

public static class BalanceConstants{
public static final double turnKP = 0.05;
public static final double turnKP = 6;
public static final double turnKI = 0;
public static final double turnKD = .005;
public static final double TURN_TOLERANCE = 1.5;
Expand Down
8 changes: 7 additions & 1 deletion src/main/java/frc/team3128/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
import frc.team3128.common.hardware.input.NAR_XboxController;
import frc.team3128.common.narwhaldashboard.NarwhalDashboard;
import frc.team3128.common.utility.Log;
import frc.team3128.subsystems.Elevator;
import frc.team3128.subsystems.Led;
import frc.team3128.common.utility.NAR_Shuffleboard;
import frc.team3128.subsystems.Swerve;
Expand Down Expand Up @@ -96,9 +97,14 @@ private void configureButtonBindings() {
controller.getButton("LeftTrigger").onTrue(new InstantCommand(()-> swerve.throttle = .25)).onFalse(new InstantCommand(()-> swerve.throttle = 0.8));
controller.getButton("X").onTrue(new RunCommand(()-> swerve.xlock(), swerve)).onFalse(new InstantCommand(()-> swerve.stop(),swerve));
controller.getButton("B").onTrue(new InstantCommand(()-> swerve.resetEncoders()));
controller.getButton("Start").onTrue(new InstantCommand(()-> swerve.zeroGyro()));

rightStick.getButton(1).onTrue(new InstantCommand(()->swerve.zeroGyro()));

rightStick.getButton(2).onTrue(new InstantCommand(()-> Elevator.getInstance().set(0.4))).onFalse(new InstantCommand(()-> Elevator.getInstance().set(0)));
rightStick.getButton(3).onTrue(new InstantCommand(()-> Elevator.getInstance().set(-0.4))).onFalse(new InstantCommand(()-> Elevator.getInstance().set(0)));
rightStick.getButton(4).onTrue(moveElevator(30));
rightStick.getButton(5).onTrue(new InstantCommand(()-> Elevator.getInstance().resetEncoder()));

rightStick.getButton(7).onTrue(Commands.sequence(
Commands.deadline(Commands.sequence(new WaitUntilCommand(()-> Math.abs(swerve.getPitch()) > 6), new CmdBangBangBalance()), new CmdBalance()),
//new RunCommand(()-> swerve.drive(new Translation2d(CmdBalance.DIRECTION ? -0.25 : 0.25,0),0,true)).withTimeout(0.5),
Expand Down
6 changes: 5 additions & 1 deletion src/main/java/frc/team3128/autonomous/Trajectories.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public class Trajectories {

private static HashMap<String, List<PathPlannerTrajectory>> trajectories = new HashMap<String, List<PathPlannerTrajectory>>();

private static SwerveAutoBuilder builder;
public static SwerveAutoBuilder builder;

private static HashMap<String, Command> CommandEventMap = new HashMap<String, Command>();

Expand Down Expand Up @@ -95,6 +95,10 @@ public static CommandBase get(String name) {
return builder.fullAuto(trajectories.get(name));
}

public static CommandBase generateAuto(PathPlannerTrajectory trajectory) {
return builder.fullAuto(trajectory);
}

public static PathPlannerTrajectory line(Pose2d start, Pose2d end) {
return PathPlanner.generatePath(
new PathConstraints(maxSpeed, 4),
Expand Down
57 changes: 57 additions & 0 deletions src/main/java/frc/team3128/commands/CmdAutoBalance.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
package frc.team3128.commands;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.CommandBase;
import static frc.team3128.Constants.AutoConstants.*;
import frc.team3128.subsystems.Swerve;

public class CmdAutoBalance extends CommandBase{
private final Swerve swerve;
private double prevAngle;
private boolean onRamp;

public CmdAutoBalance(boolean intialDirection) {
swerve = Swerve.getInstance();
}

@Override
public void initialize() {
prevAngle = swerve.getPitch();
onRamp = false;
}

@Override
public void execute() {
final double angle = swerve.getPitch();
final double angleVelocity = (angle - prevAngle) / 0.02;
prevAngle = angle;

if (angle > RAMP_THRESHOLD) onRamp = true;

if (Math.abs(angle) < ANGLE_THRESHOLD && onRamp) {
swerve.xlock();
return;
}

if ((angle < 0.0 && angleVelocity > VELOCITY_THRESHOLD) || (angle > 0.0 && angleVelocity < VELOCITY_THRESHOLD)) {
swerve.stop();
return;
}

swerve.drive(new Translation2d(DRIVE_SPEED * (angle > 0.0 ? -1.0 : 1.0), 0), 0, false);
}

@Override
public void end(boolean interrupted) {
swerve.xlock();
}

@Override
public boolean isFinished() {
return false;

}

}
Loading

0 comments on commit fd2feb0

Please sign in to comment.