Skip to content

Commit 38501eb

Browse files
committed
Merge branch 'canivore'
2 parents e613b5c + 61e47b5 commit 38501eb

File tree

7 files changed

+17
-6
lines changed

7 files changed

+17
-6
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,8 @@
3131
public final class Constants {
3232

3333
public static final double stickDeadband = 0.1;
34+
35+
public static final String canBus_name = "canBus";
3436

3537
public static final class IntakeArmConstants { // TODO: This must be tuned to specific robot
3638
// mm

src/main/java/frc/robot/Robot.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,10 @@
44

55
package frc.robot;
66

7+
import com.ctre.phoenix6.CANBus;
8+
79
import edu.wpi.first.wpilibj.TimedRobot;
10+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
811
import edu.wpi.first.wpilibj2.command.Command;
912
import edu.wpi.first.wpilibj2.command.CommandScheduler;
1013
import frc.Utils.shuffleboardAlike.AutoContainer;
@@ -54,6 +57,7 @@ public void robotPeriodic() {
5457
// and running subsystem periodic() methods. This must be called from the robot's periodic
5558
// block in order for anything in the Command-based framework to work.
5659
CommandScheduler.getInstance().run();
60+
SmartDashboard.putNumber("canivor utilization", CANBus.getStatus(Constants.canBus_name).BusUtilization);
5761
}
5862

5963
/** This function is called once each time the robot enters Disabled mode. */

src/main/java/frc/robot/subsystems/IntakeArmSubsystem.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212

1313
import edu.wpi.first.wpilibj.DigitalInput;
1414
import edu.wpi.first.wpilibj2.command.SubsystemBase;
15+
import frc.robot.Constants;
16+
1517
import static frc.robot.Constants.IntakeArmConstants.*;
1618

1719
import java.util.function.DoubleSupplier;
@@ -33,7 +35,7 @@ public static IntakeArmSubsystem getInstance() {
3335

3436
/** Creates a new IntakeArmSubsystem. */
3537
private IntakeArmSubsystem() {
36-
this.m_IntakeArmMotor = new TalonFX(IntakeArmMotorID);
38+
this.m_IntakeArmMotor = new TalonFX(IntakeArmMotorID, Constants.canBus_name);
3739
TalonFXConfiguration configs = new TalonFXConfiguration();
3840
MotionMagicConfigs mm = new MotionMagicConfigs();
3941

src/main/java/frc/robot/subsystems/ShooterArmSubsystem.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
import edu.wpi.first.wpilibj.DigitalInput;
1313
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1414
import frc.Utils.interpolation.InterpolateUtil;
15+
import frc.robot.Constants;
1516

1617
import static frc.robot.Constants.ShooterArmConstants.*;
1718

@@ -36,7 +37,7 @@ public static ShooterArmSubsystem getInstance() {
3637
}
3738

3839
private ShooterArmSubsystem() {
39-
this.m_shooterArmMotor = new TalonFX(ShooterArmID);
40+
this.m_shooterArmMotor = new TalonFX(ShooterArmID, Constants.canBus_name);
4041
this.limitSwitch = new DigitalInput(SwitchID);
4142

4243
// create the full MotionMagic

src/main/java/frc/robot/subsystems/ShooterSubsysem.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1616
import frc.Utils.interpolation.InterpolateUtil;
1717
import frc.Utils.vision.Vision;
18+
import frc.robot.Constants;
1819

1920
public class ShooterSubsysem extends SubsystemBase {
2021
private TalonFX m_shooterMotor;
@@ -34,7 +35,7 @@ public static ShooterSubsysem getInstance() {
3435
/** Creates a new ShooterSubsysem. */
3536
private ShooterSubsysem() {
3637
// giving values to the motors
37-
this.m_shooterMotor = new TalonFX(kMotorShooterID);
38+
this.m_shooterMotor = new TalonFX(kMotorShooterID, Constants.canBus_name);
3839

3940
// declaring Configs
4041
TalonFXConfiguration configs = new TalonFXConfiguration();

src/main/java/frc/Utils/swerve/SwerveModule.java renamed to src/main/java/frc/robot/subsystems/SwerveModule.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package frc.Utils.swerve;
1+
package frc.robot.subsystems;
22

33
import static edu.wpi.first.units.Units.Volts;
44

@@ -21,6 +21,8 @@
2121
import frc.Utils.motors.CANSparkMaxUtil;
2222
import frc.Utils.motors.FalconConversions;
2323
import frc.Utils.motors.CANSparkMaxUtil.Usage;
24+
import frc.Utils.swerve.CTREModuleState;
25+
import frc.Utils.swerve.SwerveModuleConstants;
2426
import frc.robot.Constants;
2527
import frc.robot.Robot;
2628

@@ -60,7 +62,7 @@ public SwerveModule(int moduleNumber, SwerveModuleConstants moduleConstants){
6062
configAngleMotor();
6163

6264
/* Drive Motor Config */
63-
mDriveMotor = new TalonFX(moduleConstants.driveMotorID);
65+
mDriveMotor = new TalonFX(moduleConstants.driveMotorID, Constants.canBus_name);
6466
configDriveMotor();
6567

6668
lastAngle = getState().angle;

src/main/java/frc/robot/subsystems/SwerveSubsystem.java

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
package frc.robot.subsystems;
22

3-
import frc.Utils.swerve.SwerveModule;
43
import frc.Utils.vision.Vision;
54
import frc.robot.Constants.Swerve.Mod0;
65
import frc.robot.Constants.Swerve.Mod1;

0 commit comments

Comments
 (0)