Compare commits

..

26 Commits

Author SHA1 Message Date
3128d3e31b
Autoformatted 2016-09-19 12:14:01 -04:00
ian
b9b0ee6628 limit switch moves arm up 2016-09-16 20:52:06 -04:00
ian
16db69d087 limit switch attemp 1 2016-09-16 20:04:15 -04:00
3b1efebba8
Autoformatted 2016-09-16 18:27:04 -04:00
901aa58894 added basic pid distance driving functionality 2016-09-16 17:36:47 +00:00
877b7aaf8d added roller code 2016-09-12 21:42:04 +00:00
670de6a143 move arm stop automatically 2016-09-12 21:06:01 +00:00
3f55c7b2b8 added compressor code 2016-09-12 20:04:15 +00:00
e7f3b43157 assigned presets to buttons 2016-09-12 15:23:00 -04:00
0108b984b1 updated pid values and added setpoint 2016-09-12 15:01:15 -04:00
18ff5daaad fixed pot conversion code 2016-09-12 14:15:10 -04:00
fe6dce9640 converted to pidsubsystem, builds but pottodegrees doesn't work 2016-09-11 20:47:05 -04:00
35b756efa4 assigned movearm to buttons 2016-09-11 23:34:20 +00:00
1542373e40 added arm code. probably wont work 2016-09-07 19:06:43 -04:00
77ae642c9b
Robot now drives and the encoder almost works 2016-07-23 23:20:38 -04:00
b326e64087
Ignore sysprops.xml, write drive code 2016-07-23 14:18:09 -04:00
ebc87707e6
Remove incorrectly cased files 2016-07-22 16:49:11 -04:00
d50d7e8556 Possible case issue fix 2016-07-22 16:46:56 -04:00
e04f4ba346 Use proper case with EncoderBase and DriveBase 2016-07-22 16:35:32 -04:00
667a528b98 Implemented LogEncoder 2016-07-22 16:29:38 -04:00
089bab94d1 Implemented CommandBase, hopefully more correct than before 2016-07-22 16:19:11 -04:00
135f031ae5 Fix grep issue on non -P enabled grep 2016-07-22 15:36:27 -04:00
8c6e5ec1b2 Autoformatted 2016-07-22 15:36:16 -04:00
a9ec38808f Fix sed issue on non gnu sed computers by using perl 2016-07-22 15:35:20 -04:00
4717100d78 Create LogEncoder and map j1b1 to start logging and j1b2 to stop logging 2016-07-22 15:28:06 -04:00
ca5ee1198c Added base encoder code 2016-07-22 13:07:03 -04:00
31 changed files with 633 additions and 112 deletions

View File

@ -1,7 +1,8 @@
<?xml version="1.0" encoding="UTF-8"?>
<classpath> <classpath>
<classpathentry kind="src" path="src"/> <classpathentry kind="src" path="src"/>
<classpathentry kind="var" path="wpilib" sourcepath="wpilib.sources"/> <classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER"/>
<classpathentry kind="var" path="networktables" sourcepath="networktables.sources"/> <classpathentry kind="lib" path="~/wpilib/java/current/lib/WPILib.jar"/>
<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER/org.eclipse.jdt.internal.debug.ui.launcher.StandardVMType/JavaSE-1.8"/> <classpathentry kind="lib" path="~/wpilib/java/current/lib/NetworkTables.jar"/>
<classpathentry kind="output" path="bin"/> <classpathentry kind="output" path="bin"/>
</classpath> </classpath>

1
.gitignore vendored
View File

@ -1,3 +1,4 @@
dist/FRCUserProgram.jar dist/FRCUserProgram.jar
build build
bin bin
sysProps.xml

View File

@ -17,7 +17,7 @@
# -H : Pad header (space after if, for, while) # -H : Pad header (space after if, for, while)
OPTS=( --mode=java -xc --style=google -j -s2 -xG -S -K -N -xn -xl -n -p -H ) OPTS=( --mode=java -xc --style=google -j -s2 -xG -S -K -N -xn -xl -n -p -H )
GLOB=( src/**/*.java ) GLOB=( src/**/*.java )
astyle $OPTS $GLOB|\grep -P '^(?!Unchanged)' astyle $OPTS $GLOB|\grep -vE '^Unchanged'
# Get rid of newlines # Get rid of newlines
sed -i'' '/^\s*$/d' $GLOB perl -ni'' -e '/^\s*$/ || print' $GLOB
\cd ->/dev/null \cd ->/dev/null

Binary file not shown.

Binary file not shown.

View File

@ -1,30 +1,56 @@
package org.usfirst.frc.team2059.robot; package org.usfirst.frc.team2059.robot;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.buttons.Button; import edu.wpi.first.wpilibj.buttons.Button;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.buttons.JoystickButton;
import org.usfirst.frc.team2059.robot.commands.LogEncoder;
import org.usfirst.frc.team2059.robot.commands.PIDDrive;
import org.usfirst.frc.team2059.robot.commands.MoveArm;
import org.usfirst.frc.team2059.robot.commands.SetArmPosition;
import org.usfirst.frc.team2059.robot.commands.SetShooterState;
import org.usfirst.frc.team2059.robot.commands.SetArmStopState;
import org.usfirst.frc.team2059.robot.commands.ShootAtSpeed;
import org.usfirst.frc.team2059.robot.commands.SpinRollers;
import org.usfirst.frc.team2059.robot.RobotMap;
/** /**
* This class is the glue that binds the controls on the physical operator * This class is the glue that binds the controls on the physical operator
* interface to the commands and command groups that allow control of the robot. * interface to the commands and command groups that allow control of the robot.
*/ */
public class OI { public class OI {
//// CREATING BUTTONS JoystickButton[][] joystickButtons;
// One type of button is a joystick button which is any button on a joystick. Joystick[] joysticks;
// You create one by telling it which joystick it's on and which button public OI() {
// number it is. joysticks = new Joystick[2];
// Joystick stick = new Joystick(port); joystickButtons = new JoystickButton[2][13];
// Button button = new JoystickButton(stick, buttonNumber); // Create joysticks
// There are a few additional built in buttons you can use. Additionally, joysticks[0] = new Joystick(0);
// by subclassing Button you can create custom triggers and bind those to joysticks[1] = new Joystick(1);
// commands the same as any other Button. // Create buttons
//// TRIGGERING COMMANDS WITH BUTTONS for (int i = 0; i < 12; i++) {
// Once you have a button, it's trivial to bind it to a button in one of joystickButtons[0][i] = new JoystickButton(joysticks[0], i + 1);
// three ways: joystickButtons[1][i] = new JoystickButton(joysticks[1], i + 1);
// Start the command when the button is pressed and let it run the command }
// until it is finished as determined by it's isFinished method. // Print log when button 1 pressed
// button.whenPressed(new ExampleCommand()); //joystickButtons[0][0].whenPressed(new LogEncoder());
// Run the command while the button is being held down and interrupt it once joystickButtons[0][0].whileHeld(new SpinRollers(1));
// the button is released. joystickButtons[0][1].whileHeld(new SetShooterState(true));
// button.whileHeld(new ExampleCommand()); // joystickButtons[0][2].whileHeld(new PIDDrive(400));
// Start the command when the button is released and let it run the command joystickButtons[1][0].whileHeld(new MoveArm(0.5));
// until it is finished as determined by it's isFinished method. joystickButtons[1][1].whileHeld(new MoveArm(-0.5));
// button.whenReleased(new ExampleCommand()); joystickButtons[1][2].whileHeld(new SetArmPosition(RobotMap.mainArmPresetCollect));
joystickButtons[1][3].whileHeld(new SetArmPosition(RobotMap.mainArmPresetTraverse));
joystickButtons[1][4].whileHeld(new SetArmPosition(RobotMap.mainArmPresetCloseShot));
joystickButtons[1][5].whileHeld(new SetArmPosition(RobotMap.mainArmPresetFarShot));
joystickButtons[1][7].whileHeld(new SetArmStopState(true));
}
public Joystick[] getJoysticks() {
return joysticks;
}
public Joystick getJoystick(int stick) {
return joysticks[stick];
}
public JoystickButton[][] getJoystickButtons() {
return joystickButtons;
}
} }
// vim: sw=2:ts=2:sts=2 // vim: sw=2:ts=2:sts=2

View File

@ -1,91 +1,55 @@
package org.usfirst.frc.team2059.robot; package org.usfirst.frc.team2059.robot;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import edu.wpi.first.wpilibj.IterativeRobot; import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.command.Command; import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler; import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/**
* The VM is configured to automatically run this class, and to call the
* functions corresponding to each mode, as described in the IterativeRobot
* documentation. If you change the name of this class or the package after
* creating this project, you must also update the manifest file in the resource
* directory.
*/
public class Robot extends IterativeRobot { public class Robot extends IterativeRobot {
public static OI oi; public static OI oi;
Command autonomousCommand; Command autonomousCommand;
SendableChooser chooser; SendableChooser chooser;
/**
* This function is run when the robot is first started up and should be
* used for any initialization code.
*/
public void robotInit() { public void robotInit() {
CommandBase.init();
oi = new OI(); oi = new OI();
chooser = new SendableChooser(); chooser = new SendableChooser();
// chooser.addObject("My Auto", new MyAutoCommand());
SmartDashboard.putData("Auto mode", chooser); SmartDashboard.putData("Auto mode", chooser);
SmartDashboard.putData("MainArm", CommandBase.mainArm.getPIDController());
SmartDashboard.putData("LeftEncoderController", CommandBase.driveBase.getLeftController());
SmartDashboard.putBoolean("CompressorEnabled", true);
//Automatically determine if rolling in or rolling out
SmartDashboard.putBoolean("SmartRollers", true);
} }
/**
* This function is called once each time the robot enters Disabled mode.
* You can use it to reset any subsystem information you want to clear when
* the robot is disabled.
*/
public void disabledInit() { public void disabledInit() {
} }
public void disabledPeriodic() { public void disabledPeriodic() {
Scheduler.getInstance().run(); Scheduler.getInstance().run();
} }
/**
* This autonomous (along with the chooser code above) shows how to select between different autonomous modes
* using the dashboard. The sendable chooser code works with the Java SmartDashboard. If you prefer the LabVIEW
* Dashboard, remove all of the chooser code and uncomment the getString code to get the auto name from the text box
* below the Gyro
*
* You can add additional auto modes by adding additional commands to the chooser code above (like the commented example)
* or additional comparisons to the switch structure below with additional strings & commands.
*/
public void autonomousInit() { public void autonomousInit() {
autonomousCommand = (Command) chooser.getSelected(); autonomousCommand = (Command) chooser.getSelected();
/* String autoSelected = SmartDashboard.getString("Auto Selector", "Default");
switch(autoSelected) {
case "My Auto":
autonomousCommand = new MyAutoCommand();
break;
case "Default Auto":
default:
autonomousCommand = new ExampleCommand();
break;
} */
// schedule the autonomous command (example)
if (autonomousCommand != null) { if (autonomousCommand != null) {
autonomousCommand.start(); autonomousCommand.start();
} }
} }
/**
* This function is called periodically during autonomous
*/
public void autonomousPeriodic() { public void autonomousPeriodic() {
Scheduler.getInstance().run(); Scheduler.getInstance().run();
} }
public void teleopInit() { public void teleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (autonomousCommand != null) { if (autonomousCommand != null) {
autonomousCommand.cancel(); autonomousCommand.cancel();
} }
CommandBase.pneumatics.setCompressorEnabled(true);
CommandBase.pneumatics.setArmStopState(false);
} }
/**
* This function is called periodically during operator control
*/
public void teleopPeriodic() { public void teleopPeriodic() {
Scheduler.getInstance().run(); Scheduler.getInstance().run();
SmartDashboard.putNumber("ArmAngleRaw", CommandBase.mainArm.getRaw());
SmartDashboard.putNumber("ArmAngleDegrees", CommandBase.mainArm.getDegrees());
SmartDashboard.putNumber("tmpRotations", CommandBase.driveBase.getLeftRotations());
CommandBase.pneumatics.setCompressorEnabled(SmartDashboard.getBoolean("CompressorEnabled"));
System.out.println(CommandBase.mainArm.getDegrees());
} }
/**
* This function is called periodically during test mode
*/
public void testPeriodic() { public void testPeriodic() {
LiveWindow.run(); LiveWindow.run();
} }

View File

@ -3,13 +3,15 @@ public class RobotMap {
//Drive //Drive
public static int driveLeftMotorOne = 1; public static int driveLeftMotorOne = 1;
public static int driveLeftMotorTwo = 2; public static int driveLeftMotorTwo = 2;
public static int driveRightMotorOne = 1; public static int driveRightMotorOne = 3;
public static int driveRightMotorTwo = 2; public static int driveRightMotorTwo = 4;
public static int driveRightEncoder = 0; public static int driveLeftEncoderA = 0;
public static int driveLeftEncoder = 1; public static int driveLeftEncoderB = 1;
//Arm //Arm
public static double zeroDegrees = 0.1; public static double zeroDegrees = 2.019;
public static double ninetyDegrees = 0.7; public static double ninetyDegrees = 3.512;
public static int armBottomLim = 4;
public static int armTopLim = 5;
public static int armPot = 0; public static int armPot = 0;
public static int armLeftMotor = 5; public static int armLeftMotor = 5;
public static int armRightMotor = 6; public static int armRightMotor = 6;
@ -25,9 +27,9 @@ public class RobotMap {
public static int armStopSolenoidOne = 4; public static int armStopSolenoidOne = 4;
public static int armStopSolenoidTwo = 5; public static int armStopSolenoidTwo = 5;
//Misc //Misc
public static int mainArmPresetCollect = 0; public static int mainArmPresetCollect = -5;
public static int mainArmPresetTraverse = 5; public static int mainArmPresetTraverse = 11;
public static int mainArmPresetCloseShot = 95; public static int mainArmPresetCloseShot = 90;
public static int mainArmPresetFarShot = 85; public static int mainArmPresetFarShot = 70;
} }
// vim: sw=2:ts=2:sts=2 // vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,22 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.subsystems.DriveBase;
import org.usfirst.frc.team2059.robot.subsystems.EncoderBase;
import org.usfirst.frc.team2059.robot.subsystems.MainArm;
import org.usfirst.frc.team2059.robot.subsystems.Pneumatics;
import org.usfirst.frc.team2059.robot.subsystems.Shooter;
import edu.wpi.first.wpilibj.command.Command;
public abstract class CommandBase extends Command {
public static EncoderBase encoderBase;
public static DriveBase driveBase;
public static MainArm mainArm;
public static Pneumatics pneumatics;
public static Shooter shooter;
public static void init() {
encoderBase = new EncoderBase();
driveBase = new DriveBase();
mainArm = new MainArm();
pneumatics = new Pneumatics();
shooter = new Shooter();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -1,16 +1,22 @@
package org.usfirst.frc.team2059.robot.commands; package org.usfirst.frc.team2059.robot.commands;
import edu.wpi.first.wpilibj.command.Command; import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
/** /**
* *
*/ */
public class Drive extends Command { public class Drive extends CommandBase {
public Drive() { public Drive() {
requires(driveBase);
} }
// Called just before this Command runs the first time // Called just before this Command runs the first time
protected void initialize() { protected void initialize() {
} }
// Called repeatedly when this Command is scheduled to run // Called repeatedly when this Command is scheduled to run
protected void execute() { protected void execute() {
double x = Robot.oi.getJoysticks()[0].getRawAxis(0);
double y = Robot.oi.getJoysticks()[0].getRawAxis(1);
double z = Robot.oi.getJoysticks()[0].getRawAxis(2);
driveBase.driveArcade(x, y, z, 0);
} }
// Make this return true when this Command no longer needs to run execute() // Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() { protected boolean isFinished() {

View File

@ -0,0 +1,28 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.structs.EncoderValues;
public class LogEncoder extends CommandBase {
public LogEncoder() {
requires(encoderBase);
}
protected void initialize() {
}
protected boolean isFinished() {
EncoderValues values = encoderBase.getValues();
System.out.println("==== Encoder log ====");
System.out.println("Count : " + values.getCount());
System.out.println("Distance : " + values.getDistance());
System.out.println("Period : " + values.getPeriod());
System.out.println("Rate : " + values.getRate());
System.out.println("Direction : " + values.getDirection());
System.out.println("Stopped : " + values.getStopped());
return true;
}
protected void execute() {
}
protected void end() {
}
protected void interrupted() {
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,36 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
/**
*
*/
public class MoveArm extends CommandBase {
double speed;
public MoveArm(double s) {
requires(mainArm);
speed = s;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
mainArm.disable();
mainArm.moveArm(speed);
System.out.println(speed);
}
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}
// Called once after isFinished returns true
protected void end() {
mainArm.moveArm(0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,32 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
/**
*
*/
public class PIDDrive extends CommandBase {
double count;
public PIDDrive(double c) {
requires(driveBase);
count = c;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
driveBase.pidDrive(count);
}
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}
// Called once after isFinished returns true
protected void end() {
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,20 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
public class ResetEncoder extends CommandBase {
public ResetEncoder() {
requires(encoderBase);
}
protected void initialize() {
}
protected boolean isFinished() {
return true;
}
protected void execute() {
encoderBase.resetEncoder();
}
protected void end() {
}
protected void interrupted() {
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,42 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
import org.usfirst.frc.team2059.robot.RobotMap;
/**
*
*/
public class SetArmPosition extends CommandBase {
double pos;
public SetArmPosition(double p) {
requires(mainArm);
pos = p;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
//Move the arm stop
if (pos == RobotMap.mainArmPresetCollect) {
pneumatics.setArmStopState(true);
} else if ((pos != RobotMap.mainArmPresetCollect) && (mainArm.getDegrees() > 2)) {
pneumatics.setArmStopState(false);
}
mainArm.enable();
mainArm.setSetpoint(pos);
}
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}
// Called once after isFinished returns true
protected void end() {
mainArm.disable();
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,33 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
/**
*
*/
public class SetArmStopState extends CommandBase {
boolean state;
public SetArmStopState(boolean s) {
state = s;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
pneumatics.setArmStopState(state);
}
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}
// Called once after isFinished returns true
protected void end() {
pneumatics.setArmStopState(!state);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,33 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
/**
*
*/
public class SetShooterState extends CommandBase {
boolean state;
public SetShooterState(boolean s) {
state = s;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
pneumatics.setShooterState(state);
}
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}
// Called once after isFinished returns true
protected void end() {
pneumatics.setShooterState(!state);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,34 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
import org.usfirst.frc.team2059.robot.RobotMap;
/**
*
*/
public class ShootAtSpeed extends CommandBase {
double speed;
public ShootAtSpeed(double s) {
speed = s;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
shooter.shootAtSpeed(speed);
}
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}
// Called once after isFinished returns true
protected void end() {
shooter.shootAtSpeed(0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,38 @@
package org.usfirst.frc.team2059.robot.commands;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
/**
*
*/
public class SpinRollers extends CommandBase {
double speed;
public SpinRollers(double s) {
speed = s;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
if (SmartDashboard.getBoolean("SmartRollers") && mainArm.getDegrees() < 5) {
shooter.shootAtSpeed(-.5);
} else {
shooter.shootAtSpeed(speed);
}
}
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}
// Called once after isFinished returns true
protected void end() {
shooter.shootAtSpeed(0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,33 @@
package org.usfirst.frc.team2059.robot.structs;
public class EncoderValues {
private int count;
private double distance, period, rate;
private boolean direction, stopped;
public EncoderValues(int count, double distance, double period, double rate, boolean direction, boolean stopped) {
this.count = count;
this.distance = distance;
this.period = period;
this.rate = rate;
this.direction = direction;
this.stopped = stopped;
}
public int getCount() {
return count;
}
public double getDistance() {
return distance;
}
public double getPeriod() {
return period;
}
public double getRate() {
return rate;
}
public boolean getDirection() {
return direction;
}
public boolean getStopped() {
return stopped;
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,46 @@
package org.usfirst.frc.team2059.robot.subsystems;
import org.usfirst.frc.team2059.robot.RobotMap;
import org.usfirst.frc.team2059.robot.commands.Drive;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.PIDController;
import edu.wpi.first.wpilibj.PIDOutput;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.CANTalon;
public class DriveBase extends Subsystem {
CANTalon leftMotorOne = new CANTalon(RobotMap.driveLeftMotorOne);
CANTalon leftMotorTwo = new CANTalon(RobotMap.driveLeftMotorTwo);
CANTalon rightMotorOne = new CANTalon(RobotMap.driveRightMotorOne);
CANTalon rightMotorTwo = new CANTalon(RobotMap.driveRightMotorTwo);
Encoder leftEncoder = new Encoder(RobotMap.driveLeftEncoderA, RobotMap.driveLeftEncoderB, false, Encoder.EncodingType.k2X);
PIDController leftEncoderController = new PIDController(0.02, 0.002, 0.017, leftEncoder, new MotorsPIDOutput());
public void initDefaultCommand() {
setDefaultCommand(new Drive());
}
public void driveArcade(double x, double y, double z, double sensitivity) {
leftMotorOne.set(-y + (x + z));
leftMotorTwo.set(-y + (x + z));
rightMotorOne.set(y + (x + z));
rightMotorTwo.set(y + (x + z));
}
public void pidDrive(double setpoint) {
leftEncoder.reset();
leftEncoderController.enable();
leftEncoderController.setSetpoint(setpoint);
}
public PIDController getLeftController() {
return leftEncoderController;
}
public double getLeftRotations() {
return leftEncoder.get();
}
public class MotorsPIDOutput implements PIDOutput {
@Override
public void pidWrite(double output) {
leftMotorOne.pidWrite(output);
leftMotorTwo.pidWrite(output);
rightMotorOne.pidWrite(-output);
rightMotorTwo.pidWrite(-output);
}
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -1,21 +0,0 @@
package org.usfirst.frc.team2059.robot.subsystems;
import org.usfirst.frc.team2059.robot.RobotMap;
import org.usfirst.frc.team2059.robot.commands.Drive;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.CANTalon;
public class Drivebase extends Subsystem {
CANTalon leftMotorOne = new CANTalon(RobotMap.driveLeftMotorOne);
CANTalon leftMotorTwo = new CANTalon(RobotMap.driveLeftMotorTwo);
CANTalon rightMotorOne = new CANTalon(RobotMap.driveRightMotorOne);
CANTalon rightMotorTwo = new CANTalon(RobotMap.driveRightMotorOne);
public void initDefaultCommand() {
setDefaultCommand(new Drive());
}
public void driveArcade(double x, double y, double z, double sensitivity) {
leftMotorOne.set(-y + (x + z));
leftMotorTwo.set(-y + (x + z));
rightMotorOne.set(y + (x + z));
rightMotorTwo.set(y + (x + z));
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,33 @@
package org.usfirst.frc.team2059.robot.subsystems;
import org.usfirst.frc.team2059.robot.RobotMap;
import org.usfirst.frc.team2059.robot.commands.Drive;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.Encoder;
import org.usfirst.frc.team2059.robot.structs.EncoderValues;
public class EncoderBase extends Subsystem {
//TODO: Might not need a constructor
public EncoderBase() {
}
//Encoder enc = new Encoder(0, 1, false, Encoder.EncodingType.k1X);
Encoder enc = new Encoder(8, 9);
public void initDefaultCommand() {
//TODO: Not sure if we need a default command, not setting one
//TODO: These are just defaults, they wil lneed to be changed
//enc.setMaxPeriod(.1);
//enc.setMinRate(10);
//enc.setDistancePerPulse(5);
//enc.setReverseDirection(false);
//enc.setSamplesToAverage(7);
}
public void resetEncoder() {
enc.reset();
}
public EncoderValues getValues() {
//TODO: There are two ways to get distance:
//enc.getDistance();
//enc.getRaw();
//figure out which to use
return new EncoderValues(enc.get() , enc.getRaw() , enc.getPeriod() , enc.getRate() , enc.getDirection() , enc.getStopped());
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,54 @@
package org.usfirst.frc.team2059.robot.subsystems;
import org.usfirst.frc.team2059.robot.RobotMap;
import org.usfirst.frc.team2059.robot.commands.Drive;
import edu.wpi.first.wpilibj.command.PIDSubsystem;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.AnalogInput;
public class MainArm extends PIDSubsystem {
CANTalon armMotorLeft = new CANTalon(RobotMap.armLeftMotor);
CANTalon armMotorRight = new CANTalon(RobotMap.armRightMotor);
AnalogInput pot = new AnalogInput(RobotMap.armPot);
DigitalInput limitSwitchBottom = new DigitalInput(RobotMap.armBottomLim);
DigitalInput limitSwitchTop = new DigitalInput(RobotMap.armTopLim);
public MainArm() {
super("MainArm", 0.06, 0.0, 0.002);
getPIDController().setContinuous(false);
setSetpoint(RobotMap.mainArmPresetTraverse);
enable();
}
public void initDefaultCommand() {
}
public void moveArm(double speed) {
armMotorLeft.set(-speed);
armMotorRight.set(speed);
}
protected double returnPIDInput() {
return getDegrees();
}
protected void usePIDOutput(double output) {
armMotorLeft.set(-output);
armMotorRight.set(output);
}
public double getRaw() {
return pot.getAverageVoltage();
}
public double getDegrees() {
return potToDegrees(getRaw());
}
private double potToDegrees(double pot) {
System.out.println(limitSwitchBottom.get());
if (!limitSwitchBottom.get()) {
RobotMap.zeroDegrees = getRaw();
System.out.println("====Bottom Switch====\n" + getRaw());
} else if (!limitSwitchTop.get()) {
RobotMap.ninetyDegrees = getRaw();
System.out.println("====Top Switch====\n" + getRaw());
}
double min = RobotMap.zeroDegrees;
double max = RobotMap.ninetyDegrees;
System.out.println((pot - min) / (Math.abs(min - max) / 90));
return (pot - min) / (Math.abs(min - max) / 90);
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,43 @@
package org.usfirst.frc.team2059.robot.subsystems;
import org.usfirst.frc.team2059.robot.RobotMap;
import org.usfirst.frc.team2059.robot.commands.Drive;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.DoubleSolenoid;
public class Pneumatics extends Subsystem {
Compressor compressor = new Compressor(RobotMap.pcmID);
DoubleSolenoid shooterSolenoid = new DoubleSolenoid(RobotMap.pcmID, RobotMap.shooterSolenoidOne, RobotMap.shooterSolenoidTwo);
DoubleSolenoid armStopSolenoid = new DoubleSolenoid(RobotMap.pcmID, RobotMap.armStopSolenoidOne, RobotMap.armStopSolenoidTwo);
boolean shooterState, armStopState;
public void initDefaultCommand() {
}
public void setCompressorEnabled(boolean state) {
compressor.setClosedLoopControl(state);
}
public void setShooterState(boolean state) {
if (state) {
shooterSolenoid.set(DoubleSolenoid.Value.kForward);
} else {
shooterSolenoid.set(DoubleSolenoid.Value.kReverse);
}
shooterState = state;
}
public void setArmStopState(boolean state) {
if (state) {
armStopSolenoid.set(DoubleSolenoid.Value.kForward);
} else {
armStopSolenoid.set(DoubleSolenoid.Value.kReverse);
}
armStopState = state;
}
public boolean getShooterState() {
return shooterState;
}
public boolean getArmStopState() {
return armStopState;
}
public boolean getCompressorEnabled() {
return compressor.enabled();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,15 @@
package org.usfirst.frc.team2059.robot.subsystems;
import org.usfirst.frc.team2059.robot.RobotMap;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.CANTalon;
public class Shooter extends Subsystem {
CANTalon shooterMotorLeft = new CANTalon(RobotMap.shooterLeftMotor);
CANTalon shooterMotorRight = new CANTalon(RobotMap.shooterRightMotor);
public void initDefaultCommand() {
}
public void shootAtSpeed(double speed) {
shooterMotorRight.set(speed);
shooterMotorLeft.set(speed);
}
}
// vim: sw=2:ts=2:sts=2