Skip to content

Commit

Permalink
Merge pull request #15 from LakeEffectRobotics/intake
Browse files Browse the repository at this point in the history
Intake
  • Loading branch information
gbuckholtz authored Mar 21, 2024
2 parents 6f24221 + f16fe1d commit da9aafe
Show file tree
Hide file tree
Showing 21 changed files with 1,120 additions and 10 deletions.
4 changes: 1 addition & 3 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,5 @@
},
],
"java.test.defaultConfig": "WPIlibUnitTests",
"cSpell.words": [
"AHRS"
]
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx2G -Xms100m -Xlog:disable"
}
42 changes: 40 additions & 2 deletions src/main/java/frc/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,9 @@
import java.util.function.DoubleSupplier;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;

public class OI {

Expand All @@ -23,20 +25,45 @@ private static class DRIVER_MAP {
private static final int LOW_SHIFT_BUTTON = 1;
}

private static final XboxController xboxController = new XboxController(PORT.OPERATOR_CONTROLLER);
/**
* The threshold that must be met before an xbox is trigger is considered "pressed". Used to bind command so triggers
*/
private static final double XBOX_TRIGGER_THRESHOLD = 0.2;

/** Operator Button Map */
private static class OPERATOR_MAP {
private static final int SPIN_OUT_INTAKE_TRIGGER = XboxController.Axis.kLeftTrigger.value;
private static final int SPIN_IN_INTAKE_TRIGGER = XboxController.Axis.kRightTrigger.value;


private static final int INTAKE_POSITION_BUTTON = XboxController.Button.kA.value;
private static final int TRANSPORT_POSITION_BUTTON = XboxController.Button.kB.value;
private static final int AMP_POSITION_BUTTON = XboxController.Button.kX.value;
private static final int TRAP_POSITION_BUTTON = XboxController.Button.kY.value;
private static final int PREPARE_CLIMB_BUTTON = XboxController.Button.kLeftBumper.value;
private static final int CLIMB_BUTTTON = XboxController.Button.kRightBumper.value;
}


/** Driver (Joystick) */
private static final Joystick leftJoystick = new Joystick(PORT.LEFT_STICK);
private static final Joystick rightJoystick = new Joystick(PORT.RIGHT_STICK);

public static final JoystickButton shiftUpButton = new JoystickButton(rightJoystick, DRIVER_MAP.SHIFT_UP_BUTTON);
public static final JoystickButton shiftDownButton = new JoystickButton(rightJoystick, DRIVER_MAP.SHIFT_DOWN_BUTTON);

public static final JoystickButton lowShiftButton = new JoystickButton(leftJoystick, DRIVER_MAP.LOW_SHIFT_BUTTON);

/** Operator (Xbox Controller) */
public static final Trigger spinOutClawButton = new Trigger(() -> xboxController.getRawAxis(OPERATOR_MAP.SPIN_OUT_INTAKE_TRIGGER) >= XBOX_TRIGGER_THRESHOLD);
public static final Trigger spinInClawButton = new Trigger(() -> xboxController.getRawAxis(OPERATOR_MAP.SPIN_IN_INTAKE_TRIGGER) >= XBOX_TRIGGER_THRESHOLD);

public static final JoystickButton intakePositionButton = new JoystickButton(xboxController, OPERATOR_MAP.INTAKE_POSITION_BUTTON);
public static final JoystickButton transportPositionButton = new JoystickButton(xboxController, OPERATOR_MAP.TRANSPORT_POSITION_BUTTON);
public static final JoystickButton ampPositionButton = new JoystickButton(xboxController, OPERATOR_MAP.AMP_POSITION_BUTTON);
public static final JoystickButton trapPositionButton = new JoystickButton(xboxController, OPERATOR_MAP.TRAP_POSITION_BUTTON);
public static final JoystickButton prepareClimbButton = new JoystickButton(xboxController, OPERATOR_MAP.PREPARE_CLIMB_BUTTON);
public static final JoystickButton climbButton = new JoystickButton(xboxController,OPERATOR_MAP.CLIMB_BUTTTON);


public static DoubleSupplier leftDriveSupplier = () -> {
double raw = leftJoystick.getY();
Expand All @@ -52,6 +79,17 @@ private static class OPERATOR_MAP {
return processDriveInput(raw);
};

/**
* Operator-supplied intake spin speed
*/
public static DoubleSupplier spinOutClawSpeedSupplier = () -> {
return Math.pow(xboxController.getRawAxis(OPERATOR_MAP.SPIN_OUT_INTAKE_TRIGGER), 2);
};

public static DoubleSupplier spinInClawSpeedSupplier = () -> {
return Math.pow(xboxController.getRawAxis(OPERATOR_MAP.SPIN_IN_INTAKE_TRIGGER), 2);
};

private static double processDriveInput(double raw) {
// TODO: Configure input processing to suit your liking
if (Math.abs(raw) < 0.1) {
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,13 @@

package frc.robot;

import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.robot.subsystems.Arm;

public class Robot extends TimedRobot {
private Command m_autonomousCommand;
Expand Down Expand Up @@ -67,6 +70,7 @@ public void teleopExit() {}
@Override
public void testInit() {
CommandScheduler.getInstance().cancelAll();

}

@Override
Expand Down
43 changes: 42 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,21 +4,42 @@

package frc.robot;

import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.commands.AmpCommandGroup;
import frc.robot.commands.ClawCommand;
import frc.robot.commands.DriveCommand;
import frc.robot.commands.IntakeCommandGroup;
import frc.robot.commands.TransportCommandGroup;
import frc.robot.commands.TrapCommandGroup;
import frc.robot.commands.instant.ClimbPrepareCommand;
import frc.robot.commands.instant.RetractArmCommand;
import frc.robot.commands.instant.ShiftDownCommand;
import frc.robot.commands.instant.ShiftUpCommand;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Claw;
import frc.robot.subsystems.Climber;
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Wrist;
import frc.robot.subsystems.Gyro;
import frc.robot.subsystems.Drivetrain.Gear;

public class RobotContainer {
public final Compressor compressor = new Compressor(PneumaticsModuleType.REVPH);

public Drivetrain drivetrain = new Drivetrain(RobotMap.leftController1, RobotMap.rightController1, RobotMap.driveShitSolenoid);
public Arm arm = new Arm(RobotMap.armPistonSolenoid, RobotMap.armController1);
public Wrist wrist = new Wrist(RobotMap.wristController);
public Claw claw = new Claw(RobotMap.clawController);
public Climber climber = new Climber(RobotMap.climbController1,RobotMap.climbShiftSolenoid);
public Gyro gyro = new Gyro();

public RobotContainer() {

compressor.enableAnalog(90, 100);

configureBindings();

drivetrain.setDefaultCommand(new DriveCommand(drivetrain, OI.leftDriveSupplier, OI.rightDriveSupplier));
Expand All @@ -36,9 +57,29 @@ private void configureBindings() {
OI.lowShiftButton.whileTrue(Commands.runOnce(() -> {
drivetrain.disableAutoShifting();
drivetrain.setGear(Gear.LOW);
})).onFalse(Commands.runOnce(() -> {
})).onFalse(Commands.runOnce(() -> {
drivetrain.enableAutoShifting();
}));

//OI.spinArmButton.whileTrue(new ArmCommand(arm, OI.spinArmSpeedSupplier.getAsDouble()));

/* Operator Bindings */
OI.spinOutClawButton.whileTrue(new ClawCommand(claw, OI.spinOutClawSpeedSupplier.getAsDouble()));
OI.spinInClawButton.whileTrue(new ClawCommand(claw, -OI.spinInClawSpeedSupplier.getAsDouble()));

// OI.extendArmButton.onTrue(Commands.runOnce(() -> {
// wrist.setTargetAngle(100);
// }));
// OI.retractArmButton.onTrue(Commands.runOnce(() -> {
// wrist.setTargetAngle(5);
// }));
OI.intakePositionButton.onTrue(new IntakeCommandGroup(wrist, arm));
OI.transportPositionButton.onTrue(new TransportCommandGroup(wrist, arm));
OI.ampPositionButton.onTrue(new AmpCommandGroup(wrist, arm));
OI.trapPositionButton.onTrue(new TrapCommandGroup(wrist, arm));
OI.prepareClimbButton.onTrue(Commands.runOnce(() -> climber.prepareClimb(),climber) );
OI.climbButton.onTrue(Commands.runOnce(() -> climber.climb(),climber));

}

public Command getAutonomousCommand() {
Expand Down
63 changes: 59 additions & 4 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,46 +4,101 @@
import com.revrobotics.AlternateEncoderType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.SPI;

public class RobotMap {

/** Inner class to hold CAN ID constants */
private class CAN {

/** Drivetrain */
private static final int LEFT_CONTROLLER_1 = 3;
private static final int LEFT_CONTROLLER_2 = 4;
private static final int RIGHT_CONTROLLER_1 = 1;
private static final int RIGHT_CONTROLLER_2 = 2;

/** Intake */

// Climber
private static final int CLIMB_CONTROLLER_1 = 5;
private static final int CLIMB_CONTROLLER_2 = 6;
private static final int CLIMB_CONTROLLER_3 = 7;

private static final int ARM_CONTROLLER_1 = 8;
private static final int ARM_CONTROLLER_2 = 9;

private static final int CLAW_CONTROLLER = 10;
private static final int WRIST_CONTROLLER = 11;

}

private class PCM {
private static final int DRIVE_SHIFT_UP = 14;
private static final int DRIVE_SHIFT_DOWN = 15;

private static final int ARM_PISTON_UP = 1;
private static final int ARM_PISTON_DOWN = 2;

private static final int CLIMB_PISTON_UP = 10; // Todo: have to find out the real number
private static final int CLIMB_PISTON_DOWN = 11; // Todo: find the real number
}

/** Drivetrain */
public static final CANSparkMax leftController1 = new CANSparkMax(CAN.LEFT_CONTROLLER_1, MotorType.kBrushless);
public static final CANSparkMax rightController1 = new CANSparkMax(CAN.RIGHT_CONTROLLER_1, MotorType.kBrushless);
public static final CANSparkMax rightController2 = new CANSparkMax(CAN.RIGHT_CONTROLLER_2, MotorType.kBrushless);
public static final CANSparkMax leftController2 = new CANSparkMax(CAN.LEFT_CONTROLLER_2, MotorType.kBrushless);

public static final DoubleSolenoid driveShitSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH, PCM.DRIVE_SHIFT_DOWN, PCM.DRIVE_SHIFT_UP);

/** Intake */

// Climber
public static final CANSparkMax climbController1 = new CANSparkMax(CAN.CLIMB_CONTROLLER_1, MotorType.kBrushless);
public static final CANSparkMax climbController2 = new CANSparkMax(CAN.CLIMB_CONTROLLER_2, MotorType.kBrushless);
public static final CANSparkMax climbController3 = new CANSparkMax(CAN.CLIMB_CONTROLLER_3, MotorType.kBrushless);
public static final DoubleSolenoid climbShiftSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH, PCM.CLIMB_PISTON_DOWN, PCM.CLIMB_PISTON_UP); // 50% prob this is the right order for down and up

// Arm
public static final CANSparkMax armController1 = new CANSparkMax(CAN.ARM_CONTROLLER_1, MotorType.kBrushless);
public static final CANSparkMax armController2 = new CANSparkMax(CAN.ARM_CONTROLLER_2, MotorType.kBrushless);
public static final DoubleSolenoid armPistonSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH, PCM.ARM_PISTON_UP, PCM.ARM_PISTON_DOWN);

public static final CANSparkMax clawController = new CANSparkMax(CAN.CLAW_CONTROLLER, MotorType.kBrushless);
public static final CANSparkMax wristController = new CANSparkMax(CAN.WRIST_CONTROLLER, MotorType.kBrushless);

// Gyro
public static final AHRS gyro = new AHRS(SPI.Port.kMXP);

// Static initializer will be run on first reference to RobotMap (stealing code from greg)
static {

/** Drivetrain */
leftController2.follow(leftController1);
rightController2.follow(rightController1);

leftController1.setInverted(true);
rightController1.setInverted(false);
leftController1.setInverted(false);
rightController1.setInverted(true);

/** Intake */

// Climber
climbController2.follow(climbController1);
climbController3.follow(climbController1);

armController2.follow(armController1);

armController1.setIdleMode(IdleMode.kCoast);
armController2.setIdleMode(IdleMode.kCoast);


wristController.setIdleMode(IdleMode.kBrake);
wristController.setInverted(true);

}

}
28 changes: 28 additions & 0 deletions src/main/java/frc/robot/commands/AmpCommandGroup.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// Copyright (c) FIRST and other WPILib contributors.
// 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.commands;

import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Wrist;
import frc.robot.subsystems.Arm.ArmExtension;
import frc.robot.subsystems.Arm.ArmPosition;
import frc.robot.subsystems.Wrist.WristPosition;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class AmpCommandGroup extends SequentialCommandGroup {
/** Creates a new IntakeCommandGroup. */
public AmpCommandGroup(Wrist wrist, Arm arm) {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());
addCommands(new WristCommand(wrist, WristPosition.UP),
new RotateArmCommand(arm,ArmPosition.AMP),
new ExtendArmCommand(arm, ArmExtension.RETRACT),
new WristCommand(wrist, WristPosition.DOWN)
);
}
}
21 changes: 21 additions & 0 deletions src/main/java/frc/robot/commands/ClawCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Claw;

public class ClawCommand extends Command {

Claw claw;
double speed;

public ClawCommand(Claw claw, double speed) {
this.claw = claw;
this.speed = speed;
}

@Override
public void execute() {
claw.setOutput(speed);
}

}
41 changes: 41 additions & 0 deletions src/main/java/frc/robot/commands/ExtendArmCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Arm.ArmExtension;

public class ExtendArmCommand extends Command {
Arm arm;
ArmExtension extend;

public ExtendArmCommand(Arm arm,Arm.ArmExtension extend) {
this.arm = arm;
this.extend = extend;


}

@Override
public void initialize(){
if(extend == ArmExtension.EXTEND){
arm.extendArm();
}else{
arm.retractArm();
}
}

@Override
public void execute() {

}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return arm.inPosition();
}
}
Loading

0 comments on commit da9aafe

Please sign in to comment.