Skip to content

Commit

Permalink
Merge pull request #39 from 2729StormRobotics/revert-38-ButtonBindings
Browse files Browse the repository at this point in the history
Revert "Merge Button Bindings into dev"
  • Loading branch information
mayazarc authored Feb 14, 2023
2 parents 616636d + af2e205 commit 2f48015
Show file tree
Hide file tree
Showing 27 changed files with 290 additions and 989 deletions.
4 changes: 2 additions & 2 deletions Charge2023Test/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2023.3.2"
id "edu.wpi.first.GradleRIO" version "2023.1.1"
}

sourceCompatibility = JavaVersion.VERSION_11
Expand Down Expand Up @@ -96,4 +96,4 @@ wpi.java.configureTestTasks(test)
// Configure string concat to always inline compile
tasks.withType(JavaCompile) {
options.compilerArgs.add '-XDstringConcat=inline'
}
}
59 changes: 25 additions & 34 deletions Charge2023Test/src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,19 +3,8 @@
// the WPILib BSD license file in the root directory of this project.

package frc.robot;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.I2C.Port;


/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
* constants. This class should not be used for any other purpose. All constants should be declared
* globally (i.e. public static). Do not put anything functional in this class.
*
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
* constants are needed, to reduce verbosity.
*/
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;

/**
* The Constants class provides a convenient place for teams to hold robot-wide
Expand Down Expand Up @@ -82,9 +71,9 @@ public static final class DriveConstants {

// Drive Motor Ports

public static final int kLeftLeaderMotorPort = 9;
public static final int kLeftFollowerMotorPort = 6;
public static final int kRightLeaderMotorPort = 2;
public static final int kLeftLeaderMotorPort = 8;
public static final int kLeftFollowerMotorPort = 2;
public static final int kRightLeaderMotorPort = 6;
public static final int kRightFollowerMotorPort = 3;


Expand Down Expand Up @@ -158,36 +147,38 @@ public static final class ButtonBindingConstants {
}

public static final class ArmConstants {
// need all port nums
public static final int kExtensionMotorPort = -1;
public static final int kAngleMotorPort = -1;
public static final int kStringPotPort = -1;

// CHANGE kMaxExtensionLengthInEncoderTicks!
public static final double kMaxExtensionLengthInEncoderTicks = 5.0;
public static final double kMaxExtensionLength = 63.75; // inches

// port numbers
public static final int kExtensionMotorPort = 9;
public static final int kAngleMotorPort = 8;
public static final int kAngleMotorFollowerPort = 2;
public static final int kLimitSwitchPort = -1;

// Arm Angle Tolerance
public static final double kArmAngleTolerance = .1;

public static final double kArmLength = 34.5; // inches

// tbd
public static final double kAngleMotorSpeed = .5;
public static final double kExtensionMotorSpeed = .5;
// grid constants
public static final double leftHorizontalShift = 0;
public static final double midHorizontalShift = 0;
public static final double rightHorizontalShift = 0;

public static final double lowAngle = 0;
public static final double midConeAngle = 0;
public static final double highConeAngle = 0;
public static final double midCubeAngle = 0;
public static final double highCubeAngle = 0;
public static final double lowExtensionDistance = 0;
public static final double midExtensionDistance = 0;
public static final double highExtensionDistance = 0;
// shelf constants
public static final double shelfAngle = 0;
public static final double shelfExtensionDistance = 0;
// charge station constants
public static final double chargingAngle = 0;
public static final double chargingExtensionDistance = 0;

public static final double kChargingAngle = 0;
// angle motor pid
public static final double kP = 0.00425;
public static final double kI = 0;
public static final double kD = 0;

}


}
}
4 changes: 1 addition & 3 deletions Charge2023Test/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,7 @@ public void autonomousInit() {

/** This function is called periodically during autonomous. */
@Override
public void autonomousPeriodic() {

}
public void autonomousPeriodic() {}

@Override
public void teleopInit() {
Expand Down
173 changes: 28 additions & 145 deletions Charge2023Test/src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,63 +4,24 @@

package frc.robot;


import java.util.logging.Handler;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.PS4Controller.Axis;
import edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.commandgroups.AutoDriveBackwards;

//import frc.robot.commandgroups.GridConeMid;
//import frc.robot.commandgroups.GridCubeHigh;
//import frc.robot.commandgroups.GridCubeMid;
import frc.robot.commands.ChangeArmAngle;
import frc.robot.commands.ExampleCommand;
import frc.robot.subsystems.Arm;
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.ExampleSubsystem;
import frc.robot.subsystems.Claw;

//import frc.robot.commands.ChangeArmAngle;
import frc.robot.commands.DriveManuallyArcade;
import frc.robot.commands.ExampleCommand;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.POVButton;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.commands.ClawConePickup;
import frc.robot.commands.ClawEject;
import frc.robot.commands.ClawPickup;
import frc.robot.commands.DriveDistance;
import frc.robot.commands.PIDbalancechargestation;
import frc.robot.commands.PointTurnGyroPID;
import frc.robot.commands.PointTurnGyroTank;
import frc.robot.commands.upanddowngyro;
import frc.robot.commands.VisionAlignToRetroreflectiveTape;
import frc.robot.commands.VisionDriveToPointOfInterest;
import frc.robot.commands.VisionPointToPointOfInference;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.commandgroups.AutoDriveBackwards;
import frc.robot.commandgroups.DriveBackwardsAndBalance;
import frc.robot.commands.DriveDistance;
import frc.robot.commands.DriveManuallyArcade;
import frc.robot.subsystems.Drivetrain;
import frc.robot.commands.PointTurnGyroTank;

import static frc.robot.Constants.*;
import static frc.robot.Constants.DriveConstants.*;


/**
* 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}
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
* 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}
* periodic methods (other than the scheduler calls). Instead, the structure of
* the robot (including
* subsystems, commands, and button mappings) should be declared here.
*/
public class RobotContainer {
Expand All @@ -69,132 +30,54 @@ public class RobotContainer {
private final XboxController m_driver = new XboxController(DriveConstants.kDriverControllerPort);
private final XboxController m_operator = new XboxController(DriveConstants.kOperatorControllerPort);


private final Arm arm;
private final Claw claw;
private final Drivetrain m_drivetrain;


private final double straightSpeedFactor = 0.6;
private final double turnSpeedFactor = 0.5;
private final double straightDecelSpeedFactor = 0.7;
private final double turnDecelSpeedFactor = 0.4;



// private final Index m_index;
// private final Intake m_intake;
// private final Shooter m_shooter;
// private final Vision m_vision;
// private final Compressor m_testCompressor;

private final SendableChooser<Command> m_autoChooser;

/** The container for the robot. Contains subsystems, OI devices, and commands. */
/**
* The container for the robot. Contains subsystems, OI devices, and commands.
*/
public RobotContainer() {

// m_index = new Index();
// m_intake = new Intake();
//m_vision = new Vision();
// m_shooter = new Shooter();
arm = new Arm();
m_drivetrain = new Drivetrain();
claw = new Claw();

m_autoChooser = new SendableChooser<>();
SmartDashboard.putData("Autonomous Selector", m_autoChooser);
//m_autoChooser.setDefaultOption("Do Nothing", new InstantCommand());
m_autoChooser.addOption("DriveBackwardsAndBalance", new DriveBackwardsAndBalance(m_drivetrain));
// m_autoChooser.addOption("Wall Shot", new AutoWallShot(m_shooter, m_index, m_drivetrain, m_intake, m_vision));

m_drivetrain.setDefaultCommand(
new DriveManuallyArcade(() -> m_driver.getLeftY(), () -> m_driver.getRightX(), m_drivetrain));



// m_index = new Index();
// m_intake = new Intake();
//m_vision = new Vision();
// m_shooter = new Shooter();

SmartDashboard.putData("Autonomous Selector", m_autoChooser);
//m_autoChooser.setDefaultOption("Do Nothing", new InstantCommand());
m_autoChooser.setDefaultOption("DriveBackwardsAndBalance", new DriveBackwardsAndBalance(m_drivetrain));
// m_autoChooser.addOption("Wall Shot", new AutoWallShot(m_shooter, m_index, m_drivetrain, m_intake, m_vision));

m_drivetrain.setDefaultCommand(
new DriveManuallyArcade(() -> m_driver.getLeftY(), () -> m_driver.getRightX(), m_drivetrain));

arm = new Arm();

// Configure the button bindings
configureButtonBindings();
}

//TAHA WUZ HERE!!!

/**
* Use this method to define your button->command mappings. Buttons can be created by
* 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.wpilibj.Joystick} or {@link XboxController}), and then passing
* it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
* @return
*/


private void configureButtonBindings() {
new Trigger(() -> (m_driver.getLeftTriggerAxis() > 0.01))
.toggleOnTrue(new DriveManuallyArcade(() -> (m_driver.getLeftY() * straightDecelSpeedFactor),
() -> (-m_driver.getRightX() * turnDecelSpeedFactor), m_drivetrain));
//One press of the trigger toggles the speed in which the drivetrain travels in. If true, the drive train will travel at a decellerated speed. Press Again to return to normal operation.

new Trigger(() -> (m_driver.getRightTriggerAxis() > 0.01))
.onTrue(new DriveManuallyArcade(() -> (m_driver.getLeftY() * straightSpeedFactor),
() -> (-m_driver.getRightX() * turnSpeedFactor), m_drivetrain));
//to NOT be used when slow speed (Left Trigger) is toggled on. This is the normal turning operation speed when the right trigger is held true.


/* Trigger aOpButton = new JoystickButton(m_operator, Button.kA.value).onTrue(
new ChangeArmAngle(arm, arm.getArmAngle() + 30);

new JoystickButton(m_operator, Button.kB.value).whileTrue(
new ChangeArmAngle(arm, arm.getArmAngle() - 30));
*/

//Trigger bOpButton = new JoystickButton(m_operator, Button.kB.value).onTrue(new GridCubeMid(arm, drivetrain));
new ChangeArmAngle(arm, 0));

// Trigger xOpButton = new JoystickButton(m_operator, Button.kX.value).onTrue(new GridConeMid(arm, drivetrain));
new JoystickButton(m_operator, Button.kY.value).whileTrue(
new ChangeArmAngle(arm, 90));

//new JoystickButton(m_operator, Button.kY.value).whileTrue(new GridCubeHigh(arm,drivetrain));
new JoystickButton(m_operator, Button.kX.value).whileTrue(
new ChangeArmAngle(arm, 180));

Trigger rBumpOpButton = new JoystickButton(m_operator, Button.kRightBumper.value).onTrue(new ClawPickup(claw));

Trigger rOpTrigger = new Trigger(() -> (m_operator.getRightTriggerAxis() > 0.01))
.whileTrue( new ClawConePickup(claw));


Trigger lOpTrigger = new Trigger(() -> (m_operator.getLeftTriggerAxis() > 0.01))
.whileTrue(new ClawEject(claw));

// Trigger downopDpad = new POVButton(m_operator, 180).onTrue(new ChargeArm(arm));
// down d-pad button
// Trigger leftopDpad = new POVButton(m_operator, 270).whileTrue(new ShelfPickup(arm));
// left d-pad button
}

//add vision button binding (Either A,B, or X button Driver)

//add dock and engage button binding (Y-Button Driver)
new JoystickButton(m_operator, Button.kA.value).whileTrue(
new ChangeArmAngle(arm, 270));

}

/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
* @return the command to run in autonomous
*/

public Command getAutonomousCommand() {

// An ExampleCommand will run in autonomous
return m_autoChooser.getSelected();
return new ExampleCommand(new ExampleSubsystem());

}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.commands.DriveDistance;
import frc.robot.commands.PointTurnGyroPID;
import frc.robot.commands.PointTurnGyroTank;
import frc.robot.subsystems.Drivetrain;

Expand All @@ -20,7 +21,8 @@ public class AutoDriveBackwards extends SequentialCommandGroup {
public AutoDriveBackwards(Drivetrain drivetrain) {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());
//addCommands(new DriveDistance(drivetrain, -0.3, 50));
addCommands(new PointTurnGyroTank(0.6, 90, drivetrain));
// addCommands(new DriveDistance(drivetrain, -0.3, 50));
// addCommands(new PointTurnGyroTank(0.6, 90, drivetrain));
addCommands(new PointTurnGyroPID(90, drivetrain));
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
// 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.commandgroups;

import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import frc.robot.commands.ChangeArmAngle;
import frc.robot.subsystems.Arm;
import static frc.robot.Constants.ArmConstants.*;

// 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

// This command group positions the arm to balance out the robot when driving onto the Charge Station.

public class ChargeArm extends ParallelCommandGroup {

private final Arm m_arm;

/** Creates a new chargeArm. */
public ChargeArm(Arm arm) {

m_arm = arm;

// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());

addCommands(new ChangeArmAngle(m_arm, kChargingAngle));

}
}
Loading

0 comments on commit 2f48015

Please sign in to comment.