From 4888a4c08d5f69fcd0706eac73e20be9d3ec803e Mon Sep 17 00:00:00 2001 From: ryan123rudder <42309874+ryan123rudder@users.noreply.github.com> Date: Sat, 22 Feb 2020 13:37:38 -0700 Subject: [PATCH] Interuptability Handling --- .../java/frc4388/robot/RobotContainer.java | 36 +++---- .../frc4388/robot/commands/HoldTarget.java | 101 ++++++++++++++++++ .../robot/commands/ShootFireGroup.java | 6 +- .../frc4388/robot/subsystems/Shooter.java | 5 +- 4 files changed, 124 insertions(+), 24 deletions(-) create mode 100644 src/main/java/frc4388/robot/commands/HoldTarget.java diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index fbd7c2a..01c4be8 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -47,6 +47,7 @@ import frc4388.robot.subsystems.Shooter; import frc4388.robot.subsystems.ShooterAim; import frc4388.robot.subsystems.Climber; import frc4388.robot.commands.RunLevelerWithJoystick; +import frc4388.robot.commands.ShootFullGroup; import frc4388.robot.subsystems.Drive; import frc4388.robot.subsystems.Intake; import frc4388.robot.subsystems.LED; @@ -79,15 +80,15 @@ public class RobotContainer { private final Storage m_robotStorage = new Storage(); /* Cameras */ - private final Camera m_robotCameraFront = new Camera("front",0,160,120,40); - private final Camera m_robotCameraBack = new Camera("back",1,160,120,40); + private final Camera m_robotCameraFront = new Camera("front", 0, 160, 120, 40); + private final Camera m_robotCameraBack = new Camera("back", 1, 160, 120, 40); /* Controllers */ private final XboxController m_driverXbox = new XboxController(OIConstants.XBOX_DRIVER_ID); private final XboxController m_operatorXbox = new XboxController(OIConstants.XBOX_OPERATOR_ID); /** - * The container for the robot. Contains subsystems, OI devices, and commands. + * The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { configureButtonBindings(); @@ -102,22 +103,22 @@ public class RobotContainer { // continually sends updates to the Blinkin LED controller to keep the lights on m_robotLED.setDefaultCommand(new RunCommand(() -> m_robotLED.updateLED(), m_robotLED)); // runs the drum shooter in idle mode - m_robotShooter.setDefaultCommand(new RunCommand(() -> m_robotShooterAim.runShooterWithInput(m_operatorXbox.getLeftXAxis()), m_robotShooter)); + m_robotShooter.setDefaultCommand(new RunCommand( + () -> m_robotShooterAim.runShooterWithInput(m_operatorXbox.getLeftXAxis()), m_robotShooter)); // drives the leveler with an axis input from the driver controller m_robotLeveler.setDefaultCommand(new RunLevelerWithJoystick(m_robotLeveler, getDriverController())); } - /** - * Use this method to define your button->command mappings. Buttons can be created by - * instantiating a {@link GenericHID} or one of its subclasses ({@link - * edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a - * {@link edu.wpi.first.wpilibj2.command.button.JoystickButton}. - */ + * Use this method to define your button->command mappings. Buttons can be + * created by instantiating a {@link GenericHID} or one of its subclasses + * ({@link edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then + * passing it to a {@link edu.wpi.first.wpilibj2.command.button.JoystickButton}. + */ private void configureButtonBindings() { /* Driver Buttons */ - + // sets solenoids into high gear new JoystickButton(getDriverJoystick(), XboxController.RIGHT_BUMPER_BUTTON) .whenPressed(new InstantCommand(() -> m_robotDrive.setShiftState(true), m_robotDrive)); @@ -126,17 +127,16 @@ public class RobotContainer { new JoystickButton(getDriverJoystick(), XboxController.LEFT_BUMPER_BUTTON) .whenPressed(new InstantCommand(() -> m_robotDrive.setShiftState(false), m_robotDrive)); - + /* Operator Buttons */ - - //TODO: Shooter Buttons + // shoots until released - //new JoystickButton(getOperatorJoystick(), XboxController.RIGHT_BUMPER_BUTTON) - // .whileHeld(new ShootShooter(m_robotShooter, m_robotStorage, 5)); + new JoystickButton(getOperatorJoystick(), XboxController.RIGHT_BUMPER_BUTTON) + .whileHeld(new ShootFullGroup(m_robotShooter, m_robotShooterAim, m_robotStorage), false); // shoots one ball - //new JoystickButton(getOperatorJoystick(), XboxController.LEFT_BUMPER_BUTTON) - // .whileHeld(new ShootShooter(m_robotShooter, m_robotStorage, 1)); + new JoystickButton(getOperatorJoystick(), XboxController.LEFT_BUMPER_BUTTON) + .whenPressed(new ShootFullGroup(m_robotShooter, m_robotShooterAim, m_robotStorage), false); // aims the turret new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON) diff --git a/src/main/java/frc4388/robot/commands/HoldTarget.java b/src/main/java/frc4388/robot/commands/HoldTarget.java new file mode 100644 index 0000000..8449078 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/HoldTarget.java @@ -0,0 +1,101 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package frc4388.robot.commands; + +import frc4388.robot.Constants.ShooterConstants; +import frc4388.robot.Constants.VisionConstants; +import frc4388.robot.subsystems.Drive; +import frc4388.robot.subsystems.Shooter; +import frc4388.robot.subsystems.ShooterAim; +import frc4388.utility.controller.IHandController; +import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableEntry; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; + +public class HoldTarget extends CommandBase { + //Setup + NetworkTableEntry xEntry; + ShooterAim m_shooterAim; + Shooter m_shooter; + IHandController m_driverController; + //Aiming + double turnAmount = 0; + double xAngle = 0; + double yAngle = 0; + double target = 0; + public double distance; + public static double fireVel; + public static double fireAngle; + + /** + * Uses the Limelight to track the target + */ + public HoldTarget(Shooter shooterSubsystem, ShooterAim aimSubsystem) { + m_shooterAim = aimSubsystem; + m_shooter = shooterSubsystem; + addRequirements(m_shooter); + NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(1); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + //Vision Processing Mode + NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(0); + NetworkTableInstance.getDefault().getTable("limelight").getEntry("ledMode").setNumber(3); + } + + + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + target = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tv").getDouble(0); + xAngle = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tx").getDouble(0); + yAngle = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ty").getDouble(0); + + if (target == 1.0){ //If target in view + //Aiming Left/Right + turnAmount = (xAngle/VisionConstants.FOV)*VisionConstants.TURN_P_VALUE; + if (Math.abs(xAngle) < VisionConstants.X_ANGLE_ERROR){turnAmount = 0;} //Angle Error Zone + //Deadzones + else if(turnAmount > 0 && turnAmount < VisionConstants.MOTOR_DEAD_ZONE){turnAmount = VisionConstants.MOTOR_DEAD_ZONE;} + else if(turnAmount < 0 && turnAmount > -VisionConstants.MOTOR_DEAD_ZONE){turnAmount = -VisionConstants.MOTOR_DEAD_ZONE;} + m_shooterAim.runShooterWithInput(turnAmount/3); + + //Finding Distance + distance = VisionConstants.TARGET_HEIGHT/Math.tan((VisionConstants.LIME_ANGLE + yAngle)*(Math.PI/180)); + SmartDashboard.putNumber("Distance to Target", distance); + + double yVel = Math.sqrt(2*VisionConstants.GRAV*VisionConstants.TARGET_HEIGHT); + double xVel = (distance*VisionConstants.GRAV)/(yVel); + + fireVel = Math.sqrt((Math.pow(xVel, 2))+(Math.pow(yVel,2))); + fireAngle = Math.atan(yVel/xVel); + m_shooter.m_fireVel = fireVel; + m_shooter.m_fireAngle = fireAngle; + + } + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + //Drive Camera Mode + NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(1); + NetworkTableInstance.getDefault().getTable("limelight").getEntry("ledMode").setNumber(0); + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc4388/robot/commands/ShootFireGroup.java b/src/main/java/frc4388/robot/commands/ShootFireGroup.java index 03371d7..0175198 100644 --- a/src/main/java/frc4388/robot/commands/ShootFireGroup.java +++ b/src/main/java/frc4388/robot/commands/ShootFireGroup.java @@ -25,9 +25,9 @@ public class ShootFireGroup extends ParallelRaceGroup { */ public ShootFireGroup(Shooter m_shooter, ShooterAim m_shooterAim, Storage m_storage) { super( - new ShooterVelocityControlPID(m_shooter, m_shooter.addFireVel()), - new HoodAdjustPID(m_shooter), - new TrackTarget(m_shooter, m_shooterAim), + new RunCommand(() -> m_shooter.runDrumShooterVelocityPID(m_shooter.addFireVel(), m_shooter.m_shooterFalcon.getSelectedSensorVelocity())), + new RunCommand(() -> m_shooter.runAngleAdjustPID(m_shooter.addFireAngle())), + new HoldTarget(m_shooter, m_shooterAim), new StorageRun(m_storage) ); } diff --git a/src/main/java/frc4388/robot/subsystems/Shooter.java b/src/main/java/frc4388/robot/subsystems/Shooter.java index 14d4080..5f9507c 100644 --- a/src/main/java/frc4388/robot/subsystems/Shooter.java +++ b/src/main/java/frc4388/robot/subsystems/Shooter.java @@ -134,8 +134,7 @@ public class Shooter extends SubsystemBase { } } - public void resetGyroAngleAdj() - { + public void resetGyroAngleAdj(){ m_angleEncoder.setPosition(0); - } + } } \ No newline at end of file