Robot now drives and the encoder almost works

This commit is contained in:
Austen Adler 2016-07-23 23:20:32 -04:00
parent b326e64087
commit 77ae642c9b
No known key found for this signature in database
GPG Key ID: 7ECEE590CCDFE3F1
10 changed files with 45 additions and 27 deletions

View File

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

View File

@ -12,9 +12,11 @@ public class OI {
JoystickButton[][] joystickButtons;
Joystick[] joysticks;
public OI() {
joysticks = new Joystick[2];
joystickButtons = new JoystickButton[2][13];
// Create joysticks
joysticks[0] = new Joystick(1);
joysticks[1] = new Joystick(2);
joysticks[0] = new Joystick(0);
joysticks[1] = new Joystick(1);
// Create buttons
for (int i = 0; i < 12; i++) {
joystickButtons[0][i] = new JoystickButton(joysticks[0], i + 1);
@ -26,6 +28,9 @@ public class OI {
public Joystick[] getJoysticks() {
return joysticks;
}
public Joystick getJoystick(int stick) {
return joysticks[stick];
}
public JoystickButton[][] getJoystickButtons() {
return joystickButtons;
}

View File

@ -1,4 +1,5 @@
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.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;
@ -10,6 +11,7 @@ public class Robot extends IterativeRobot {
Command autonomousCommand;
SendableChooser chooser;
public void robotInit() {
CommandBase.init();
oi = new OI();
chooser = new SendableChooser();
SmartDashboard.putData("Auto mode", chooser);

View File

@ -1,10 +1,10 @@
package org.usfirst.frc.team2059.robot;
public class RobotMap {
//Drive
public static int driveLeftMotorOne = 1;
public static int driveLeftMotorTwo = 2;
public static int driveRightMotorOne = 3;
public static int driveRightMotorTwo = 4;
public static int driveLeftMotorOne = 0;
public static int driveLeftMotorTwo = 1;
public static int driveRightMotorOne = 2;
public static int driveRightMotorTwo = 3;
public static int driveRightEncoder = 0;
public static int driveLeftEncoder = 1;
//Arm

View File

@ -3,7 +3,11 @@ 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();
protected static EncoderBase encoderBase;
protected static DriveBase driveBase;
public static void init() {
encoderBase = new EncoderBase();
driveBase = new DriveBase();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -6,6 +6,7 @@ import org.usfirst.frc.team2059.robot.Robot;
*/
public class Drive extends CommandBase {
public Drive() {
requires(driveBase);
}
// Called just before this Command runs the first time
protected void initialize() {
@ -15,9 +16,6 @@ public class Drive extends CommandBase {
double x = Robot.oi.getJoysticks()[0].getRawAxis(0);
double y = Robot.oi.getJoysticks()[0].getRawAxis(1);
double z = Robot.oi.getJoysticks()[0].getRawAxis(2);
System.out.println("x: "+x);
System.out.println("y: "+y);
System.out.println("z: "+z);
driveBase.driveArcade(x, y, z, 0);
}
// Make this return true when this Command no longer needs to run execute()

View File

@ -8,11 +8,6 @@ public class LogEncoder extends CommandBase {
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());
@ -21,6 +16,9 @@ public class LogEncoder extends CommandBase {
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() {
}

View File

@ -4,6 +4,12 @@ public class EncoderValues {
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;

View File

@ -7,7 +7,7 @@ public class DriveBase extends Subsystem {
Talon leftMotorOne = new Talon(RobotMap.driveLeftMotorOne);
Talon leftMotorTwo = new Talon(RobotMap.driveLeftMotorTwo);
Talon rightMotorOne = new Talon(RobotMap.driveRightMotorOne);
Talon rightMotorTwo = new Talon(RobotMap.driveRightMotorOne);
Talon rightMotorTwo = new Talon(RobotMap.driveRightMotorTwo);
public void initDefaultCommand() {
setDefaultCommand(new Drive());
}

View File

@ -5,15 +5,19 @@ 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);
//TODO: Might not need a constructor
public EncoderBase() {
}
//Encoder enc = new Encoder(0, 1, false, Encoder.EncodingType.k1X);
Encoder enc = new Encoder(0, 1);
public void initDefaultCommand() {
//TODO: Not sure if we need a default command, not settingo one
//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);
//enc.setMaxPeriod(.1);
//enc.setMinRate(10);
//enc.setDistancePerPulse(5);
//enc.setReverseDirection(false);
//enc.setSamplesToAverage(7);
}
public void resetEncoder() {
enc.reset();