Skip to content

Commit 7265fa4

Browse files
committed
changed magazine to chimney
1 parent 0140934 commit 7265fa4

File tree

8 files changed

+34
-18
lines changed

8 files changed

+34
-18
lines changed

src/main/java/org/mayheminc/robot2020/RobotContainer.java

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -56,10 +56,10 @@ public RobotContainer() {
5656
configureAutonomousPrograms();
5757
configureDefaultCommands();
5858

59-
pidtuner = new PidTuner(RobotContainer.DRIVER_STICK.DRIVER_STICK_BUTTON_SIX,
60-
RobotContainer.DRIVER_STICK.DRIVER_STICK_BUTTON_SEVEN,
61-
RobotContainer.DRIVER_STICK.DRIVER_STICK_BUTTON_ELEVEN,
62-
RobotContainer.DRIVER_STICK.DRIVER_STICK_BUTTON_TEN, shooter);
59+
pidtuner = new PidTuner(RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_SIX,
60+
RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_SEVEN,
61+
RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_ELEVEN,
62+
RobotContainer.DRIVER_STICK.DRIVER_STICK_ENA_BUTTON_TEN, shooter);
6363
}
6464

6565
public static void init() {
@@ -130,6 +130,7 @@ private void configureDriverPadButtons() {
130130
DRIVER_PAD.DRIVER_PAD_BLUE_BUTTON.whenPressed(new ShooterAdjustWheel(100.0));
131131
DRIVER_PAD.DRIVER_PAD_GREEN_BUTTON.whenPressed(new ShooterAdjustWheel(-100.0));
132132
DRIVER_PAD.DRIVER_PAD_RED_BUTTON.whenPressed(new ShooterSetWheel(0.0));
133+
DRIVER_PAD.DRIVER_PAD_YELLOW_BUTTON.whenPressed(new ShooterSetWheel(4600));
133134

134135
DRIVER_PAD.DRIVER_PAD_LEFT_UPPER_TRIGGER_BUTTON.whileHeld(new ShooterSetFeeder(0.5));
135136

src/main/java/org/mayheminc/robot2020/commands/ClimberSetWinchesPower.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ public void initialize() {
3131
// Called every time the scheduler runs while the command is scheduled.
3232
@Override
3333
public void execute() {
34-
RobotContainer.climber.setWinchLeftSpeed(power);
34+
RobotContainer.climber.setWinchLeftSpeed(-power);
3535
RobotContainer.climber.setWinchRightSpeed(power);
3636
}
3737

src/main/java/org/mayheminc/robot2020/commands/MagazineSetChimney.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ public class MagazineSetChimney extends CommandBase {
1919
*/
2020
public MagazineSetChimney(double d) {
2121
// Use addRequirements() here to declare subsystem dependencies.
22-
addRequirements(RobotContainer.magazine);
22+
addRequirements(RobotContainer.chimney);
2323
m_speed = d;
2424
}
2525

@@ -32,11 +32,12 @@ public void initialize() {
3232
// Called once the command ends or is interrupted.
3333
@Override
3434
public void end(boolean interrupted) {
35+
RobotContainer.chimney.setChimneySpeed(0.0);
3536
}
3637

3738
// Returns true when the command should end.
3839
@Override
3940
public boolean isFinished() {
40-
return true;
41+
return false;
4142
}
4243
}

src/main/java/org/mayheminc/robot2020/subsystems/Chimney.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,8 @@ public void periodic() {
3737
}
3838

3939
void updateSmartDashboard() {
40-
SmartDashboard.putNumber("Magazine Turntable", chimneyTalon.getSpeed());
40+
SmartDashboard.putNumber("Chimney Speed", chimneyTalon.getSpeed());
41+
SmartDashboard.putNumber("Chimney Current", chimneyTalon.getStatorCurrent());
4142
}
4243

4344
void monitorTurntableMovement() {

src/main/java/org/mayheminc/robot2020/subsystems/Climber.java

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -30,19 +30,20 @@ public class Climber extends SubsystemBase {
3030
* Creates a new Climber.
3131
*/
3232
public Climber() {
33-
winchLeft.setNeutralMode(NeutralMode.Coast);
33+
winchLeft.setNeutralMode(NeutralMode.Brake);
3434
winchLeft.configNominalOutputVoltage(+0.0f, -0.0f);
3535
winchLeft.configPeakOutputVoltage(+12.0, -12.0);
3636

3737
winchRight.setNeutralMode(NeutralMode.Coast);
38+
winchRight.setNeutralMode(NeutralMode.Brake);
3839
winchRight.configNominalOutputVoltage(+0.0f, -0.0f);
3940
winchRight.configPeakOutputVoltage(+12.0, -12.0);
4041

41-
walkerRight.setNeutralMode(NeutralMode.Coast);
42+
walkerRight.setNeutralMode(NeutralMode.Brake);
4243
walkerRight.configNominalOutputVoltage(+0.0f, -0.0f);
4344
walkerRight.configPeakOutputVoltage(+12.0, -12.0);
4445

45-
walkerLeft.setNeutralMode(NeutralMode.Coast);
46+
walkerLeft.setNeutralMode(NeutralMode.Brake);
4647
walkerLeft.configNominalOutputVoltage(+0.0f, -0.0f);
4748
walkerLeft.configPeakOutputVoltage(+12.0, -12.0);
4849

@@ -56,8 +57,8 @@ public void zero() {
5657
@Override
5758
public void periodic() {
5859
// This method will be called once per scheduler run
59-
// SmartDashboard.putNumber("Climber Winch Left", winchLeft.getPosition());
60-
// SmartDashboard.putNumber("Climber Winch Right", winchRight.getPosition());
60+
SmartDashboard.putNumber("Climber Winch Left", winchLeft.getPosition());
61+
SmartDashboard.putNumber("Climber Winch Right", winchRight.getPosition());
6162
// SmartDashboard.putNumber("Climber Walker Left", walkerLeft.getPosition());
6263
// SmartDashboard.putNumber("Climber Walker Right", walkerRight.getPosition());
6364
// SmartDashboard.putBoolean("Climber Pistons", pistons.get());

src/main/java/org/mayheminc/robot2020/subsystems/Magazine.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@ public void periodic() {
4242
}
4343

4444
void updateSmartDashboard() {
45-
SmartDashboard.putNumber("Magazine Turntable", turntableTalon.getSpeed());
45+
SmartDashboard.putNumber("Magazine Speed", turntableTalon.getSpeed());
46+
// SmartDashboard.putNumber("Magazine Speed", turntableTalon.getSpeed());
4647
}
4748

4849
void monitorTurntableMovement() {

src/main/java/org/mayheminc/robot2020/subsystems/Shooter.java

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,11 @@ public Shooter() {
4040
configureWheelTalon();
4141
configureHoodTalon();
4242
configureFeederTalon();
43+
44+
shooterWheelTalon.config_kP(0, 3.0, 0);
45+
shooterWheelTalon.config_kI(0, 0.0, 0);
46+
shooterWheelTalon.config_kD(0, 0.0, 0);
47+
shooterWheelTalon.config_kF(0, 0.048);// 1023.0 / convertRpmToTicksPer100ms(5760), 0);
4348
}
4449

4550
public void init() {
@@ -72,10 +77,6 @@ private void configureHoodTalon() {
7277
}
7378

7479
private void configureWheelTalon() {
75-
shooterWheelTalon.config_kP(0, 0.0, 0);
76-
shooterWheelTalon.config_kI(0, 0.0, 0);
77-
shooterWheelTalon.config_kD(0, 0.0, 0);
78-
shooterWheelTalon.config_kF(0, 1023.0 / convertRpmToTicksPer100ms(5760), 0);
7980

8081
shooterWheelTalon.setFeedbackDevice(FeedbackDevice.IntegratedSensor);
8182

@@ -163,6 +164,11 @@ public void setFeederSpeed(double pos) {
163164
feederTalon.set(ControlMode.PercentOutput, pos);
164165
}
165166

167+
/**
168+
* Set shooter to rpm speed.
169+
*
170+
* @param rpm
171+
*/
166172
public void setShooterWheelSpeed(double rpm) {
167173
double ticks = convertRpmToTicksPer100ms(rpm);
168174
m_targetSpeedRPM = rpm;

src/main/java/org/mayheminc/util/MayhemDriverStick.java

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,11 @@ public class MayhemDriverStick {
2121
public final Button DRIVER_STICK_BUTTON_TEN = new DisabledOnlyJoystickButton(Joystick, 10);
2222
public final Button DRIVER_STICK_BUTTON_ELEVEN = new DisabledOnlyJoystickButton(Joystick, 11);
2323

24+
public final Button DRIVER_STICK_ENA_BUTTON_SIX = new EnabledOnlyJoystickButton(Joystick, 6);
25+
public final Button DRIVER_STICK_ENA_BUTTON_SEVEN = new EnabledOnlyJoystickButton(Joystick, 7);
26+
public final Button DRIVER_STICK_ENA_BUTTON_TEN = new EnabledOnlyJoystickButton(Joystick, 10);
27+
public final Button DRIVER_STICK_ENA_BUTTON_ELEVEN = new EnabledOnlyJoystickButton(Joystick, 11);
28+
2429
public final int DRIVER_STICK_X_AXIS = 0;
2530
public final int DRIVER_STICK_Y_AXIS = 1;
2631

0 commit comments

Comments
 (0)