Skip to content
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 src/main/java/frc/robot/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,13 @@ public class Drivetrain {
private final Translation2d m_backLeftLocation = new Translation2d(-0.381, 0.381);
private final Translation2d m_backRightLocation = new Translation2d(-0.381, -0.381);

// Todo: these drive motor channel IDs need to be set
Copy link
Copy Markdown
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We need to address these todos before deploying the code.

Please remove after it is done.

private final SwerveModule m_frontLeft = new SwerveModule(1, 2);
private final SwerveModule m_frontRight = new SwerveModule(3, 4);
private final SwerveModule m_backLeft = new SwerveModule(5, 6);
private final SwerveModule m_backRight = new SwerveModule(7, 8);

// Todo: Gyro channel ID needs to be set
private final AnalogGyro m_gyro = new AnalogGyro(0);

private final SwerveDriveKinematics m_kinematics = new SwerveDriveKinematics(
Expand Down
17 changes: 9 additions & 8 deletions src/main/java/frc/robot/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,10 @@

package frc.robot;

import com.ctre.phoenix.motorcontrol.TalonFXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonFX;

import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
Expand All @@ -24,8 +25,8 @@ public class SwerveModule {
private static final double kModuleMaxAngularAcceleration
= 2 * Math.PI; // radians per second squared

private final SpeedController m_driveMotor;
private final SpeedController m_turningMotor;
private final TalonFX m_driveMotor;
private final TalonFX m_turningMotor;

private final Encoder m_driveEncoder = new Encoder(0, 1);
private final Encoder m_turningEncoder = new Encoder(2, 3);
Expand All @@ -43,8 +44,8 @@ public class SwerveModule {
* @param turningMotorChannel ID for the turning motor.
*/
public SwerveModule(int driveMotorChannel, int turningMotorChannel) {
m_driveMotor = new PWMVictorSPX(driveMotorChannel);
m_turningMotor = new PWMVictorSPX(turningMotorChannel);
m_driveMotor = new TalonFX(driveMotorChannel);
m_turningMotor = new TalonFX(turningMotorChannel);

// Set the distance per pulse for the drive encoder. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
Expand Down Expand Up @@ -86,7 +87,7 @@ public void setDesiredState(SwerveModuleState state) {
);

// Calculate the turning motor output from the turning PID controller.
m_driveMotor.set(driveOutput);
Copy link
Copy Markdown
Collaborator Author

@lilawren lilawren Nov 11, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

With the sample code using PWM VictorSPX motor controller (looks like this), this was previously expecting values of -1.0 < x < 1.0

Screenshot 2021-11-11 001840

For TalonFX we need to create the same behavior. How can we do this? We can do a hover over m_driveMotor.set or do a control + click to view the class definition they provide us.

Hover:
image

ctrl + click (same content different format)
image

This is how we can get information on how to use the libraries provided by wpi and external vendors.

m_turningMotor.set(turnOutput);
m_driveMotor.set(TalonFXControlMode.PercentOutput, driveOutput);
m_turningMotor.set(TalonFXControlMode.PercentOutput, turnOutput);
}
}
234 changes: 234 additions & 0 deletions vendordeps/Phoenix.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,234 @@
{
Copy link
Copy Markdown
Collaborator Author

@lilawren lilawren Nov 11, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We needed to add this external vendor library or the code will not compile. Basically looked on google for "phoenix talon fx java frc" There's a lot of subjects but the one we needed was this:

https://docs.ctre-phoenix.com/en/latest/ch05a_CppJava.html#frc-c-java-add-phoenix

So I followed the steps and visited https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix-latest.json and just copy pasted the content to Phoenix.json like we do for FalconRecharged2021 code.

We can do similar thought process for other libraries: look at documentation. There might even be FRC friendly docs like for there was for Phoenix.

"fileName": "Phoenix.json",
"name": "CTRE-Phoenix",
"version": "5.20.0-beta-1",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix-latest.json",
"javaDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.20.0"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.20.0"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.20.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"linuxathena"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.20.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simTalonSRX",
"version": "5.20.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simTalonFX",
"version": "5.20.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simVictorSPX",
"version": "5.20.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simPigeonIMU",
"version": "5.20.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simCANCoder",
"version": "5.20.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
}
],
"cppDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.20.0",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"linuxathena",
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.20.0",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"linuxathena",
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.20.0",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"linuxathena"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.20.0",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simTalonSRX",
"version": "5.20.0",
"libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simTalonFX",
"version": "5.20.0",
"libName": "CTRE_SimTalonFX",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simVictorSPX",
"version": "5.20.0",
"libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simPigeonIMU",
"version": "5.20.0",
"libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "simCANCoder",
"version": "5.20.0",
"libName": "CTRE_SimCANCoder",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxx86-64"
]
}
]
}