diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 1d62112..3a7282b 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -133,6 +133,15 @@ public final class Constants { public static final int SMARTDASHBOARD_UPDATE_FRAME = 2; } + public static final class IntakeConstants { + public static final int PIVOT_ID = 17; + public static final int INTAKE_ID = 18; + public static final double IN_POSITION = 0; + public static final double OUT_POSITION = 0; + public static final double INTAKE_SPEED = .75; + public static final double OUTTAKE_SPEED = 1.0; + } + public static final class ShooterConstants { public static final double SHOOTER_SPEED = .5; public static final int LEFT_SHOOTER_ID = 15; diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 0ac83b5..fa44509 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -11,6 +11,7 @@ import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.hardware.Pigeon2; +import frc4388.robot.Constants.IntakeConstants; import frc4388.robot.Constants.ShooterConstants; // import edu.wpi.first.wpilibj.motorcontrol.Spark; // import frc4388.robot.Constants.LEDConstants; @@ -32,6 +33,9 @@ public class RobotMap { public SwerveModule leftBack; public SwerveModule rightBack; + public TalonFX pivotMotor = new TalonFX(IntakeConstants.PIVOT_ID); + public TalonFX intakeMotor = new TalonFX(IntakeConstants.INTAKE_ID); + public RobotMap() { configureDriveMotorControllers(); }