Skip to content

Commit

Permalink
TopDownShooter
Browse files Browse the repository at this point in the history
  • Loading branch information
NotNotTy committed Sep 24, 2024
1 parent 9ff0afd commit bc97308
Show file tree
Hide file tree
Showing 3 changed files with 52 additions and 53 deletions.
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,9 @@ public static class VisionConstants{

// Intake constants
public static class IntakeConstants{
public static final String pivotUpKey = "Pivot Speed";
public static final String rollerInKey = "Roller Speed";

public static final int pivotID = 9;
public static final int rollerID = 10;
public static final double intakeUpSpeed = 0.3;
Expand Down
18 changes: 15 additions & 3 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,9 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.CAN;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.ctre.phoenix.motorcontrol.TalonSRXControlMode;
Expand All @@ -20,13 +22,17 @@
public class Intake extends SubsystemBase {
private static final double DEADZONE = 0.05;
private CANSparkMax m_IntakePivotMotor;
private TalonSRX m_IntakeRollerMotor;
private CANSparkMax m_IntakeRollerMotor;

private double realPivotSpeed = Constants.IntakeConstants.intakeUpSpeed;
private double realRollerSpeed = Constants.IntakeConstants.rollerSpeedIntake;

private AnalogInput IRSensor = new AnalogInput(Constants.IntakeConstants.IRport);
static Intake instance = null;
/** Creates a new Intake. */
public Intake() {
m_IntakePivotMotor = new CANSparkMax(Constants.IntakeConstants.pivotID, MotorType.kBrushless);
m_IntakeRollerMotor = new TalonSRX(Constants.IntakeConstants.rollerID);
m_IntakeRollerMotor = new CANSparkMax(Constants.IntakeConstants.rollerID, MotorType.kBrushless);
m_IntakePivotMotor.setIdleMode(IdleMode.kBrake);
}

Expand Down Expand Up @@ -59,7 +65,7 @@ public void rotateIntake(double rotate){
// move intake rollers
public void moveRollers(double rotate){
if(Math.abs(rotate) < DEADZONE) rotate = 0;
m_IntakeRollerMotor.set(TalonSRXControlMode.PercentOutput, rotate);
m_IntakeRollerMotor.set(rotate);
}

public double getIRSensor(){
Expand All @@ -72,5 +78,11 @@ public void periodic() {
// SmartDashboard.putBoolean("limit reverse", getIntakeLimitStateReverse());
// SmartDashboard.putNumber("IR Sensor", getIRSensor());
// This method will be called once per scheduler run

SmartDashboard.putNumber(Constants.IntakeConstants.pivotUpKey, m_IntakePivotMotor.getOutputCurrent());
SmartDashboard.putNumber(Constants.IntakeConstants.rollerInKey, m_IntakeRollerMotor.getOutputCurrent());

Constants.ShooterConstants.shooterLeftSpeedSpeaker = Preferences.getDouble(Constants.IntakeConstants.pivotUpKey, realPivotSpeed);
Constants.ShooterConstants.shooterRightSpeedSpeaker = Preferences.getDouble(Constants.IntakeConstants.rollerInKey, realRollerSpeed);
}
}
84 changes: 34 additions & 50 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
@@ -1,85 +1,69 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.subsystems;

import com.ctre.phoenix.motorcontrol.TalonSRXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

public class Shooter extends SubsystemBase {
private static final double DEADZONE = 0.05;
private TalonSRX m_ShooterMotorLeft;
private TalonSRX m_ShooterMotorRight;
private CANSparkMax m_ShooterMotorLeft;
private CANSparkMax m_ShooterMotorRight;

private double realLeftSpeed = Constants.ShooterConstants.shooterLeftSpeedSpeaker;
private double realRightSpeed = Constants.ShooterConstants.shooterRightSpeedSpeaker;
private double realLeftSpeed = Constants.ShooterConstants.shooterLeftSpeedSpeaker;
private double realRightSpeed = Constants.ShooterConstants.shooterRightSpeedSpeaker;
static Shooter instance = null;
/** Creates a new Shooter. */

/** Creates a new Shooter. */
public Shooter() {
m_ShooterMotorLeft = new TalonSRX(Constants.ShooterConstants.shooterLeftID);
m_ShooterMotorRight = new TalonSRX(Constants.ShooterConstants.shooterRightID);
// Preferences.initDouble(Constants.ShooterConstants.leftSpeedKey, realLeftSpeed);
m_ShooterMotorLeft = new CANSparkMax(Constants.ShooterConstants.shooterLeftID, MotorType.kBrushless);
m_ShooterMotorRight = new CANSparkMax(Constants.ShooterConstants.shooterRightID, MotorType.kBrushless);
Preferences.initDouble(Constants.ShooterConstants.rightSpeedKey, realRightSpeed);
}

// Retrieve instance of shooter
// Retrieve instance of shooter
public static Shooter getInstance(){
if(instance == null) instance = new Shooter();
return instance;
if(instance == null) instance = new Shooter();
return instance;
}

// move shooter motors
// Move shooter motors
public void shoot(double rotateLeft, double rotateRight){
if(Math.abs(rotateLeft) < DEADZONE) rotateLeft = 0;
if(Math.abs(rotateRight) < DEADZONE) rotateRight = 0;
moveLeftMotor(rotateLeft);
moveRightMotor(rotateRight);
if(Math.abs(rotateLeft) < DEADZONE) rotateLeft = 0;
if(Math.abs(rotateRight) < DEADZONE) rotateRight = 0;
moveLeftMotor(rotateLeft);
moveRightMotor(rotateRight);
}

// move left motor
// Move left motor
public void moveLeftMotor(double rotateLeft){
if(Math.abs(rotateLeft) < DEADZONE) rotateLeft = 0;
m_ShooterMotorLeft.set(TalonSRXControlMode.PercentOutput, rotateLeft);
if(Math.abs(rotateLeft) < DEADZONE) rotateLeft = 0;
m_ShooterMotorLeft.set(rotateLeft);
}

// move right motor
// Move right motor
public void moveRightMotor(double rotateRight){
if(Math.abs(rotateRight) < DEADZONE) rotateRight = 0;
m_ShooterMotorRight.set(TalonSRXControlMode.PercentOutput, rotateRight);
if(Math.abs(rotateRight) < DEADZONE) rotateRight = 0;
m_ShooterMotorRight.set(rotateRight);
}

public double getCurrent() {
return (m_ShooterMotorLeft.getSupplyCurrent() + m_ShooterMotorRight.getSupplyCurrent()) / 2;
return (m_ShooterMotorLeft.getOutputCurrent() + m_ShooterMotorRight.getOutputCurrent()) / 2;
}

@Override
@Override
public void periodic() {
SmartDashboard.putNumber("current left", m_ShooterMotorLeft.getSupplyCurrent());
SmartDashboard.putNumber("current right", m_ShooterMotorRight.getSupplyCurrent());


Constants.ShooterConstants.shooterLeftSpeedSpeaker = Preferences.getDouble(Constants.ShooterConstants.leftSpeedKey, realLeftSpeed);
Constants.ShooterConstants.shooterRightSpeedSpeaker = Preferences.getDouble(Constants.ShooterConstants.rightSpeedKey, realRightSpeed);



// SmartDashboard.putNumber("Speed Left Speaker", Constants.ShooterConstants.shooterLeftSpeedSpeaker);
// SmartDashboard.putNumber("Speed Right Speaker", Constants.ShooterConstants.shooterRightSpeedSpeaker);
// SmartDashboard.putNumber("Speed Left Amp", Constants.ShooterConstants.shooterLeftSpeedAmp);
// SmartDashboard.putNumber("Speed Right Amp", Constants.ShooterConstants.shooterRightSpeedAmp);
// SmartDashboard.putNumber("Outtake speed", Constants.IntakeConstants.rollerSpeedOuttake);
SmartDashboard.putNumber("current left", m_ShooterMotorLeft.getOutputCurrent());
SmartDashboard.putNumber("current right", m_ShooterMotorRight.getOutputCurrent());

// Constants.ShooterConstants.shooterLeftSpeedSpeaker = SmartDashboard.getNumber("Speed Left Speaker", Constants.ShooterConstants.shooterLeftSpeedSpeaker);
// Constants.ShooterConstants.shooterRightSpeedSpeaker = SmartDashboard.getNumber("Speed Right Speaker", Constants.ShooterConstants.shooterRightSpeedSpeaker);
// Constants.ShooterConstants.shooterLeftSpeedAmp = SmartDashboard.getNumber("Speed Left Amp", Constants.ShooterConstants.shooterLeftSpeedAmp);
// Constants.ShooterConstants.shooterRightSpeedAmp = SmartDashboard.getNumber("Speed Right Amp", Constants.ShooterConstants.shooterRightSpeedAmp);
// Constants.IntakeConstants.rollerSpeedOuttake = SmartDashboard.getNumber("Outtake speed", Constants.IntakeConstants.rollerSpeedOuttake);
// This method will be called once per scheduler run
Constants.ShooterConstants.shooterLeftSpeedSpeaker = Preferences.getDouble(Constants.ShooterConstants.leftSpeedKey, realLeftSpeed);
Constants.ShooterConstants.shooterRightSpeedSpeaker = Preferences.getDouble(Constants.ShooterConstants.rightSpeedKey, realRightSpeed);
}
}

0 comments on commit bc97308

Please sign in to comment.