Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/auto' into auto
Browse files Browse the repository at this point in the history
# Conflicts:
#	autonomous.chor
#	src/main/deploy/choreo/TestingPath.traj
#	src/main/java/frc/robot/Constants.java
  • Loading branch information
nevadex committed Feb 5, 2024
2 parents e949ef0 + 45a92b8 commit 25d10e0
Show file tree
Hide file tree
Showing 7 changed files with 456 additions and 21 deletions.
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Constants204.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@ public static final class Autonomous {
public static final String CHOREO_PATH_FILE = "TestingPath"; // omit file extension
}
public static final class Controller {
public static final int PORT = 1;
public static final int DRIVER_PORT = 1;
public static final int OPERATOR_PORT = 2;
}

// BELOW IS UNUSED
Expand Down
11 changes: 11 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

import edu.wpi.first.net.PortForwarder;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;

Expand All @@ -17,6 +19,11 @@ public class Robot extends TimedRobot {
private Command teleopCommand;
private RobotContainer robotContainer;

public enum ControlMode {
SINGLE, COMPETITION
}
public static final SendableChooser<ControlMode> ControlModeChooser = new SendableChooser<>();

/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
Expand All @@ -29,6 +36,10 @@ public void robotInit() {
robotContainer = new RobotContainer();
//CameraServer.startAutomaticCapture(); // use for USB camera
PortForwarder.add(8888, "10.2.4.69", 80);

ControlModeChooser.setDefaultOption("Single Controller (Driver:1 Operator:1)", ControlMode.SINGLE);
ControlModeChooser.addOption("Competition (Driver:1 Operator:2)", ControlMode.COMPETITION);
SmartDashboard.putData("Control Mode", ControlModeChooser);
}
/**
* This function is called every 20 ms, no matter the mode. Use this for items like diagnostics
Expand Down
54 changes: 46 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,14 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc.robot.commands.TeleopSwerve;
import frc.robot.subsystems.*;
import frc.robot.util.*;

import static frc.robot.Robot.ControlModeChooser;
import static frc.robot.Robot.ControlMode;

/*
* This class is where the bulk of the robot should be declared. Since Command-based is a
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
Expand All @@ -15,34 +19,68 @@
public class RobotContainer {
public final SwerveSubsystem SwerveSubsystem = new SwerveSubsystem();
public final ShooterSubsystem ShooterSubsystem = new ShooterSubsystem();
public final LinearActuatorSubsystem LinearActuatorSubsystem = new LinearActuatorSubsystem();
private final AutonomousManager AutonomousManager = new AutonomousManager(SwerveSubsystem);
Gamepad CONTROLLER = new Gamepad(Constants204.Controller.PORT);
Gamepad DRIVER = new Gamepad(Constants204.Controller.DRIVER_PORT);
Gamepad OPERATOR = new Gamepad(Constants204.Controller.DRIVER_PORT);

/**
* The container for the robot. Contains subsystems, OI devices, and commands.
*/
public RobotContainer() {
ControlModeChooser.onChange((ControlMode mode) -> {
if (mode == ControlMode.SINGLE) {
OPERATOR = new Gamepad(Constants204.Controller.DRIVER_PORT);
} else {
OPERATOR = new Gamepad(Constants204.Controller.OPERATOR_PORT);
}
configureButtonBindings();
System.out.println("Switched control mode to " + mode);
});

configureButtonBindings();
SwerveSubsystem.setDefaultCommand(
new TeleopSwerve(
SwerveSubsystem,
() -> CONTROLLER.getLeftX(),
() -> -1 * CONTROLLER.getLeftY(),
() -> -1 * CONTROLLER.getRightX(),
() -> DRIVER.getLeftX(),
() -> -1 * DRIVER.getLeftY(),
() -> -1 * DRIVER.getRightX(),
() -> false,
() -> CONTROLLER.getYButton(),
() -> CONTROLLER.getAButton()));
() -> DRIVER.getYButton(),
() -> DRIVER.getAButton()));


if (CONTROLLER.getBButton()) {
if (DRIVER.getBButton()) {
SwerveSubsystem.gyro.reset();
// s_Swerve.m_gyro_P2.calib;
System.out.println("you have calibed the gyro");
}

ShooterSubsystem.setDefaultCommand(
new RunCommand(
() -> ShooterSubsystem.speakerShot(CONTROLLER.getXButton()),
() -> ShooterSubsystem.speakerShot(OPERATOR.getXButton()),
ShooterSubsystem));

LinearActuatorSubsystem.setDefaultCommand(
new RunCommand(
() -> LinearActuatorSubsystem.shift(OPERATOR.getPOV()==0, OPERATOR.getPOV()==180),
LinearActuatorSubsystem
)
);
}
private void configureButtonBindings() {
new JoystickButton(OPERATOR, 5)
.whileTrue(
new RunCommand(() -> ShooterSubsystem.receive(true), ShooterSubsystem));

new JoystickButton(OPERATOR, 6)
.whileTrue(
new RunCommand(() -> ShooterSubsystem.bump(true), ShooterSubsystem));

new JoystickButton(OPERATOR, 10)
.whileTrue(
new RunCommand(() -> ShooterSubsystem.ampShot(true), ShooterSubsystem));

}

public Command getAutonomousCommand() {
Expand Down
129 changes: 129 additions & 0 deletions src/main/java/frc/robot/subsystems/HookSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
//package frc.robot.subsystems;
//import java.util.*;
//import com.revrobotics.*;
//import com.revrobotics.CANSparkLowLevel.MotorType;
//
//import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
//import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
//import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
//import edu.wpi.first.wpilibj2.command.SubsystemBase;
//import frc.robot.Constants;
//
//public class HookSubsystem extends SubsystemBase {
// private CANSparkMax hookMotor; // Create the Spark Max object in the program and include the CAN id and the type of motor used with the controller
// private RelativeEncoder hookEncoder; // Grab the attached encoder
// private final SparkPIDController hookController;
//
// public HookSubsystem() {
// hookMotor = new CANSparkMax(Constants.Hook.MOTOR_CAN_ID, MotorType.kBrushless); // Create the Spark Max object in the program and include the CAN id and the type of motor used with the controller
// hookEncoder = hookMotor.getEncoder(); // Grab the attached encoder
// hookController = hookMotor.getPIDController();
// hookMotor.restoreFactoryDefaults();
// hookMotor.setSmartCurrentLimit(Constants.Shooter.driveContinuousCurrentLimit);
// hookMotor.setInverted(Constants.Shooter.driveInvert);
// hookMotor.setIdleMode(Constants.Shooter.driveNeutralMode);
// hookController.setP(1.0);
// hookController.setI(0);
// hookController.setD(0);
// hookController.setFF(0);
// hookMotor.burnFlash();
// hookEncoder.setPosition(0.0);
// }
//
//
//
//
//
// double i = hookEncoder.getPosition();
//
// //raises the hook motor
// public void liftHook() {
// //private CANSparkMax hookRaising = new CANSparkMax(Constants.MAXIMUMHOOK_HEIGHT, MotorType.kBrushless);
// System.out.println("Raising Hook");
// hookController.setReference(Constants.Hook.LIFT_HOOK_HEIGHT, ControlType.kPosition);
// }
//
// //lowers the hook motor
// public void downHook() {
// //private CANSparkMax hookDepth = new CANSparkMax(Constants.MAXIMUMHOOK_DEPTH, MotorType.kBrushless);
// System.out.println("Down Hook");
// hookController.setReference(Constants.Hook.WITHDRAWN_HOOK_HEIGHT, ControlType.kPosition);
// }
//
// //lowers the hook motor
// public void extendHook() {
// //private CANSparkMax hookDepth = new CANSparkMax(Constants.MAXIMUMHOOK_DEPTH, MotorType.kBrushless);
// System.out.println("Down Hook");
// hookController.setReference(Constants.Hook.EXTENDED_HOOK_HEIGHT, ControlType.kPosition);
// }
//
// //Shuffleboard
// protected void execute() {
// SmartDashboard.putNumber("Hook Lifting", hookEncoder.getPosition());
// SmartDashboard.putNumber("Hook Extension", hookEncoder.getPosition());
// SmartDashboard.putNumber("Hook Withdrawn", hookEncoder.getPosition());
// //SmartDashboard.putNumber("Shooter Angle", .getPosition());
// //SmartDashboard.putNumber("Speed", );
// //SmartDashboard.putNumber("Front Left Drive Encoder", 0);
// //SmartDashboard.putNumber("Front Right Drive Encoder", 0);
// //SmartDashboard.putNumber("Back Left Drive Encoder", 0);
// //SmartDashboard.putNumber("Back Right Drive Encoder", 0);
// //SmartDashboard.putNumber("Swerve Angle", 0);
// }
// Shuffleboard.getTab("Hook Lifting")
// .addPersistent("Lifting Height", Constants.Hook.LIFT_HOOK_HEIGHT)
// .withWidget(BuiltInWidgets.kNumberSlider)
// .withProperties(Map.of("min", 0, "max", 5))
// .withSize(330,270)
// .withPosition(500,0)
// .getEntry();
// Shuffleboard.getTab("Hook Extension")
// .addPersistent("Extended Height", Constants.Hook.EXTENDED_HOOK_HEIGHT)
// .withWidget(BuiltInWidgets.kNumberSlider)
// .withProperties(Map.of("min", 0, "max", 5))
// .withSize(330,270)
// .withPosition(500,275)
// .getEntry();
// Shuffleboard.getTab("Hook Withdrawn")
// .addPersistent("Max Depth", Constants.Hook.WITHDRAWN_HOOK_HEIGHT)
// .withWidget(BuiltInWidgets.kNumberSlider)
// .withProperties(Map.of("min", 0, "max", -5))
// .withSize(330,270)
// .withPosition(500,550)
// .getEntry();
// Shuffleboard.getTab("Shooter Angle")
// .addPersistent("Shooter Angle", SHOOTER_ANGLE)
// .withSize(800,530)
// .withPosition(850,0)
// .getEntry();
// Shuffleboard.getTab("Speed")
// .addPersistent("Speed", SPEED)
// .withSize(330,270)
// .withPosition(500,825)
// .getEntry();
// Shuffleboard.getTab("Front Left Drive Encoder")
// .addPersistent("Front Left Drive Encoder", FRONTLEFT_DRIVE_ENCODER)
// .withSize(495,269)
// .withPosition(0,0)
// .getEntry();
// Shuffleboard.getTab("Front Right Drive Encoder")
// .addPersistent("Front Right Drive Encoder", FRONTRIGHT_DRIVE_ENCODER)
// .withSize(495,269)
// .withPosition(0,270)
// .getEntry();
// Shuffleboard.getTab("Back Left Drive Encoder")
// .addPersistent("Back Left Drive Encoder", BACKLEFT_DRIVE_ENCODER)
// .withSize(495,269)
// .withPosition(0,540)
// .getEntry();
// Shuffleboard.getTab("Right Drive Encoder")
// .addPersistent("Back Right Drive Encoder", BACKRIGHT_DRIVE_ENCODER)
// .withSize(495,269)
// .withPosition(0,810)
// .getEntry();
// Shuffleboard.getTab("Swerve Angle")
// .addPersistent("Swerve Angle", SWERVE_ANGLE)
// .withSize(800,530)
// .withPosition(850,545)
// .getEntry();
//}
34 changes: 34 additions & 0 deletions src/main/java/frc/robot/subsystems/LinearActuatorSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
package frc.robot.subsystems;

import com.revrobotics.CANSparkBase;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.lib.util.CANSparkMaxUtil;
import frc.lib.util.CANSparkMaxUtil.Usage;
import frc.robot.Constants;

public class LinearActuatorSubsystem extends SubsystemBase {
private final CANSparkMax actuatorMotor;

public LinearActuatorSubsystem() {
actuatorMotor = new CANSparkMax(27, MotorType.kBrushed);

actuatorMotor.restoreFactoryDefaults();
CANSparkMaxUtil.setCANSparkMaxBusUsage(actuatorMotor, Usage.kAll);
actuatorMotor.setSmartCurrentLimit(Constants.Shooter.driveContinuousCurrentLimit);
actuatorMotor.setIdleMode(CANSparkBase.IdleMode.kBrake);
actuatorMotor.enableVoltageCompensation(Constants.Shooter.voltageComp);
actuatorMotor.burnFlash();
}

public void shift(boolean up, boolean down) {
if (up && !down) {
actuatorMotor.set(-1.0);
} else if (!up && down) {
actuatorMotor.set(1.0);
} else {
actuatorMotor.set(0);
}
}
}
Loading

0 comments on commit 25d10e0

Please sign in to comment.