Skip to content
This repository has been archived by the owner on Jan 6, 2024. It is now read-only.

Commit

Permalink
port over swerve from spike hector & susan
Browse files Browse the repository at this point in the history
  • Loading branch information
Owen756 committed Aug 30, 2023
1 parent 8f22ab4 commit ad0cba3
Show file tree
Hide file tree
Showing 14 changed files with 1,985 additions and 62 deletions.
82 changes: 82 additions & 0 deletions src/main/java/frc/robot/config/Config.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,14 @@

package frc.robot.config;

import com.pathplanner.lib.auto.PIDConstants;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import frc.robot.localization.VisionMode;
import frc.robot.swerve.SwerveCorner;
import frc.robot.swerve.SwerveModuleConstants;

public class Config {
public static final String SERIAL_NUMBER = System.getenv("serialnum");

Expand All @@ -12,5 +20,79 @@ public class Config {

public static final String CANIVORE_ID = "581CANivore";

public static final VisionMode VISION_MODE = VisionMode.ENABLED_UNUSED;
public static final Translation2d SWERVE_FRONT_LEFT_LOCATION =
new Translation2d(0.263525, 0.263525);
public static final Translation2d SWERVE_FRONT_RIGHT_LOCATION =
new Translation2d(0.263525, -0.263525);
public static final Translation2d SWERVE_BACK_LEFT_LOCATION =
new Translation2d(-0.263525, 0.263525);
public static final Translation2d SWERVE_BACK_RIGHT_LOCATION =
new Translation2d(-0.263525, -0.263525);

public static final double WHEEL_DIAMETER = Units.inchesToMeters(3.84);
public static final double SWERVE_STEER_GEARING_REDUCTION = 150.0 / 7.0;
public static final double SWERVE_DRIVE_GEARING_REDUCTION =
50.0 * 16.0 * 45.0 / 14.0 / 28.0 / 15.0;
public static final double SWERVE_STEER_KV = 0.0;
public static final double SWERVE_STEER_KP = 5.0;
public static final double SWERVE_STEER_KI = 0.0;
public static final double SWERVE_STEER_KD = 0.0;
public static final double SWERVE_STEER_KS = 0.0;

public static final int SWERVE_DRIVE_VOLTAGE_PEAK_FORWARD_VOLTAGE = 12;
public static final int SWERVE_DRIVE_VOLTAGE_PEAK_REVERSE_VOLTAGE = -12;
public static final double SWERVE_DRIVE_CURRENT_LIMIT = 35.0;
public static final boolean SWERVE_DRIVE_LIMITS_ENABLE = true;

public static final double SWERVE_DRIVE_KP = 0.24;
public static final double SWERVE_DRIVE_KI = 0.0;
public static final double SWERVE_DRIVE_KD = 0.0;
public static final double SWERVE_DRIVE_KV = 0.1185;
public static final double SWERVE_DRIVE_KS = 0.0;

public static final double STEER_MOTOR_LIMITS = 35;
public static final boolean SWERVE_MOTOR_LIMITS_ENABLED = true;
public static final PIDConstants SWERVE_TRANSLATION_PID = new PIDConstants(2.5, 0, 0);
public static final PIDConstants SWERVE_ROTATION_PID = new PIDConstants(4.5, 0, 0.1);
public static final PIDConstants SWERVE_ROTATION_SNAP_PID = PIDConstants(7.5, 0, 0.5);
public static final boolean SWERVE_USE_FOC = true;

final int SWERVE_FL_DRIVE_MOTOR_ID = 8;
public static final int SWERVE_FL_STEER_MOTOR_ID = 9;
public static final int SWERVE_FL_CANCODER_ID = 13;
public static final SwerveModuleConstants SWERVE_FL_CONSTANTS =
new SwerveModuleConstants(
Rotation2d.fromDegrees(182.021484375), SwerveCorner.FRONT_LEFT, true, true);

// -62.84
public static final int SWERVE_FR_DRIVE_MOTOR_ID = 6;
public static final int SWERVE_FR_STEER_MOTOR_ID = 7;
public static final int SWERVE_FR_CANCODER_ID = 12;
public static final SwerveModuleConstants SWERVE_FR_CONSTANTS =
new SwerveModuleConstants(
Rotation2d.fromDegrees(159.521484375), SwerveCorner.FRONT_RIGHT, true, true);

// -147.8
public static final int SWERVE_BL_DRIVE_MOTOR_ID = 4;
public static final int SWERVE_BL_STEER_MOTOR_ID = 5;
public static final int SWERVE_BL_CANCODER_ID = 11;
public static final SwerveModuleConstants SWERVE_BL_CONSTANTS =
new SwerveModuleConstants(
Rotation2d.fromDegrees(2.548828125), SwerveCorner.BACK_LEFT, true, true);
// 78.75
public static final int SWERVE_BR_DRIVE_MOTOR_ID = 2;
public static final int SWERVE_BR_STEER_MOTOR_ID = 3;
public static final int SWERVE_BR_CANCODER_ID = 10;
public static final SwerveModuleConstants SWERVE_BR_CONSTANTS =
new SwerveModuleConstants(
Rotation2d.fromDegrees(110.390625), SwerveCorner.BACK_RIGHT, true, true);

// 104.58

private Config() {}

private static PIDConstants PIDConstants(double d, int i, double e) {
return null;
}
}
65 changes: 65 additions & 0 deletions src/main/java/frc/robot/imu/ImuSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
// 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 frc.robot.imu;

import com.ctre.phoenix6.configs.MountPoseConfigs;
import com.ctre.phoenix6.configs.Pigeon2Configuration;
import com.ctre.phoenix6.hardware.Pigeon2;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.util.scheduling.LifecycleSubsystem;
import frc.robot.util.scheduling.SubsystemPriority;
import org.littletonrobotics.junction.Logger;

public class ImuSubsystem extends LifecycleSubsystem {
private final Pigeon2 imu;

public ImuSubsystem(Pigeon2 imu) {
super(SubsystemPriority.IMU);

this.imu = imu;

Pigeon2Configuration imuConfig = new Pigeon2Configuration();

imu.getConfigurator().apply(imuConfig);
}

public void robotPeriodic() {
Logger.getInstance().recordOutput("Imu/RobotHeading", this.getRobotHeading().getDegrees());
Logger.getInstance()
.recordOutput("Imu/RobotHeadingRadians", this.getRobotHeading().getRadians());
}

public Rotation2d getRobotHeading() {
return Rotation2d.fromDegrees(imu.getYaw().getValue());
}

public Rotation2d getRoll() {
return Rotation2d.fromDegrees(imu.getRoll().getValue());
}

public void zero() {
setAngle(new Rotation2d());

MountPoseConfigs mountPoseConfig = new MountPoseConfigs();

mountPoseConfig.MountPoseRoll = getRoll().getDegrees();

imu.getConfigurator().apply(mountPoseConfig);
}

public void setAngle(Rotation2d zeroAngle) {
this.imu.setYaw(zeroAngle.getDegrees());
}

public boolean atAngle(Rotation2d angle) {
return Math.abs(getRobotHeading().minus(angle).getDegrees()) < 3;
}

public Command getZeroCommand() {
return Commands.runOnce(() -> zero());
}
}
32 changes: 32 additions & 0 deletions src/main/java/frc/robot/localization/JacksonLagUtil.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
// 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 frc.robot.localization;

import com.fasterxml.jackson.core.JsonProcessingException;
import com.fasterxml.jackson.databind.DeserializationFeature;
import com.fasterxml.jackson.databind.ObjectMapper;
import edu.wpi.first.wpilibj.Timer;
import frc.robot.localization.LimelightHelpers.LimelightResults;

public class JacksonLagUtil {
public static void causeLag() {
ObjectMapper mapper =
new ObjectMapper().configure(DeserializationFeature.FAIL_ON_UNKNOWN_PROPERTIES, false);

System.out.println("JacksonLagUtil: Causing lag spike...");
double time = Timer.getFPGATimestamp();
try {
LimelightResults results = new LimelightResults();
mapper.readValue(mapper.writeValueAsString(results), LimelightHelpers.LimelightResults.class);
} catch (JsonProcessingException e) {
System.err.println("JacksonLagUtil: Failed to cause lag spike, JSON parser error:");
e.printStackTrace();
}
System.out.println(
"JacksonLagUtil: Lag spike caused in " + (Timer.getFPGATimestamp() - time) + "s");
}

private JacksonLagUtil() {}
}
134 changes: 134 additions & 0 deletions src/main/java/frc/robot/localization/Landmarks.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
// 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 frc.robot.localization;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import java.util.List;

public class Landmarks {
public static final Pose2d APRILTAG_1 =
new Pose2d(
Units.inchesToMeters(610.77), Units.inchesToMeters(42.19), Rotation2d.fromDegrees(180));
public static final Pose2d APRILTAG_2 =
new Pose2d(
Units.inchesToMeters(610.77), Units.inchesToMeters(108.19), Rotation2d.fromDegrees(180));
public static final Pose2d APRILTAG_3 =
new Pose2d(
Units.inchesToMeters(610.77), Units.inchesToMeters(174.19), Rotation2d.fromDegrees(180));
public static final Pose2d APRILTAG_4 =
new Pose2d(
Units.inchesToMeters(636.96), Units.inchesToMeters(265.74), Rotation2d.fromDegrees(180));
public static final Pose2d APRILTAG_5 =
new Pose2d(
Units.inchesToMeters(14.25), Units.inchesToMeters(265.74), Rotation2d.fromDegrees(0));
public static final Pose2d APRILTAG_6 =
new Pose2d(
Units.inchesToMeters(40.45), Units.inchesToMeters(174.19), Rotation2d.fromDegrees(0));
public static final Pose2d APRILTAG_7 =
new Pose2d(
Units.inchesToMeters(40.45), Units.inchesToMeters(108.19), Rotation2d.fromDegrees(0));
public static final Pose2d APRILTAG_8 =
new Pose2d(
Units.inchesToMeters(40.45), Units.inchesToMeters(42.19), Rotation2d.fromDegrees(0));

public static final Pose2d BLUE_GRID_RIGHT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(42), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_CENTER =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(108), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_LEFT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(174), Rotation2d.fromDegrees(0));

public static final Pose2d BLUE_GRID_LEFT_NODE_LEFT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(196), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_LEFT_NODE_CENTER =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(174), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_LEFT_NODE_RIGHT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(152), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_CENTER_NODE_LEFT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(130), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_CENTER_NODE_CENTER =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(108), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_CENTER_NODE_RIGHT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(86), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_RIGHT_NODE_LEFT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(64), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_RIGHT_NODE_CENTER =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(42), Rotation2d.fromDegrees(0));
public static final Pose2d BLUE_GRID_RIGHT_NODE_RIGHT =
new Pose2d(Units.inchesToMeters(54.05), Units.inchesToMeters(20), Rotation2d.fromDegrees(0));

public static final Pose2d RED_GRID_LEFT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(42), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_CENTER =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(108), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_RIGHT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(174), Rotation2d.fromDegrees(180));

public static final Pose2d RED_GRID_LEFT_NODE_RIGHT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(64), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_LEFT_NODE_CENTER =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(42), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_LEFT_NODE_LEFT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(20), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_CENTER_NODE_RIGHT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(130), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_CENTER_NODE_CENTER =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(108), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_CENTER_NODE_LEFT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(86), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_RIGHT_NODE_RIGHT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(196), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_RIGHT_NODE_CENTER =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(174), Rotation2d.fromDegrees(180));
public static final Pose2d RED_GRID_RIGHT_NODE_LEFT =
new Pose2d(
Units.inchesToMeters(596.77), Units.inchesToMeters(152), Rotation2d.fromDegrees(180));

public static final Pose2d BLUE_STAGING_MARK_FAR_RIGHT =
new Pose2d(
Units.inchesToMeters(278.05), Units.inchesToMeters(36.19), Rotation2d.fromDegrees(180));
public static final Pose2d BLUE_STAGING_MARK_RIGHT =
new Pose2d(
Units.inchesToMeters(278.05), Units.inchesToMeters(84.19), Rotation2d.fromDegrees(180));
public static final Pose2d BLUE_STAGING_MARK_LEFT =
new Pose2d(
Units.inchesToMeters(278.05), Units.inchesToMeters(132.19), Rotation2d.fromDegrees(180));
public static final Pose2d BLUE_STAGING_MARK_FAR_LEFT =
new Pose2d(
Units.inchesToMeters(278.05), Units.inchesToMeters(180.19), Rotation2d.fromDegrees(180));

public static final Pose2d RED_STAGING_MARK_FAR_LEFT =
new Pose2d(
Units.inchesToMeters(372.77), Units.inchesToMeters(36.19), Rotation2d.fromDegrees(0));
public static final Pose2d RED_STAGING_MARK_LEFT =
new Pose2d(
Units.inchesToMeters(372.77), Units.inchesToMeters(84.19), Rotation2d.fromDegrees(0));
public static final Pose2d RED_STAGING_MARK_RIGHT =
new Pose2d(
Units.inchesToMeters(372.77), Units.inchesToMeters(132.19), Rotation2d.fromDegrees(0));
public static final Pose2d RED_STAGING_MARK_FAR_RIGHT =
new Pose2d(
Units.inchesToMeters(372.77), Units.inchesToMeters(180.19), Rotation2d.fromDegrees(0));

public static final List<Pose2d> RED_GRIDS =
List.of(RED_GRID_LEFT, RED_GRID_CENTER, RED_GRID_RIGHT);
public static final List<Pose2d> BLUE_GRIDS =
List.of(BLUE_GRID_LEFT, BLUE_GRID_CENTER, BLUE_GRID_RIGHT);

private Landmarks() {}
}
Loading

0 comments on commit ad0cba3

Please sign in to comment.