Skip to content

Commit

Permalink
Added new logging and timeslice duration, added offseason branch chan…
Browse files Browse the repository at this point in the history
…ges.
  • Loading branch information
We-Gold committed Nov 17, 2022
1 parent 63ed773 commit e4c0f56
Show file tree
Hide file tree
Showing 12 changed files with 212 additions and 149 deletions.
17 changes: 17 additions & 0 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2023.1.1-beta-3"
id 'com.diffplug.spotless' version '6.6.1'
}

sourceCompatibility = JavaVersion.VERSION_11
Expand Down Expand Up @@ -87,3 +88,19 @@ wpi.java.configureExecutableTasks(jar)
tasks.withType(JavaCompile) {
options.compilerArgs.add '-XDstringConcat=inline'
}

spotless {
enforceCheck false

java {
target fileTree('.') {
include '**/*.java'
exclude '**/build/**', '**/build-*/**'
}
toggleOffOn()
palantirJavaFormat()
removeUnusedImports()
trimTrailingWhitespace()
endWithNewline()
}
}
Empty file modified gradlew
100644 → 100755
Empty file.
7 changes: 5 additions & 2 deletions src/main/java/frc/lib/controller/CustomXboxController.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,9 @@

import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;

import java.util.HashMap;

public class CustomXboxController {
Expand Down Expand Up @@ -52,6 +53,8 @@ public CustomXboxController(int port) {
rightTrigger = new JoystickAxis(joystick, 3);
rightXAxis = new JoystickAxis(joystick, 4);
rightYAxis = new JoystickAxis(joystick, 5);

buttonPurposeHashMap.put("type", "CustomXboxController");
}

public Trigger getButtonA() {
Expand Down Expand Up @@ -189,4 +192,4 @@ public void nameRightXAxis(String purpose) {
public void nameRightYAxis(String purpose) {
buttonPurposeHashMap.put("rightYAxis", purpose);
}
}
}
41 changes: 35 additions & 6 deletions src/main/java/frc/lib/controller/LogitechController.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,16 @@
package frc.lib.controller;

import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import java.util.HashMap;
import java.util.Map;
import java.util.stream.Collectors;

public class LogitechController {
private int port;

private final Joystick joystick;

private final Trigger A;
Expand Down Expand Up @@ -38,6 +43,8 @@ public class LogitechController {
* @param port The port the controller is on
*/
public LogitechController(int port) {
this.port = port;

joystick = new Joystick(port);

A = new JoystickButton(joystick, 1);
Expand Down Expand Up @@ -66,6 +73,8 @@ public LogitechController(int port) {
leftYAxis.setInverted(true);
rightYAxis.setInverted(true);
dPadYAxis.setInverted(true);

buttonPurposeHashMap.put("type", "LogitechController");
}

public Trigger getA() {
Expand Down Expand Up @@ -220,27 +229,47 @@ public void nameDPadLeft(String purpose) {
buttonPurposeHashMap.put("dPadLeft", purpose);
}

public void namLftXAxis(String purpose) {
public void nameLeftXAxis(String purpose) {
buttonPurposeHashMap.put("leftXAxis", purpose);
}

public void namLftYAxis(String purpose) {
public void nameLeftYAxis(String purpose) {
buttonPurposeHashMap.put("leftYAxis", purpose);
}

public void namRghtXAxis(String purpose) {
public void nameRightXAxis(String purpose) {
buttonPurposeHashMap.put("rightXAxis", purpose);
}

public void namRghtYAxis(String purpose) {
public void nameRightYAxis(String purpose) {
buttonPurposeHashMap.put("rightYAxis", purpose);
}

public void namDadXAxis(String purpose) {
public void nameDPadXAxis(String purpose) {
buttonPurposeHashMap.put("dPadXAxis", purpose);
}

public void namDadYAxis(String purpose) {
public void nameDPadYAxis(String purpose) {
buttonPurposeHashMap.put("dPadYAxis", purpose);
}

public void sendButtonNamesToNT() {
NetworkTableInstance.getDefault()
.getTable("Controllers")
.getEntry(port + "")
.setString(toJSON());
}

/**
* @return Button names as a JSON String
*/
public String toJSON() {
return buttonPurposeHashMap.entrySet().stream()
.map((Map.Entry<String, String> buttonEntry) -> stringifyButtonName(buttonEntry))
.collect(Collectors.joining(", ", "{", "}"));
}

private String stringifyButtonName(Map.Entry<String, String> buttonEntry) {
return "\"" + buttonEntry.getKey() + "\": " + "\"" + buttonEntry.getValue() + "\"";
}
}
29 changes: 29 additions & 0 deletions src/main/java/frc/lib/controller/ThrustmasterJoystick.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,16 @@
package frc.lib.controller;

import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import java.util.HashMap;
import java.util.Map;
import java.util.stream.Collectors;

public class ThrustmasterJoystick {
private int port;

private final Joystick joystick;

private final Trigger trigger;
Expand Down Expand Up @@ -36,6 +41,8 @@ public class ThrustmasterJoystick {
* @param port The port the controller is on
*/
public ThrustmasterJoystick(int port) {
this.port = port;

joystick = new Joystick(port);

trigger = new JoystickButton(joystick, 1);
Expand All @@ -60,6 +67,8 @@ public ThrustmasterJoystick(int port) {
zAxis = new JoystickAxis(joystick, 2);
sliderAxis = new JoystickAxis(joystick, 3);
sliderAxis.setInverted(true);

buttonPurposeHashMap.put("type", "ThrustmasterJoystick");
}

public Trigger getTrigger() {
Expand Down Expand Up @@ -221,4 +230,24 @@ public void nameZAxis(String purpose) {
public void nameSliderAxis(String purpose) {
buttonPurposeHashMap.put("sliderAxis", purpose);
}

public void sendButtonNamesToNT() {
NetworkTableInstance.getDefault()
.getTable("Controllers")
.getEntry(port + "")
.setString(toJSON());
}

/**
* @return Button names as a JSON String
*/
public String toJSON() {
return buttonPurposeHashMap.entrySet().stream()
.map((Map.Entry<String, String> buttonEntry) -> stringifyButtonName(buttonEntry))
.collect(Collectors.joining(", ", "{", "}"));
}

private String stringifyButtonName(Map.Entry<String, String> buttonEntry) {
return "\"" + buttonEntry.getKey() + "\": " + "\"" + buttonEntry.getValue() + "\"";
}
}
20 changes: 17 additions & 3 deletions src/main/java/frc/lib/loops/UpdateManager.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
package frc.lib.loops;

import edu.wpi.first.wpilibj.TimesliceRobot;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.Subsystem;

public class UpdateManager {
private TimesliceRobot robot;
Expand All @@ -9,7 +11,19 @@ public UpdateManager(TimesliceRobot robot) {
this.robot = robot;
}

public void schedule(Updatable subsystem, double updateTimeslice) {
robot.schedule(() -> subsystem.update(), updateTimeslice);
/**
* @param subsystem The subsystem getting registered.
*/
public void schedule(Subsystem subsystem) {
CommandScheduler.getInstance().registerSubsystem(subsystem);
}
}

/**
* @param subsystem The subsystem getting registered.
* @param updateTimeslice The corresponding timeslice of the subsystem.
*/
public void schedule(Subsystem subsystem, double updateTimeslice) {
schedule(subsystem);
robot.schedule(() -> ((Updatable) subsystem).update(), updateTimeslice);
}
}
55 changes: 28 additions & 27 deletions src/main/java/frc/lib/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.DemandType;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import com.ctre.phoenix.sensors.CANCoder;
import com.ctre.phoenix.sensors.WPI_CANCoder;

import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModuleState;
Expand All @@ -14,9 +15,9 @@
public class SwerveModule {
public int moduleNumber;
private double angleOffset;
private WPI_TalonFX mAngleMotor;
private WPI_TalonFX mDriveMotor;
private CANCoder angleEncoder;
private WPI_TalonFX angleMotor;
private WPI_TalonFX driveMotor;
private WPI_CANCoder angleEncoder;
private double lastAngle;
private boolean inverted;

Expand All @@ -31,18 +32,18 @@ public SwerveModule(int moduleNumber, SwerveModuleConstants moduleConstants) {

/* Angle Encoder Config */
angleEncoder = moduleConstants.canivoreName.isEmpty()
? new CANCoder(moduleConstants.cancoderID)
: new CANCoder(moduleConstants.cancoderID, moduleConstants.canivoreName.get());
? new WPI_CANCoder(moduleConstants.cancoderID)
: new WPI_CANCoder(moduleConstants.cancoderID, moduleConstants.canivoreName.get());
configAngleEncoder();

/* Angle Motor Config */
mAngleMotor = moduleConstants.canivoreName.isEmpty()
angleMotor = moduleConstants.canivoreName.isEmpty()
? new WPI_TalonFX(moduleConstants.angleMotorID)
: new WPI_TalonFX(moduleConstants.angleMotorID, moduleConstants.canivoreName.get());
configAngleMotor();

/* Drive Motor Config */
mDriveMotor = moduleConstants.canivoreName.isEmpty()
driveMotor = moduleConstants.canivoreName.isEmpty()
? new WPI_TalonFX(moduleConstants.driveMotorID)
: new WPI_TalonFX(moduleConstants.driveMotorID, moduleConstants.canivoreName.get());
configDriveMotor();
Expand All @@ -59,13 +60,13 @@ public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop)

if (isOpenLoop) {
double percentOutput = desiredState.speedMetersPerSecond / Constants.SwerveConstants.maxSpeed;
mDriveMotor.set(ControlMode.PercentOutput, percentOutput);
driveMotor.set(ControlMode.PercentOutput, percentOutput);
} else {
double velocity = Conversions.MPSToFalcon(
desiredState.speedMetersPerSecond,
Constants.SwerveConstants.wheelCircumference,
Constants.SwerveConstants.driveGearRatio);
mDriveMotor.set(
driveMotor.set(
ControlMode.Velocity,
velocity,
DemandType.ArbitraryFeedForward,
Expand All @@ -76,15 +77,15 @@ public void setDesiredState(SwerveModuleState desiredState, boolean isOpenLoop)
? lastAngle
: desiredState.angle
.getDegrees(); // Prevent rotating module if speed is less then 1%. Prevents Jittering.
mAngleMotor.set(
angleMotor.set(
ControlMode.Position, Conversions.degreesToFalcon(angle, Constants.SwerveConstants.angleGearRatio));
lastAngle = angle;
}

public void resetToAbsolute() {
double absolutePosition = Conversions.degreesToFalcon(
getCanCoder().getDegrees() - angleOffset, Constants.SwerveConstants.angleGearRatio);
mAngleMotor.setSelectedSensorPosition(absolutePosition);
angleMotor.setSelectedSensorPosition(absolutePosition);
}

private void configAngleEncoder() {
Expand All @@ -93,21 +94,21 @@ private void configAngleEncoder() {
}

private void configAngleMotor() {
mAngleMotor.configFactoryDefault();
mAngleMotor.configAllSettings(Robot.ctreConfigs.swerveAngleFXConfig);
mAngleMotor.setInverted(Constants.SwerveConstants.angleMotorInvert);
mAngleMotor.setNeutralMode(Constants.SwerveConstants.angleNeutralMode);
mAngleMotor.enableVoltageCompensation(true);
angleMotor.configFactoryDefault();
angleMotor.configAllSettings(Robot.ctreConfigs.swerveAngleFXConfig);
angleMotor.setInverted(Constants.SwerveConstants.angleMotorInvert);
angleMotor.setNeutralMode(Constants.SwerveConstants.angleNeutralMode);
angleMotor.enableVoltageCompensation(true);
resetToAbsolute();
}

private void configDriveMotor() {
mDriveMotor.configFactoryDefault();
mDriveMotor.configAllSettings(Robot.ctreConfigs.swerveDriveFXConfig);
mDriveMotor.setNeutralMode(Constants.SwerveConstants.driveNeutralMode);
mDriveMotor.setSelectedSensorPosition(0);
mDriveMotor.enableVoltageCompensation(true);
mDriveMotor.setInverted(inverted);
driveMotor.configFactoryDefault();
driveMotor.configAllSettings(Robot.ctreConfigs.swerveDriveFXConfig);
driveMotor.setNeutralMode(Constants.SwerveConstants.driveNeutralMode);
driveMotor.setSelectedSensorPosition(0);
driveMotor.enableVoltageCompensation(true);
driveMotor.setInverted(inverted);
}

public Rotation2d getCanCoder() {
Expand All @@ -116,19 +117,19 @@ public Rotation2d getCanCoder() {

public SwerveModuleState getState() {
double velocity = Conversions.falconToMPS(
mDriveMotor.getSelectedSensorVelocity(),
driveMotor.getSelectedSensorVelocity(),
Constants.SwerveConstants.wheelCircumference,
Constants.SwerveConstants.driveGearRatio);
Rotation2d angle = Rotation2d.fromDegrees(Conversions.falconToDegrees(
mAngleMotor.getSelectedSensorPosition(), Constants.SwerveConstants.angleGearRatio));
angleMotor.getSelectedSensorPosition(), Constants.SwerveConstants.angleGearRatio));
return new SwerveModuleState(velocity, angle);
}

public double getDriveTemperature() {
return mDriveMotor.getTemperature();
return driveMotor.getTemperature();
}

public double getSteerTemperature() {
return mAngleMotor.getTemperature();
return angleMotor.getTemperature();
}
}
Loading

0 comments on commit e4c0f56

Please sign in to comment.