Revert "Revert "Merge branch 'Shooter' of https://github.com/Team4388/2022NoWayHome into Shooter""

This reverts commit 6d53d0431a.
This commit is contained in:
Pushkar9236
2022-01-28 19:06:28 -07:00
parent 6d53d0431a
commit 2d9cd7abe6
7 changed files with 151 additions and 13 deletions
+3 -3
View File
@@ -94,9 +94,9 @@ public final class Constants {
public static final SupplyCurrentLimitConfiguration SUPPLY_CURRENT_LIMIT_CONFIG = new SupplyCurrentLimitConfiguration(true, 60, 40, 0.5);
public static final int SHOOTER_FALCON_LEFT_CAN_ID = 0;
public static final int SHOOTER_FALCON_RIGHT_CAN_ID = 0;
public static final int SHOOTER_ROTATE_ID = 0; //"unknown value" //figure out later
public static final int SHOOTER_ROTATE_ID = 31; //"unknown value" //figure out later
public static final int TURRET_RIGHT_SOFT_LIMIT = 0; //""//
public static final int TURRET_SPEED_MULTIPLIER = 0; //""//
public static final double TURRET_SPEED_MULTIPLIER = 0.1d; //""//
public static final int DEGREES_PER_ROT = 0; //""//
public static final int TURRET_MOTOR_POS_AT_ZERO_ROT = 0; //""//
public static final int TURRET_MOTOR_ROTS_PER_ROT = 0; //""//
@@ -105,7 +105,7 @@ public final class Constants {
/* Turret Constants */
//ID
public static final int TURRET_MOTOR_CAN_ID = 0;
public static final int TURRET_MOTOR_CAN_ID = 30;
public static final Gains SHOOTER_TURRET_GAINS = new Gains(0.6, 0.0, 0.0, 0.0, 0, 1.0);
public static final Gains SHOOTER_ANGLE_GAINS = new Gains(0.05, 0.0, 0.0, 0.0, 0, 0.3);
public static final double SHOOTER_TURRET_MIN = -1.0;
@@ -73,11 +73,11 @@ public class RobotContainer {
m_robotTurret.setDefaultCommand(
new RunCommand(() -> m_robotTurret.runShooterWithInput(getOperatorController().getLeftXAxis()), m_robotTurret)
);
);
// m_robotTurret.setDefaultCommand(
// new RunCommand(() -> m_robotTurret.aimToCenter()));
}
m_robotTurret.setDefaultCommand(
new RunCommand(() -> m_robotTurret.aimToCenter()));
/**
* Use this method to define your button->command mappings. Buttons can be
* created by instantiating a {@link GenericHID} or one of its subclasses
+3 -1
View File
@@ -6,6 +6,8 @@ package frc4388.robot;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import com.ctre.phoenix.sensors.CANCoder;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import frc4388.robot.Constants.LEDConstants;
@@ -97,7 +99,7 @@ public class RobotMap {
/*Boom Boom Subsystem*/
public final WPI_TalonFX shooterFalconLeft = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_LEFT_CAN_ID);
public final WPI_TalonFX shooterFalconRight = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_RIGHT_CAN_ID);
public final CANSparkMax shooterTurret = new CANSparkMax(ShooterConstants.SHOOTER_TURRET_CAN_ID);
public final CANSparkMax shooterTurret = new CANSparkMax(ShooterConstants.TURRET_MOTOR_CAN_ID, MotorType.kBrushless);
//Create motor CANSparkMax
void ConfigureShooterMotorControllers() {
@@ -4,6 +4,7 @@
package frc4388.robot.subsystems;
import java.io.Console;
import java.util.Base64.Encoder;
import com.ctre.phoenix.motorcontrol.NeutralMode;
@@ -27,6 +28,7 @@ public ShooterTables m_shooterTable;
public static Gains m_drumShooterGains = ShooterConstants.DRUM_SHOOTER_GAINS;
public static BoomBoom m_boomBoom;
public static IHandController m_driverController; //not sure if driverController in 2022 = m_controller in 2020
BangBangController m_controller = new BangBangController();
double velP;
double input;
@@ -135,7 +137,6 @@ public void setShooterGains() {
m_shooterFalconLeft.set(TalonFXControlMode.Velocity, targetVel); //Init
m_shooterFalconRight.follow(m_shooterFalconLeft);
// New BoomBoom controller stuff
BangBangController controller = new BangBangController();
//Controls a motor with the output of the BangBang controller
//Controls a motor with the output of the BangBang conroller and a feedforward
//Shrinks the feedforward slightly to avoid over speeding the shooter
@@ -143,4 +144,4 @@ public void setShooterGains() {
}
}
}
@@ -67,11 +67,11 @@ public class Turret extends SubsystemBase {
@Override
public void periodic() {
SmartDashboard.putNumber("Turret Angle Raw", getboomBoomRotatePosition());
// SmartDashboard.putNumber("Turret Angle Raw", getboomBoomRotatePosition());
SmartDashboard.putData("Turret Angle", (Sendable) m_turretGyro);
// SmartDashboard.putData("Turret Angle", (Sendable) m_turretGyro);
SmartDashboard.putBoolean("Turret Aimed", m_isAimReady);
// SmartDashboard.putBoolean("Turret Aimed", m_isAimReady);
// This method will be called once per scheduler run
}