mirror of
https://github.com/Team4388/Robot-Essentials.git
synced 2026-06-08 16:28:02 -06:00
Merge pull request #4 from Team4388/command-based-update
Command based update
This commit is contained in:
+1
-1
@@ -1,6 +1,6 @@
|
||||
plugins {
|
||||
id "java"
|
||||
id "edu.wpi.first.GradleRIO" version "2020.1.1-beta-2"
|
||||
id "edu.wpi.first.GradleRIO" version "2019.1.1"
|
||||
}
|
||||
|
||||
def ROBOT_MAIN_CLASS = "frc4388.robot.Main"
|
||||
|
||||
@@ -8,6 +8,9 @@
|
||||
package frc4388.robot;
|
||||
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.buttons.JoystickButton;
|
||||
import frc4388.robot.commands.Drive.DriveWithJoystick;
|
||||
import frc4388.robot.commands.Drive.GamerMove;
|
||||
import frc4388.utility.controller.IHandController;
|
||||
import frc4388.utility.controller.XboxController;
|
||||
|
||||
@@ -46,12 +49,16 @@ public class OI {
|
||||
|
||||
private static OI instance;
|
||||
|
||||
private static XboxController m_driverXbox;
|
||||
public static XboxController m_driverXbox;
|
||||
private static XboxController m_operatorXbox;
|
||||
|
||||
public OI() {
|
||||
m_driverXbox = new XboxController(RobotMap.XBOX_DRIVER_ID);
|
||||
m_operatorXbox = new XboxController(RobotMap.XBOX_OPERATOR_ID);
|
||||
|
||||
JoystickButton GamerMove = new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON);
|
||||
GamerMove.whenPressed(new GamerMove());
|
||||
GamerMove.whenReleased(new DriveWithJoystick());
|
||||
}
|
||||
|
||||
public static OI getInstance() {
|
||||
@@ -74,4 +81,9 @@ public class OI {
|
||||
{
|
||||
return m_operatorXbox.getJoyStick();
|
||||
}
|
||||
|
||||
public Joystick getDriverJoystick()
|
||||
{
|
||||
return m_driverXbox.getJoyStick();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,53 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2018 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.Drive;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.Command;
|
||||
import frc4388.robot.OI;
|
||||
import frc4388.robot.Robot;
|
||||
|
||||
public class DriveWithJoystick extends Command {
|
||||
|
||||
public double m_inputMove, m_inputSteer;
|
||||
|
||||
public DriveWithJoystick() {
|
||||
// Use requires() here to declare subsystem dependencies
|
||||
// eg. requires(chassis);
|
||||
requires(Robot.m_Drive);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
@Override
|
||||
protected void initialize() {
|
||||
}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
@Override
|
||||
protected void execute() {
|
||||
m_inputMove = OI.getInstance().getDriverController().getLeftYAxis();
|
||||
m_inputSteer = -(OI.getInstance().getDriverController().getRightXAxis());
|
||||
Robot.m_Drive.driveWithInput(m_inputMove, m_inputSteer);
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
@Override
|
||||
protected boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Called once after isFinished returns true
|
||||
@Override
|
||||
protected void end() {
|
||||
}
|
||||
|
||||
// Called when another command which requires one or more of the same
|
||||
// subsystems is scheduled to run
|
||||
@Override
|
||||
protected void interrupted() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,47 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2018 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.Drive;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.Command;
|
||||
import frc4388.robot.Robot;
|
||||
|
||||
public class GamerMove extends Command {
|
||||
public GamerMove() {
|
||||
// Use requires() here to declare subsystem dependencies
|
||||
// eg. requires(chassis);
|
||||
requires(Robot.m_Drive);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
@Override
|
||||
protected void initialize() {
|
||||
}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
@Override
|
||||
protected void execute() {
|
||||
Robot.m_Drive.driveWithInput(0, 1);
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
@Override
|
||||
protected boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Called once after isFinished returns true
|
||||
@Override
|
||||
protected void end() {
|
||||
}
|
||||
|
||||
// Called when another command which requires one or more of the same
|
||||
// subsystems is scheduled to run
|
||||
@Override
|
||||
protected void interrupted() {
|
||||
}
|
||||
}
|
||||
+3
-3
@@ -5,18 +5,18 @@
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package frc4388.robot.commands;
|
||||
package frc4388.robot.commands.LED;
|
||||
|
||||
import frc4388.robot.Robot;
|
||||
import frc4388.robot.constants.LEDPatterns;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.Command;
|
||||
|
||||
public class setLEDPattern extends Command {
|
||||
public class SetLEDPattern extends Command {
|
||||
|
||||
public static LEDPatterns m_pattern;
|
||||
|
||||
public setLEDPattern(LEDPatterns pattern) {
|
||||
public SetLEDPattern(LEDPatterns pattern) {
|
||||
requires(Robot.m_led);
|
||||
m_pattern = pattern;
|
||||
}
|
||||
@@ -0,0 +1,46 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2018 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.LED;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.Command;
|
||||
import frc4388.robot.Robot;
|
||||
|
||||
public class UpdateLED extends Command {
|
||||
public UpdateLED() {
|
||||
// Use requires() here to declare subsystem dependencies
|
||||
requires(Robot.m_led);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
@Override
|
||||
protected void initialize() {
|
||||
}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
@Override
|
||||
protected void execute() {
|
||||
Robot.m_led.updateLED();
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
@Override
|
||||
protected boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Called once after isFinished returns true
|
||||
@Override
|
||||
protected void end() {
|
||||
}
|
||||
|
||||
// Called when another command which requires one or more of the same
|
||||
// subsystems is scheduled to run
|
||||
@Override
|
||||
protected void interrupted() {
|
||||
}
|
||||
}
|
||||
@@ -17,6 +17,8 @@ import edu.wpi.first.wpilibj.Talon;
|
||||
import edu.wpi.first.wpilibj.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import frc4388.robot.RobotMap;
|
||||
import frc4388.robot.commands.Drive.DriveWithJoystick;
|
||||
import frc4388.robot.commands.Drive.GamerMove;
|
||||
import frc4388.robot.OI;
|
||||
import frc4388.robot.Robot;
|
||||
import frc4388.utility.controller.XboxController;
|
||||
@@ -61,17 +63,14 @@ public class Drive extends Subsystem {
|
||||
m_rightBackMotor.setInverted(InvertType.FollowMaster);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
m_inputMove = OI.getInstance().getDriverController().getLeftYAxis();
|
||||
m_inputSteer = -(OI.getInstance().getDriverController().getRightXAxis());
|
||||
|
||||
m_driveTrain.arcadeDrive(m_inputMove, m_inputSteer);
|
||||
public void driveWithInput(double move, double steer){
|
||||
m_driveTrain.arcadeDrive(move, steer);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initDefaultCommand() {
|
||||
public void initDefaultCommand(){
|
||||
// Set the default command for a subsystem here.
|
||||
// setDefaultCommand(new MySpecialCommand());
|
||||
setDefaultCommand(new DriveWithJoystick());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -8,6 +8,7 @@
|
||||
package frc4388.robot.subsystems;
|
||||
|
||||
import frc4388.robot.RobotMap;
|
||||
import frc4388.robot.commands.LED.UpdateLED;
|
||||
import frc4388.robot.constants.LEDPatterns;
|
||||
import edu.wpi.first.wpilibj.Spark;
|
||||
import edu.wpi.first.wpilibj.command.Subsystem;
|
||||
@@ -27,9 +28,8 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
LEDController.set(currentLED);
|
||||
}
|
||||
|
||||
public void periodic() {
|
||||
public void updateLED(){
|
||||
LEDController.set(currentLED);
|
||||
SmartDashboard.putNumber("LED", currentLED);
|
||||
}
|
||||
|
||||
public void setPattern(LEDPatterns pattern){
|
||||
@@ -37,7 +37,15 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
LEDController.set(currentLED);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic(){
|
||||
SmartDashboard.putNumber("LED", currentLED);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initDefaultCommand() {
|
||||
// Set the default command for a subsystem here.
|
||||
// setDefaultCommand(new MySpecialCommand());
|
||||
setDefaultCommand(new UpdateLED());
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user