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

Update, fix several issues #11

Open
wants to merge 5 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
/.gradle/
/build/
/examples/*/build/
bin/

# Intellij Project Files
/.idea/
/.vscode/
4 changes: 2 additions & 2 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,15 @@ allprojects {
maven { url = uri('https://frcmaven.wpi.edu/artifactory/release/') }

// CTRE
maven { url = uri('https://devsite.ctr-electronics.com/maven/release/') }
maven { url = uri('https://maven.ctr-electronics.com/release/') }

// REV
maven { url = uri('https://maven.revrobotics.com/') }
}
}

dependencies {
implementation 'edu.wpi.first.wpilibj:wpilibj-java:2022.1.1'
implementation 'edu.wpi.first.wpilibj:wpilibj-java:2022.3.1'

// CTRE is implementation because it is not a hard requirement
implementation 'com.ctre.phoenix:api-java:5.20.2'
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import com.swervedrivespecialties.examples.mk3minibot.commands.DriveCommand;
import com.swervedrivespecialties.examples.mk3minibot.subsystems.DrivetrainSubsystem;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.button.Button;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import com.swervedrivespecialties.examples.mk3testchassis.commands.DriveCommand;
import com.swervedrivespecialties.examples.mk3testchassis.subsystems.DrivetrainSubsystem;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.button.Button;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
package com.swervedrivespecialties.swervelib;

public interface DriveController {
Object getDriveMotor();

void setReferenceVoltage(double voltage);

double getStateVelocity();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
package com.swervedrivespecialties.swervelib;

import com.swervedrivespecialties.swervelib.ctre.*;
import com.swervedrivespecialties.swervelib.rev.NeoDriveControllerFactoryBuilder;
import com.swervedrivespecialties.swervelib.rev.NeoSteerConfiguration;
import com.swervedrivespecialties.swervelib.rev.NeoSteerControllerFactoryBuilder;
import com.swervedrivespecialties.swervelib.rev.*;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;

public final class Mk3SwerveModuleHelper {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
package com.swervedrivespecialties.swervelib;

import com.swervedrivespecialties.swervelib.ctre.*;
import com.swervedrivespecialties.swervelib.rev.NeoDriveControllerFactoryBuilder;
import com.swervedrivespecialties.swervelib.rev.NeoSteerConfiguration;
import com.swervedrivespecialties.swervelib.rev.NeoSteerControllerFactoryBuilder;
import com.swervedrivespecialties.swervelib.rev.*;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;

public final class Mk4SwerveModuleHelper {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
package com.swervedrivespecialties.swervelib;

public interface SteerController {
Object getSteerMotor();

AbsoluteEncoder getSteerEncoder();

double getReferenceAngle();

void setReferenceAngle(double referenceAngleRadians);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,12 @@
package com.swervedrivespecialties.swervelib;

public interface SwerveModule {
Object getDriveMotor();

Object getSteerMotor();

AbsoluteEncoder getSteerEncoder();

double getDriveVelocity();

double getSteerAngle();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package com.swervedrivespecialties.swervelib;

import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;

public class SwerveModuleFactory<DriveConfiguration, SteerConfiguration> {
Expand Down Expand Up @@ -47,6 +46,21 @@ private ModuleImplementation(DriveController driveController, SteerController st
this.steerController = steerController;
}

@Override
public Object getDriveMotor() {
return driveController.getDriveMotor();
}

@Override
public Object getSteerMotor() {
return steerController.getSteerMotor();
}

@Override
public AbsoluteEncoder getSteerEncoder() {
return steerController.getSteerEncoder();
}

@Override
public double getDriveVelocity() {
return driveController.getStateVelocity();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,13 @@

import com.ctre.phoenix.ErrorCode;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;

public final class CtreUtils {
private CtreUtils() {
}
private CtreUtils() {}

public static void checkCtreError(ErrorCode errorCode, String message) {
if (errorCode != ErrorCode.OK) {
if (RobotBase.isReal() && errorCode != ErrorCode.OK) {
DriverStation.reportError(String.format("%s: %s", message, errorCode.toString()), false);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,11 @@ private ControllerImplementation(TalonFX motor, double sensorVelocityCoefficient
this.sensorVelocityCoefficient = sensorVelocityCoefficient;
}

@Override
public Object getDriveMotor() {
return this.motor;
}

@Override
public void setReferenceVoltage(double voltage) {
motor.set(TalonFXControlMode.PercentOutput, voltage / nominalVoltage);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,16 @@ private ControllerImplementation(TalonFX motor,
this.absoluteEncoder = absoluteEncoder;
}

@Override
public Object getSteerMotor() {
return this.motor;
}

@Override
public AbsoluteEncoder getSteerEncoder() {
return this.absoluteEncoder;
}

@Override
public double getReferenceAngle() {
return referenceAngleRadians;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,11 @@ private ControllerImplementation(CANSparkMax motor, RelativeEncoder encoder) {
this.encoder = encoder;
}

@Override
public Object getDriveMotor() {
return this.motor;
}

@Override
public void setReferenceVoltage(double voltage) {
motor.setVoltage(voltage);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ public static class ControllerImplementation implements SteerController {
private static final int ENCODER_RESET_ITERATIONS = 500;
private static final double ENCODER_RESET_MAX_ANGULAR_VELOCITY = Math.toRadians(0.5);

@SuppressWarnings({"FieldCanBeLocal", "unused"})
@SuppressWarnings("FieldCanBeLocal")
private final CANSparkMax motor;
private final SparkMaxPIDController controller;
private final RelativeEncoder motorEncoder;
Expand All @@ -116,6 +116,16 @@ public ControllerImplementation(CANSparkMax motor, AbsoluteEncoder absoluteEncod
this.absoluteEncoder = absoluteEncoder;
}

@Override
public Object getSteerMotor() {
return this.motor;
}

@Override
public AbsoluteEncoder getSteerEncoder() {
return this.absoluteEncoder;
}

@Override
public double getReferenceAngle() {
return referenceAngleRadians;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,13 @@

import com.revrobotics.REVLibError;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;

public final class RevUtils {
private RevUtils() {}

public static void checkNeoError(REVLibError error, String message) {
if (error != REVLibError.kOk) {
if (RobotBase.isReal() && error != REVLibError.kOk) {
DriverStation.reportError(String.format("%s: %s", message, error.toString()), false);
}
}
Expand Down