Added CS12 and CS13 first versions
This commit is contained in:
@@ -0,0 +1,3 @@
|
||||
Files placed in this directory will be deployed to the RoboRIO into the
|
||||
'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function
|
||||
to get a proper path relative to the deploy directory.
|
||||
@@ -0,0 +1,15 @@
|
||||
// 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;
|
||||
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
public final class Main {
|
||||
private Main() {}
|
||||
|
||||
public static void main(String... args) {
|
||||
RobotBase.startRobot(Robot::new);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,73 @@
|
||||
// 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;
|
||||
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
|
||||
public class Robot extends TimedRobot {
|
||||
private Command m_autonomousCommand;
|
||||
|
||||
private RobotContainer m_robotContainer;
|
||||
|
||||
@Override
|
||||
public void robotInit() {
|
||||
m_robotContainer = new RobotContainer();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void disabledExit() {}
|
||||
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
|
||||
if (m_autonomousCommand != null) {
|
||||
m_autonomousCommand.schedule();
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void autonomousExit() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
if (m_autonomousCommand != null) {
|
||||
m_autonomousCommand.cancel();
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopExit() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void testPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testExit() {}
|
||||
}
|
||||
@@ -0,0 +1,87 @@
|
||||
// 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;
|
||||
|
||||
import java.util.Map;
|
||||
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import frc.robot.constants.ArmConstants;
|
||||
import frc.robot.constants.OIConstants;
|
||||
import frc.robot.subsystems.Arm;
|
||||
import frc.robot.subsystems.Drivetrain;
|
||||
import frc.robot.subsystems.Elevator;
|
||||
|
||||
public class RobotContainer {
|
||||
private Drivetrain drivetrain;
|
||||
private Elevator elevator;
|
||||
private Arm arm;
|
||||
|
||||
private CommandXboxController driver;
|
||||
private CommandXboxController operator;
|
||||
|
||||
public RobotContainer() {
|
||||
drivetrain = new Drivetrain();
|
||||
elevator = new Elevator();
|
||||
arm = new Arm();
|
||||
|
||||
driver = new CommandXboxController(OIConstants.kDriverUSB);
|
||||
operator = new CommandXboxController(OIConstants.kOperatorUSB);
|
||||
|
||||
configureBindings();
|
||||
configureShuffleboard();
|
||||
}
|
||||
|
||||
private void configureBindings() {
|
||||
drivetrain.setDefaultCommand(
|
||||
drivetrain.driveArcade(
|
||||
driver::getLeftY,
|
||||
driver::getLeftX
|
||||
)
|
||||
);
|
||||
|
||||
elevator.setDefaultCommand(
|
||||
elevator.setSpeed(operator::getLeftY)
|
||||
);
|
||||
|
||||
arm.setDefaultCommand(
|
||||
arm.setSpeed(operator::getRightY)
|
||||
);
|
||||
|
||||
operator.a().onTrue(elevator.goToTop(() -> .5, 3));
|
||||
operator.b().onTrue(elevator.goToBottom(() -> .5, 3));
|
||||
operator.x().onTrue(arm.goToAngle(() -> .5, 45, 3));
|
||||
operator.y().onTrue(arm.goToAngle(() -> .5, 135, 3));
|
||||
}
|
||||
|
||||
private void configureShuffleboard() {
|
||||
ShuffleboardTab robotIndicatorTab = Shuffleboard.getTab(OIConstants.kRobotIndicatorsTabName);
|
||||
|
||||
robotIndicatorTab.addBoolean("Elevator Top Beam Break", elevator::getTopBeamBreak)
|
||||
.withPosition(0, 0)
|
||||
.withSize(2, 1)
|
||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||
|
||||
robotIndicatorTab.addBoolean("Elevator Bottom Beam Break", elevator::getBottomBeamBreak)
|
||||
.withPosition(0, 1)
|
||||
.withSize(2, 1)
|
||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||
|
||||
robotIndicatorTab.addDouble("Arm Angle", arm::getArmAngle)
|
||||
.withPosition(2, 0)
|
||||
.withSize(2, 2)
|
||||
.withWidget(BuiltInWidgets.kDial)
|
||||
.withProperties(Map.of(
|
||||
"Max", ArmConstants.kPotentiometerMaxAngle
|
||||
));
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
return drivetrain.driveTank(() -> .4, () -> -.4);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,9 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class ArmConstants {
|
||||
public static final int kMotorPWM = 6;
|
||||
|
||||
public static final int kPotentiometerAnalogIn = 0;
|
||||
|
||||
public static final double kPotentiometerMaxAngle = 180;
|
||||
}
|
||||
@@ -0,0 +1,8 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class DrivetrainConstants {
|
||||
public static final int kLeftFrontPWM = 0;
|
||||
public static final int kLeftRearPWM = 1;
|
||||
public static final int kRightFrontPWM = 2;
|
||||
public static final int kRightRearPWM = 3;
|
||||
}
|
||||
@@ -0,0 +1,9 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class ElevatorConstants {
|
||||
public static final int kMotor1PWM = 4;
|
||||
public static final int kMotor2PWM = 5;
|
||||
|
||||
public static final int kBottomBeamBreakDIO = 0;
|
||||
public static final int kTopBeamBreakDIO = 1;
|
||||
}
|
||||
@@ -0,0 +1,8 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class OIConstants {
|
||||
public static final int kDriverUSB = 0;
|
||||
public static final int kOperatorUSB = 1;
|
||||
|
||||
public static final String kRobotIndicatorsTabName = "Robot Indicators";
|
||||
}
|
||||
@@ -0,0 +1,53 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj.AnalogPotentiometer;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.VictorSP;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ArmConstants;
|
||||
|
||||
public class Arm extends SubsystemBase {
|
||||
private VictorSP motor;
|
||||
|
||||
private AnalogPotentiometer potentiometer;
|
||||
|
||||
public Arm() {
|
||||
motor = new VictorSP(ArmConstants.kMotorPWM);
|
||||
|
||||
potentiometer = new AnalogPotentiometer(
|
||||
ArmConstants.kPotentiometerAnalogIn,
|
||||
ArmConstants.kPotentiometerMaxAngle
|
||||
);
|
||||
}
|
||||
|
||||
public double getArmAngle() {
|
||||
return potentiometer.get();
|
||||
}
|
||||
|
||||
public Command setSpeed(DoubleSupplier speed){
|
||||
return run(() -> {
|
||||
motor.set(speed.getAsDouble());
|
||||
});
|
||||
}
|
||||
|
||||
public Command goToAngle(DoubleSupplier speed, double angle, double timeout) {
|
||||
boolean shouldNegate = potentiometer.get() > angle;
|
||||
|
||||
return setSpeed(() -> {
|
||||
if (shouldNegate) {
|
||||
return -1 * Math.abs(speed.getAsDouble());
|
||||
} else {
|
||||
return Math.abs(speed.getAsDouble());
|
||||
}
|
||||
})
|
||||
.until(() -> MathUtil.isNear(angle, potentiometer.get(), 3))
|
||||
.withTimeout(timeout);
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return setSpeed(() -> 0);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,43 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.VictorSP;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.DrivetrainConstants;
|
||||
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
private VictorSP leftFront;
|
||||
private VictorSP leftRear;
|
||||
private VictorSP rightFront;
|
||||
private VictorSP rightRear;
|
||||
|
||||
private DifferentialDrive drive;
|
||||
|
||||
public Drivetrain() {
|
||||
leftFront = new VictorSP(DrivetrainConstants.kLeftFrontPWM);
|
||||
leftRear = new VictorSP(DrivetrainConstants.kLeftRearPWM);
|
||||
rightFront = new VictorSP(DrivetrainConstants.kRightFrontPWM);
|
||||
rightRear = new VictorSP(DrivetrainConstants.kRightRearPWM);
|
||||
|
||||
leftFront.addFollower(leftRear);
|
||||
rightFront.addFollower(rightRear);
|
||||
rightFront.setInverted(true);
|
||||
|
||||
drive = new DifferentialDrive(leftFront, rightFront);
|
||||
}
|
||||
|
||||
public Command driveArcade(DoubleSupplier xSpeed, DoubleSupplier zRotation) {
|
||||
return run(() -> {
|
||||
drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble());
|
||||
});
|
||||
}
|
||||
|
||||
public Command driveTank(DoubleSupplier leftSpeed, DoubleSupplier rightSpeed) {
|
||||
return run(() -> {
|
||||
drive.tankDrive(leftSpeed.getAsDouble(), rightSpeed.getAsDouble());
|
||||
});
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,71 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.VictorSP;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ElevatorConstants;
|
||||
|
||||
public class Elevator extends SubsystemBase {
|
||||
private VictorSP motor1;
|
||||
private VictorSP motor2;
|
||||
|
||||
private DigitalInput bottomBeamBreak;
|
||||
private DigitalInput topBeamBreak;
|
||||
|
||||
public Elevator() {
|
||||
motor1 = new VictorSP(ElevatorConstants.kMotor1PWM);
|
||||
motor2 = new VictorSP(ElevatorConstants.kMotor2PWM);
|
||||
|
||||
motor1.addFollower(motor2);
|
||||
|
||||
bottomBeamBreak = new DigitalInput(ElevatorConstants.kBottomBeamBreakDIO);
|
||||
topBeamBreak = new DigitalInput(ElevatorConstants.kTopBeamBreakDIO);
|
||||
}
|
||||
|
||||
public boolean getBottomBeamBreak() {
|
||||
return bottomBeamBreak.get();
|
||||
}
|
||||
|
||||
public boolean getTopBeamBreak() {
|
||||
return topBeamBreak.get();
|
||||
}
|
||||
|
||||
public Command setSpeed(DoubleSupplier speed) {
|
||||
return run(() -> {
|
||||
double desiredSpeed = speed.getAsDouble();
|
||||
|
||||
if (desiredSpeed < 0) {
|
||||
if (bottomBeamBreak.get()) {
|
||||
motor1.set(0);
|
||||
} else {
|
||||
motor1.set(desiredSpeed);
|
||||
}
|
||||
} else {
|
||||
if (topBeamBreak.get()) {
|
||||
motor1.set(0);
|
||||
} else {
|
||||
motor1.set(desiredSpeed);
|
||||
}
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
public Command goToBottom(DoubleSupplier speed, double timeout) {
|
||||
return setSpeed(() -> -Math.abs(speed.getAsDouble()))
|
||||
.until(bottomBeamBreak::get)
|
||||
.withTimeout(timeout);
|
||||
}
|
||||
|
||||
public Command goToTop(DoubleSupplier speed, double timeout) {
|
||||
return setSpeed(() -> Math.abs(speed.getAsDouble()))
|
||||
.until(topBeamBreak::get)
|
||||
.withTimeout(timeout);
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return setSpeed(() -> 0);
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user