Compare commits
10 Commits
Author | SHA1 | Date | |
---|---|---|---|
ebc87707e6 | |||
d50d7e8556 | |||
e04f4ba346 | |||
667a528b98 | |||
089bab94d1 | |||
135f031ae5 | |||
8c6e5ec1b2 | |||
a9ec38808f | |||
4717100d78 | |||
ca5ee1198c |
@ -17,7 +17,7 @@
|
||||
# -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 )
|
||||
GLOB=( src/**/*.java )
|
||||
astyle $OPTS $GLOB|\grep -P '^(?!Unchanged)'
|
||||
astyle $OPTS $GLOB|\grep -vE '^Unchanged'
|
||||
# Get rid of newlines
|
||||
sed -i'' '/^\s*$/d' $GLOB
|
||||
perl -ni'' -e '/^\s*$/ || print' $GLOB
|
||||
\cd ->/dev/null
|
||||
|
@ -1,30 +1,27 @@
|
||||
package org.usfirst.frc.team2059.robot;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
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;
|
||||
/**
|
||||
* 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.
|
||||
*/
|
||||
public class OI {
|
||||
//// CREATING BUTTONS
|
||||
// One type of button is a joystick button which is any button on a joystick.
|
||||
// You create one by telling it which joystick it's on and which button
|
||||
// number it is.
|
||||
// Joystick stick = new Joystick(port);
|
||||
// Button button = new JoystickButton(stick, buttonNumber);
|
||||
// There are a few additional built in buttons you can use. Additionally,
|
||||
// by subclassing Button you can create custom triggers and bind those to
|
||||
// commands the same as any other Button.
|
||||
//// TRIGGERING COMMANDS WITH BUTTONS
|
||||
// Once you have a button, it's trivial to bind it to a button in one of
|
||||
// three ways:
|
||||
// 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.
|
||||
// button.whenPressed(new ExampleCommand());
|
||||
// Run the command while the button is being held down and interrupt it once
|
||||
// the button is released.
|
||||
// button.whileHeld(new ExampleCommand());
|
||||
// Start the command when the button is released and let it run the command
|
||||
// until it is finished as determined by it's isFinished method.
|
||||
// button.whenReleased(new ExampleCommand());
|
||||
JoystickButton[][] joystickButtons;
|
||||
Joystick[] joysticks;
|
||||
public OI() {
|
||||
// Create joysticks
|
||||
joysticks[0] = new Joystick(1);
|
||||
joysticks[1] = new Joystick(2);
|
||||
// Create buttons
|
||||
for (int i = 0; i < 12; i++) {
|
||||
joystickButtons[0][i] = new JoystickButton(joysticks[0], i + 1);
|
||||
joystickButtons[1][i] = new JoystickButton(joysticks[1], i + 1);
|
||||
}
|
||||
// Print log when button 1 pressed
|
||||
joystickButtons[0][0].whenPressed(new LogEncoder());
|
||||
}
|
||||
}
|
||||
// vim: sw=2:ts=2:sts=2
|
||||
|
@ -0,0 +1,9 @@
|
||||
package org.usfirst.frc.team2059.robot.commands;
|
||||
import org.usfirst.frc.team2059.robot.subsystems.DriveBase;
|
||||
import org.usfirst.frc.team2059.robot.subsystems.EncoderBase;
|
||||
import edu.wpi.first.wpilibj.command.Command;
|
||||
public abstract class CommandBase extends Command {
|
||||
protected static EncoderBase encoderBase = new EncoderBase();
|
||||
protected static DriveBase driveBase = new DriveBase();
|
||||
}
|
||||
// vim: sw=2:ts=2:sts=2
|
@ -24,4 +24,4 @@ public class Drive extends Command {
|
||||
protected void interrupted() {
|
||||
}
|
||||
}
|
||||
// vim: sw=2:ts=2:sts=2
|
||||
// vim: sw=2:ts=2:sts=2
|
||||
|
30
src/org/usfirst/frc/team2059/robot/commands/LogEncoder.java
Normal file
30
src/org/usfirst/frc/team2059/robot/commands/LogEncoder.java
Normal file
@ -0,0 +1,30 @@
|
||||
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() {
|
||||
//TODO: Not sure if isFinished() is checked before execute()
|
||||
//assuming it is not,
|
||||
return true;
|
||||
}
|
||||
protected void execute() {
|
||||
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());
|
||||
}
|
||||
protected void end() {
|
||||
}
|
||||
protected void interrupted() {
|
||||
}
|
||||
}
|
||||
// vim: sw=2:ts=2:sts=2
|
@ -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
|
@ -0,0 +1,27 @@
|
||||
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) {
|
||||
}
|
||||
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
|
@ -3,7 +3,7 @@ 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 {
|
||||
public class DriveBase extends Subsystem {
|
||||
CANTalon leftMotorOne = new CANTalon(RobotMap.driveLeftMotorOne);
|
||||
CANTalon leftMotorTwo = new CANTalon(RobotMap.driveLeftMotorTwo);
|
||||
CANTalon rightMotorOne = new CANTalon(RobotMap.driveRightMotorOne);
|
@ -0,0 +1,29 @@
|
||||
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 {
|
||||
Encoder enc = new Encoder(0, 1, false, Encoder.EncodingType.k4X);
|
||||
public void initDefaultCommand() {
|
||||
//TODO: Not sure if we need a default command, not settingo 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
|
Loading…
x
Reference in New Issue
Block a user