Skip to content

Commit

Permalink
make swerve work with talonFX
Browse files Browse the repository at this point in the history
  • Loading branch information
mwitcpalek committed Jan 25, 2020
1 parent 76e2268 commit 7c4d49b
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 5 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ plugins {
}

group = 'org.strykeforce'
version = '20.1.1'
version = '20.2.0'

sourceCompatibility = JavaVersion.VERSION_11
targetCompatibility = JavaVersion.VERSION_11
Expand Down
7 changes: 4 additions & 3 deletions src/main/java/org/strykeforce/thirdcoast/swerve/Wheel.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import static org.strykeforce.thirdcoast.swerve.SwerveDrive.DriveMode.TELEOP;

import com.ctre.phoenix.ErrorCode;
import com.ctre.phoenix.motorcontrol.can.BaseTalon;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import java.util.Objects;
import java.util.function.DoubleConsumer;
Expand Down Expand Up @@ -32,7 +33,7 @@ public class Wheel {

private static final Logger logger = LoggerFactory.getLogger(Wheel.class);
private final double driveSetpointMax;
private final TalonSRX driveTalon;
private final BaseTalon driveTalon;
private final TalonSRX azimuthTalon;
protected DoubleConsumer driver;
private boolean isInverted = false;
Expand All @@ -49,7 +50,7 @@ public class Wheel {
* @param drive the configured drive TalonSRX
* @param driveSetpointMax scales closed-loop drive output to this value when drive setpoint = 1.0
*/
public Wheel(TalonSRX azimuth, TalonSRX drive, double driveSetpointMax) {
public Wheel(TalonSRX azimuth, BaseTalon drive, double driveSetpointMax) {
this.driveSetpointMax = driveSetpointMax;
azimuthTalon = Objects.requireNonNull(azimuth);
driveTalon = Objects.requireNonNull(drive);
Expand Down Expand Up @@ -184,7 +185,7 @@ public TalonSRX getAzimuthTalon() {
*
* @return drive Talon instance used by wheel
*/
public TalonSRX getDriveTalon() {
public BaseTalon getDriveTalon() {
return driveTalon;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,9 @@ class TelemetryService(private val telemetryControllerFactory: Function<Inventor
*/
fun register(swerveDrive: SwerveDrive) = swerveDrive.wheels.forEach {
register(TalonSRXItem(it.azimuthTalon))
register(TalonSRXItem(it.driveTalon))
if(it.driveTalon is TalonSRX) register(TalonSRXItem(it.driveTalon as TalonSRX))
else if(it.driveTalon is TalonFX) register(TalonFXItem(it.driveTalon as TalonFX))
else throw IllegalArgumentException()
}

/**
Expand Down

0 comments on commit 7c4d49b

Please sign in to comment.