Skip to content

Commit 30e53c1

Browse files
committed
working version 1.3
1 parent 865256c commit 30e53c1

File tree

5 files changed

+42
-32
lines changed

5 files changed

+42
-32
lines changed

src/main/java/frc/team5115/Commands/StopClimb.java renamed to src/main/java/frc/team5115/Commands/Climber/StopClimb.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package frc.team5115.Commands;
1+
package frc.team5115.Commands.Climber;
22

33
import edu.wpi.first.wpilibj2.command.CommandBase;
44
import frc.team5115.Subsystems.Climber;

src/main/java/frc/team5115/Constants.java

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,14 +36,16 @@ public class Constants{
3636

3737

3838
public static final byte INTAKE_BUTTON_ID = 1;
39-
public static final byte WINCH_DOWN_BUTTON_ID = 2;
40-
public static final byte SCISSORS_DOWN_BUTTON_ID = 3;
39+
public static final byte INTAKE_EXCRETE_BUTTON_ID = 2;
40+
public static final byte CLIMBER_DOWN_BUTTON_ID = 3;
4141
public static final byte CLIMBER_UP_BUTTON_ID = 4;
4242
public static final byte AUTO_TURN_AND_MOVE_BUTTON_ID = 5;
4343
public static final byte SHOOTER_BUTTON_ID = 6;
44-
public static final byte AUTO_BALL_TARCKING = 7;
44+
public static final byte AUTO_BALL_TRACKING = 7;
45+
public static final byte GRANNY_MODE_BUTTON_ID = 7;
4546
public static final byte AUTO_TURN_BUTTON_ID = 8;
46-
public static final byte WINCH_RELEASE_BUTTON_ID = 9;
47+
public static final byte WINCH_DOWN_BUTTON_ID = 9;
48+
public static final int WINCH_FORWARD_BUTTON_ID = 10;
4749

4850

4951
//Speed constants for subsystems.

src/main/java/frc/team5115/Robot/RobotContainer.java

Lines changed: 24 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -41,25 +41,29 @@ public RobotContainer() {
4141
private void configureButtonBindings() {
4242

4343
new JoystickButton(joy, AUTO_TURN_AND_MOVE_BUTTON_ID).whenHeld(new ShootHighGoal(drivetrain, locationator, shooter, limelight));
44+
4445
new JoystickButton(joy, AUTO_TURN_BUTTON_ID).whenHeld(new AssistedShootHighGoal(drivetrain, shooter, limelight, joy));
45-
new JoystickButton(joy, AUTO_BALL_TARCKING).whenHeld(new PickupBallAuto(drivetrain, locationator, limelight, feeder));
46-
new JoystickButton(joy, SHOOTER_BUTTON_ID).whenHeld(new InstantCommand(shooter::shoot)).whenReleased(new InstantCommand(shooter::stopShoot));
47-
new JoystickButton(joy, CLIMBER_UP_BUTTON_ID).whenHeld(new InstantCommand(climber::ScissorUp)).whenReleased(new InstantCommand(climber::StopClimb));
48-
// new JoystickButton(joy, CLIMBER_DOWN_BUTTON_ID).whenHeld(
49-
// new InstantCommand(climber::ScissorDown)
50-
// .alongWith(new InstantCommand(climber::WinchDown)))
51-
// .whenReleased(new InstantCommand(climber::StopClimb));
52-
new JoystickButton(joy, SCISSORS_DOWN_BUTTON_ID).whenHeld(new InstantCommand(climber::ScissorDown));
53-
new JoystickButton(joy, WINCH_DOWN_BUTTON_ID).whenHeld(new InstantCommand(climber::WinchDown));
54-
new JoystickButton(joy, WINCH_RELEASE_BUTTON_ID).whenHeld(new InstantCommand(climber::WinchRelease));
55-
56-
new JoystickButton(joy, INTAKE_BUTTON_ID)
57-
.whenHeld(
58-
new InstantCommand(intake::driverIntake)
59-
.alongWith(new InstantCommand(feeder::moveCells)))
60-
.whenReleased(
61-
new InstantCommand(intake::stopIntake)
62-
.alongWith(new InstantCommand(feeder::stopCells)));
46+
47+
//new JoystickButton(joy, AUTO_BALL_TRACKING).whenHeld(new PickupBallAuto(drivetrain, locationator, limelight, feeder));
48+
49+
//new JoystickButton(joy, GRANNY_MODE_BUTTON_ID).whenPressed(new InstantCommand(drivetrain::toggleSpeed));
50+
51+
new JoystickButton(joy, SHOOTER_BUTTON_ID).whenHeld(new InstantCommand(shooter::shoot));
52+
//.whenReleased(new InstantCommand(shooter::stopShoot));
53+
54+
new JoystickButton(joy, CLIMBER_UP_BUTTON_ID).whenHeld(new InstantCommand(climber::ScissorUp));
55+
//.whenReleased(new InstantCommand(climber::StopClimb));
56+
57+
new JoystickButton(joy, CLIMBER_DOWN_BUTTON_ID).whenHeld(new InstantCommand(climber::ScissorDown).alongWith(new InstantCommand(climber::WinchDown)));
58+
59+
new JoystickButton(joy, INTAKE_EXCRETE_BUTTON_ID).whenHeld(new InstantCommand(intake::spitout));
60+
61+
new JoystickButton(joy, INTAKE_BUTTON_ID).whenHeld(new InstantCommand(intake::driverIntake).alongWith(new InstantCommand(feeder::moveCells)));
62+
//.whenReleased(new InstantCommand(intake::stopIntake).alongWith(new InstantCommand(feeder::stopCells)));
63+
64+
new JoystickButton(joy, WINCH_DOWN_BUTTON_ID).whenHeld(new InstantCommand(climber::WinchDown)).whenReleased(new InstantCommand(climber::StopClimb));
65+
66+
new JoystickButton(joy, WINCH_FORWARD_BUTTON_ID).whenHeld(new InstantCommand(climber::WinchForward)).whenReleased(new InstantCommand(climber::StopClimb));
6367

6468
drivetrain.setDefaultCommand(new driveDefaultCommand(drivetrain, joy).perpetually());
6569
}
@@ -77,8 +81,8 @@ public driveDefaultCommand(Drivetrain drivetrain, Joystick joystick) {
7781

7882
@Override
7983
public void execute() {
80-
drivetrain.drive(joystick.getRawAxis(XBOX_X_AXIS_ID), joystick.getRawAxis(XBOX_Y_AXIS_ID), 1);
81-
//drivetrain.drive(-.5, -.5, 1);
84+
drivetrain.drive(joystick.getRawAxis(XBOX_X_AXIS_ID), joystick.getRawAxis(XBOX_Y_AXIS_ID), .7);
85+
//drivetrain.XBoxDrive(joystick);
8286
}
8387
}
8488

src/main/java/frc/team5115/Subsystems/Climber.java

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -2,24 +2,21 @@
22

33
import com.ctre.phoenix.motorcontrol.ControlMode;
44
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
5-
import edu.wpi.first.wpilibj.DigitalInput;
65
import edu.wpi.first.wpilibj2.command.SubsystemBase;
7-
import frc.team5115.Commands.StopClimb;
6+
import frc.team5115.Commands.Climber.StopClimb;
87

98
import static frc.team5115.Constants.SCISSOR_MOTOR_ID;
109
import static frc.team5115.Constants.WINCH_MOTOR_ID;
1110

1211
public class Climber extends SubsystemBase {
1312
TalonSRX winch;
1413
TalonSRX scissor;
15-
double climbspeed = -0.75;
16-
DigitalInput bottomClimberLimitSwitch;
14+
double climbspeed = -1;
1715

1816
public Climber(){
1917
winch = new TalonSRX(WINCH_MOTOR_ID);
2018
scissor = new TalonSRX(SCISSOR_MOTOR_ID);
2119
setDefaultCommand(new StopClimb(this).perpetually());
22-
bottomClimberLimitSwitch =new DigitalInput(1);
2320
}
2421

2522
public void ScissorUp(){
@@ -34,11 +31,13 @@ public void WinchDown(){
3431
winch.set(ControlMode.PercentOutput, -climbspeed);
3532
}
3633

37-
public void WinchRelease(){winch.set(ControlMode.PercentOutput, .75* climbspeed);}
34+
public void WinchForward() {
35+
winch.set(ControlMode.PercentOutput, climbspeed);
36+
}
3837

3938
public void StopClimb() {
4039
scissor.set(ControlMode.PercentOutput, 0);
4140
winch.set(ControlMode.PercentOutput, 0);
4241
}
4342

44-
}
43+
}

src/main/java/frc/team5115/Subsystems/Drivetrain.java

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
66
import com.ctre.phoenix.motorcontrol.can.VictorSPX;
77
import edu.wpi.first.wpilibj.Joystick;
8+
import edu.wpi.first.wpilibj.Servo;
89
import edu.wpi.first.wpilibj2.command.SubsystemBase;
910
import frc.team5115.Auto.DriveBase;
1011
import frc.team5115.Robot.RobotContainer;
@@ -20,6 +21,8 @@ public class Drivetrain extends SubsystemBase implements DriveBase {
2021
private TalonSRX backLeft;
2122
private TalonSRX backRight;
2223

24+
Servo servo;
25+
2326
private double targetAngle; //during regular operation, the drive train keeps control of the drive. This is the angle that it targets.
2427

2528
private double rightSpd;
@@ -28,6 +31,7 @@ public class Drivetrain extends SubsystemBase implements DriveBase {
2831

2932
public Drivetrain(RobotContainer x) {
3033
//this.locationator = x.locationator;
34+
servo = new Servo(1);
3135
locationator = x.locationator;
3236

3337
frontLeft = new VictorSPX(FRONT_LEFT_MOTOR_ID);
@@ -68,6 +72,7 @@ public void drive(double x, double y, double throttle) { //Change the drive outp
6872
frontRight.set(ControlMode.PercentOutput, rightSpd);
6973
backLeft.set(ControlMode.PercentOutput, leftSpd);
7074
backRight.set(ControlMode.PercentOutput, rightSpd);
75+
servo.setAngle(85 - (15*getSpeedFeetPerSecond()));
7176
}
7277

7378
public void XBoxDrive(Joystick joy) {

0 commit comments

Comments
 (0)