package frc.robot.constants;
+import com.ctre.phoenix6.CANBus;
+
import edu.wpi.first.wpilibj.RobotBase;
public class Constants {
public static final double LOOP_TIME = 0.02;
// CAN bus names
- public static final String CANIVORE_CAN = "CANivore";
- public static final String RIO_CAN = "rio";
+ public static final CANBus CANIVORE_CAN = new CANBus("CANivore");
+ public static final CANBus RIO_CAN = new CANBus("rio");
// Logging
public static final boolean USE_TELEMETRY = true;
package frc.robot.constants.swerve;
+import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
public static final double PATH_PLANNER_TRANSLATIONAL_D = 0;
// CAN
- public static String DRIVE_MOTOR_CAN = Constants.CANIVORE_CAN;
- public static String STEER_MOTOR_CAN = Constants.CANIVORE_CAN;
- public static String STEER_ENCODER_CAN = Constants.CANIVORE_CAN;
- public static String PIGEON_CAN = Constants.CANIVORE_CAN;
+ public static CANBus DRIVE_MOTOR_CAN = Constants.CANIVORE_CAN;
+ public static CANBus STEER_MOTOR_CAN = Constants.CANIVORE_CAN;
+ public static CANBus STEER_ENCODER_CAN = Constants.CANIVORE_CAN;
+ public static CANBus PIGEON_CAN = Constants.CANIVORE_CAN;
public static COTSFalconSwerveConstants MODULE_CONSTANTS = COTSFalconSwerveConstants.SDSMK4i(DRIVE_GEAR_RATIO);
package frc.robot.subsystems.LED;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import frc.robot.constants.Constants;
import frc.robot.constants.IdConstants;
import com.ctre.phoenix.led.CANdle;
// Constructor
public LED() {
- this.candle = new CANdle(IdConstants.CANDLE_ID, "rio");
+ this.candle = new CANdle(IdConstants.CANDLE_ID);
candle.configStatusLedState(false);
candle.configLOSBehavior(false);