Skip to content

Commit

Permalink
Merge branch 'canivore'
Browse files Browse the repository at this point in the history
  • Loading branch information
ori-coval committed Feb 1, 2024
2 parents e613b5c + 61e47b5 commit 38501eb
Show file tree
Hide file tree
Showing 7 changed files with 17 additions and 6 deletions.
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
public final class Constants {

public static final double stickDeadband = 0.1;

public static final String canBus_name = "canBus";

public static final class IntakeArmConstants { // TODO: This must be tuned to specific robot
// mm
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@

package frc.robot;

import com.ctre.phoenix6.CANBus;

import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.Utils.shuffleboardAlike.AutoContainer;
Expand Down Expand Up @@ -54,6 +57,7 @@ public void robotPeriodic() {
// and running subsystem periodic() methods. This must be called from the robot's periodic
// block in order for anything in the Command-based framework to work.
CommandScheduler.getInstance().run();
SmartDashboard.putNumber("canivor utilization", CANBus.getStatus(Constants.canBus_name).BusUtilization);
}

/** This function is called once each time the robot enters Disabled mode. */
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/subsystems/IntakeArmSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

import static frc.robot.Constants.IntakeArmConstants.*;

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

/** Creates a new IntakeArmSubsystem. */
private IntakeArmSubsystem() {
this.m_IntakeArmMotor = new TalonFX(IntakeArmMotorID);
this.m_IntakeArmMotor = new TalonFX(IntakeArmMotorID, Constants.canBus_name);
TalonFXConfiguration configs = new TalonFXConfiguration();
MotionMagicConfigs mm = new MotionMagicConfigs();

Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/ShooterArmSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.Utils.interpolation.InterpolateUtil;
import frc.robot.Constants;

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

Expand All @@ -36,7 +37,7 @@ public static ShooterArmSubsystem getInstance() {
}

private ShooterArmSubsystem() {
this.m_shooterArmMotor = new TalonFX(ShooterArmID);
this.m_shooterArmMotor = new TalonFX(ShooterArmID, Constants.canBus_name);
this.limitSwitch = new DigitalInput(SwitchID);

// create the full MotionMagic
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/ShooterSubsysem.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.Utils.interpolation.InterpolateUtil;
import frc.Utils.vision.Vision;
import frc.robot.Constants;

public class ShooterSubsysem extends SubsystemBase {
private TalonFX m_shooterMotor;
Expand All @@ -34,7 +35,7 @@ public static ShooterSubsysem getInstance() {
/** Creates a new ShooterSubsysem. */
private ShooterSubsysem() {
// giving values to the motors
this.m_shooterMotor = new TalonFX(kMotorShooterID);
this.m_shooterMotor = new TalonFX(kMotorShooterID, Constants.canBus_name);

// declaring Configs
TalonFXConfiguration configs = new TalonFXConfiguration();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.Utils.swerve;
package frc.robot.subsystems;

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

Expand All @@ -21,6 +21,8 @@
import frc.Utils.motors.CANSparkMaxUtil;
import frc.Utils.motors.FalconConversions;
import frc.Utils.motors.CANSparkMaxUtil.Usage;
import frc.Utils.swerve.CTREModuleState;
import frc.Utils.swerve.SwerveModuleConstants;
import frc.robot.Constants;
import frc.robot.Robot;

Expand Down Expand Up @@ -60,7 +62,7 @@ public SwerveModule(int moduleNumber, SwerveModuleConstants moduleConstants){
configAngleMotor();

/* Drive Motor Config */
mDriveMotor = new TalonFX(moduleConstants.driveMotorID);
mDriveMotor = new TalonFX(moduleConstants.driveMotorID, Constants.canBus_name);
configDriveMotor();

lastAngle = getState().angle;
Expand Down
1 change: 0 additions & 1 deletion src/main/java/frc/robot/subsystems/SwerveSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.robot.subsystems;

import frc.Utils.swerve.SwerveModule;
import frc.Utils.vision.Vision;
import frc.robot.Constants.Swerve.Mod0;
import frc.robot.Constants.Swerve.Mod1;
Expand Down

0 comments on commit 38501eb

Please sign in to comment.