Compare commits

...

2 Commits

5 changed files with 64 additions and 11 deletions

View File

@ -8,23 +8,43 @@ import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.constants.ArmConstants; import frc.robot.constants.ArmConstants;
import frc.robot.constants.IOConstants; import frc.robot.constants.IOConstants;
import frc.robot.subsystems.Arm; import frc.robot.subsystems.Arm;
import frc.robot.subsystems.DriveTrain;
import frc.robot.subsystems.Grabber;
public class RobotContainer { public class RobotContainer {
CommandXboxController driver; CommandPS5Controller driver;
Arm arm; Arm arm;
DriveTrain driveTrain;
Grabber grabber;
public RobotContainer() { public RobotContainer() {
arm = new Arm(); arm = new Arm();
driver = new CommandXboxController(IOConstants.kDriverID0); driveTrain = new DriveTrain();
grabber = new Grabber();
driver = new CommandPS5Controller(IOConstants.kDriverID0);
configureBindings(); configureBindings();
} }
private void configureBindings() { private void configureBindings() {
driveTrain.setDefaultCommand(
driveTrain.driveArcade(
driver::getLeftY,
driver::getLeftX
)
);
grabber.setDefaultCommand(grabber.stop());
driver.R1().whileTrue(grabber.runGrabberMotor(1));
driver.L1().whileTrue(grabber.runGrabberMotor(-1));
arm.setDefaultCommand(arm.stop());
driver.povUp().whileTrue(arm.runArmMotor(1));
driver.povDown().whileTrue(arm.runArmMotor(-1));
} }
public Command getAutonomousCommand() { public Command getAutonomousCommand() {

View File

@ -0,0 +1,6 @@
package frc.robot.constants;
public class GrabberConstants {
public static final int kGrabberLtMotorID6 = 6;
public static final int kGrabberRtMotorID7 = 7;
}

View File

@ -18,4 +18,8 @@ public class Arm extends SubsystemBase {
motor.set(speed); motor.set(speed);
}); });
} }
public Command stop() {
return run(() -> motor.set(0));
}
} }

View File

@ -30,15 +30,8 @@ public class DriveTrain extends SubsystemBase {
} }
public Command driveArcade(DoubleSupplier xSpeed, DoubleSupplier zRotation) { public Command driveArcade(DoubleSupplier xSpeed, DoubleSupplier zRotation) {
return run(() -> { return run(() -> {
//makes car like steering possible
drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble()); drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble());
}); });
} }
public Command driveTank(DoubleSupplier leftSpeed, DoubleSupplier rightSpeed) {
return run(() -> {
//makes tank steering possible
drive.tankDrive(leftSpeed.getAsDouble(), rightSpeed.getAsDouble());
});
}
} }

View File

@ -0,0 +1,30 @@
package frc.robot.subsystems;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ArmConstants;
import frc.robot.constants.DriveTrainConstants;
import frc.robot.constants.GrabberConstants;
public class Grabber extends SubsystemBase {
private WPI_TalonSRX motorRight;
private WPI_TalonSRX motorLeft;
public Grabber() {
motorRight = new WPI_TalonSRX(GrabberConstants.kGrabberRtMotorID7);
motorLeft = new WPI_TalonSRX(GrabberConstants.kGrabberLtMotorID6);
motorLeft.follow(motorRight);
}
public Command runGrabberMotor(double speed) {
return run(() -> {
motorRight.set(speed);
});
}
public Command stop() {
return run(() -> motorRight.set(0));
}
}