Skip to content

Commit

Permalink
Added buttons and stuff for delrin pilot practice
Browse files Browse the repository at this point in the history
  • Loading branch information
frc3316 committed Feb 2, 2016
1 parent 73173f3 commit 70ad3ee
Show file tree
Hide file tree
Showing 6 changed files with 88 additions and 13 deletions.
2 changes: 1 addition & 1 deletion Config2016/src/Config.java
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ private void initConfig()
addToVariables("chassis_TankDrive_DeadBand", 0.05);

addToVariables("chassis_TankDrive_InvertX", false);
addToVariables("chassis_TankDrive_InvertY", true);
addToVariables("chassis_TankDrive_InvertY", false);
}

}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
package org.usfirst.frc.team3316.robot.commands.intake;

import org.usfirst.frc.team3316.robot.commands.DBugCommand;

public class ToggleIntake extends DBugCommand
{
private static boolean set = true;

private static DBugCommand close, open;

static
{
close = new CloseIntake();
open = new OpenIntake();
}

protected void init()
{

}

protected void execute()
{
if (set)
{
open.start();
}
else
{
close.start();
}

set = !set;
}

protected boolean isFinished()
{
return true;
}

protected void fin()
{

}

protected void interr()
{
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,16 @@
package org.usfirst.frc.team3316.robot.humanIO;

import org.usfirst.frc.team3316.robot.Robot;
import org.usfirst.frc.team3316.robot.commands.intake.RollIn;
import org.usfirst.frc.team3316.robot.commands.intake.RollOut;
import org.usfirst.frc.team3316.robot.commands.intake.ToggleIntake;
import org.usfirst.frc.team3316.robot.config.Config;
import org.usfirst.frc.team3316.robot.config.Config.ConfigException;
import org.usfirst.frc.team3316.robot.logger.DBugLogger;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.buttons.Button;
import edu.wpi.first.wpilibj.buttons.JoystickButton;

public class Joysticks
{
Expand Down Expand Up @@ -59,7 +63,13 @@ public Joysticks()
*/
public void initButtons()
{
// TODO: We can start configuring buttons for driver commands (will be
// useful for testing code when we will need it)
JoystickButton btn2 = new JoystickButton(joystickOperator, 2);
JoystickButton btn3 = new JoystickButton(joystickOperator, 3);

btn2.whileHeld(new RollIn());
btn3.whileHeld(new RollOut());

JoystickButton intakeButton = new JoystickButton(joystickOperator, 1);
intakeButton.whenPressed(new ToggleIntake());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,8 @@ private void initSDB ()
putConfigVariableInSDB("intake_RollIn_Speed");
putConfigVariableInSDB("intake_RollOut_Speed");

putConfigVariableInSDB("chassis_TankDrive_InvertY");

/*
* For testing
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,16 @@

import edu.wpi.first.wpilibj.*;

public class Chassis extends DBugSubsystemCC
public class Chassis extends DBugSubsystem
{

// Actuators
private DBugSpeedController leftMotor1, rightMotor2, leftMotor2,
rightMotor1;

// Sensors
private AHRS navx; // For the navX
private Encoder leftEncoder;
private Encoder rightEncoder;

// Variables
private boolean isOnDefense = false; // For the navX
Expand All @@ -44,14 +45,6 @@ public Chassis()
leftMotor2 = Robot.actuators.leftChassis2;
rightMotor1 = Robot.actuators.rightChassis1;

addSpeedController(leftMotor1);
addSpeedController(leftMotor2);
addSpeedController(rightMotor1);
addSpeedController(rightMotor2);

// Sensors
navx = Robot.sensors.navx;

// Create moving average
movingAvg = new MovingAverage(
(int) config.get("CHASSIS_ANGLE_MOVING_AVG_SIZE"), 20, () ->
Expand Down Expand Up @@ -123,4 +116,25 @@ public double getPitch()
{
return navx.getRoll();
}

public double getLeftSpeed()
{
return leftEncoder.getRate(); // Returns the speed in meter per
// second units.
}

public double getRightSpeed()
{
return rightEncoder.getRate(); // Returns the speed in meter per
// second units.
}

public double getDistance() {
return (rightEncoder.getDistance() + leftEncoder.getDistance()) / 2;
}

public void resetEncoders() {
rightEncoder.reset();
leftEncoder.reset();
}
}
Binary file modified Robot Code/sysProps.xml
Binary file not shown.

0 comments on commit 70ad3ee

Please sign in to comment.