Skip to content
This repository has been archived by the owner on Sep 11, 2018. It is now read-only.

Commit

Permalink
Merged release/v0.0.2 into master
Browse files Browse the repository at this point in the history
  • Loading branch information
edwanvi committed Feb 18, 2017
2 parents 24bd2d4 + 9c1b30c commit 3d342dc
Show file tree
Hide file tree
Showing 110 changed files with 4,762 additions and 526 deletions.
11 changes: 10 additions & 1 deletion 3494_2017_repo/src/org/usfirst/frc/team3494/robot/OI.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
package org.usfirst.frc.team3494.robot;

import org.usfirst.frc.team3494.robot.commands.auto.AngleTurn;
import org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive;
import org.usfirst.frc.team3494.robot.commands.intake.SwitchPosition;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
Expand Down Expand Up @@ -41,8 +43,15 @@ public class OI {
// until it is finished as determined by it's isFinished method.
// button.whenReleased(new ExampleCommand());
public JoystickButton xbox_a = new JoystickButton(xbox, 1);
public JoystickButton xbox_lt = new JoystickButton(xbox, 5);
public JoystickButton xbox_rt = new JoystickButton(xbox, 6);
public JoystickButton xbox_b = new JoystickButton(xbox, 2);
public JoystickButton xbox_y = new JoystickButton(xbox, 4);
public JoystickButton xbox_x = new JoystickButton(xbox, 3);

public OI() {
xbox_a.whenPressed(new DistanceDrive(8.0, UnitTypes.INCHES));
xbox_b.whenPressed(new SwitchPosition());
xbox_y.whenPressed(new AngleTurn(90));
xbox_x.whenPressed(new DistanceDrive(2, UnitTypes.FEET));
}
}
32 changes: 28 additions & 4 deletions 3494_2017_repo/src/org/usfirst/frc/team3494/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,16 @@

import org.usfirst.frc.team3494.robot.subsystems.Climber;
import org.usfirst.frc.team3494.robot.subsystems.Drivetrain;
import org.usfirst.frc.team3494.robot.subsystems.Intake;
import org.usfirst.frc.team3494.robot.subsystems.Kompressor;
import org.usfirst.frc.team3494.robot.subsystems.Turret;

import com.kauailabs.navx.frc.AHRS;

import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.PowerDistributionPanel;
import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.SerialPort;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
Expand All @@ -26,7 +31,15 @@ public class Robot extends IterativeRobot {
public static Drivetrain driveTrain;
public static Climber climber;
public static Turret turret;
public static Intake intake;
public static Kompressor kompressor;
/**
* The gyro board mounted to the RoboRIO.
*
* @since 0.0.2
*/
public static AHRS ahrs;
public static PowerDistributionPanel pdp = new PowerDistributionPanel();

Command autonomousCommand;
SendableChooser<Command> chooser = new SendableChooser<>();
Expand All @@ -41,12 +54,14 @@ public void robotInit() {
// chooser.addDefault("Default Auto", new ExampleCommand());
// chooser.addObject("My Auto", new MyAutoCommand());
driveTrain = new Drivetrain();
oi = new OI();
climber = new Climber();
turret = new Turret();
kompressor = new Kompressor();
intake = new Intake();
oi = new OI();
ahrs = new AHRS(SerialPort.Port.kMXP);
// put chooser on DS
SmartDashboard.putData("Auto mode", chooser);
// SmartDashboard.putData("Auto mode", chooser);
// get preferences
prefs = Preferences.getInstance();
}
Expand Down Expand Up @@ -94,7 +109,7 @@ public void autonomousInit() {
}

/**
* This function is called periodically during autonomous
* This function is called periodically during autonomous.
*/
@Override
public void autonomousPeriodic() {
Expand All @@ -112,11 +127,20 @@ public void teleopInit() {
}

/**
* This function is called periodically during operator control
* This function is called periodically during operator control.
*/
@Override
public void teleopPeriodic() {
Scheduler.getInstance().run();
SmartDashboard.putNumber("Gyro Z", ahrs.getAngle());

SmartDashboard.putNumber("Motor 0", Robot.pdp.getCurrent(0));
SmartDashboard.putNumber("Motor 1", Robot.pdp.getCurrent(1));
SmartDashboard.putNumber("Motor 2", Robot.pdp.getCurrent(2));

SmartDashboard.putNumber("Motor 13", Robot.pdp.getCurrent(13));
SmartDashboard.putNumber("Motor 14", Robot.pdp.getCurrent(14));
SmartDashboard.putNumber("Motor 15", Robot.pdp.getCurrent(15));
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ public class RobotMap {
// public static int rangefinderPort = 1;
// public static int rangefinderModule = 1;
// drivetrain left
public static final int leftTalonOne = 0;
public static final int leftTalonOne = 17;
public static final int leftTalonTwo = 1;
public static final int leftTalonThree = 2;
// drivetrain right
Expand All @@ -32,8 +32,8 @@ public class RobotMap {
public static final int ENCODER_RIGHT_A = 0;
public static final int ENCODER_RIGHT_B = 1;
// intake
public static final int INTAKE_MOTOR = 60;
public static final int UP_MOTOR = 65;
public static final int INTAKE_MOTOR = 0;
public static final int UP_MOTOR = 2;
// climber
public static final int CLIMBER_MOTOR = 1;
// turret
Expand All @@ -42,4 +42,6 @@ public class RobotMap {
public static final int TURRET_UPPER = 64;
// compressor
public static final int COMPRESSOR = 0;
public static final int INTAKE_PISTON_CHONE = 2;
public static final int INTAKE_PISTON_CHTWO = 3;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
package org.usfirst.frc.team3494.robot.commands.auto;

import org.usfirst.frc.team3494.robot.Robot;

import edu.wpi.first.wpilibj.command.Command;

/**
* Turns the robot using the gyro board mounted to the RoboRIO. The angle to
* turn by must be specified in the constructor.
*
* @since 0.0.2
* @see org.usfirst.frc.team3494.robot.Robot
* @see org.usfirst.frc.team3494.robot.subsystems.Drivetrain
*/
public class AngleTurn extends Command {

private double angle;
private static double tolerance = Robot.prefs.getDouble("angle tolerance", 2.5);

public AngleTurn(double angle) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.driveTrain);
this.angle = angle;
}

// Called just before this Command runs the first time
protected void initialize() {
Robot.ahrs.reset();
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
if (!((Robot.ahrs.getAngle() > this.angle - tolerance) && (Robot.ahrs.getAngle() < this.angle + tolerance))) {
System.out.println(this.angle);
if (this.angle > 0) {
Robot.driveTrain.adjustedTankDrive(-0.4, 0.4);
Robot.driveTrain.resetRight();
return;
} else if (this.angle < 0) {
Robot.driveTrain.adjustedTankDrive(0.4, -0.4);
Robot.driveTrain.resetRight();
return;
} else {
Robot.driveTrain.adjustedTankDrive(0.4, 0.4);
}
}
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return ((Robot.ahrs.getAngle() > this.angle - tolerance) && (Robot.ahrs.getAngle() < this.angle + tolerance));
}

// 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() {
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
package org.usfirst.frc.team3494.robot.commands.auto;

import org.usfirst.frc.team3494.robot.Robot;
import org.usfirst.frc.team3494.robot.UnitTypes;

import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;

/**
* WIP coordinate drive system.
*
* @see org.usfirst.frc.team3494.robot.commands.auto.AngleTurn
* @see org.usfirst.frc.team3494.robot.commands.auto.DistanceDrive
* @since 0.0.2
*/
public class CartesianTurnDrive extends Command {

private double rise;
private double run;
private double hypot;
private double angle;
private boolean isDone = false;

public CartesianTurnDrive(double rise, double run) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.driveTrain);
this.rise = rise;
this.run = run;
// angle = inverse tan(rise/run)
this.angle = Math.toDegrees(Math.atan2(rise, run));
}

// Called just before this Command runs the first time
protected void initialize() {
Robot.ahrs.reset();
Robot.driveTrain.resetRight();
double run2 = this.run * this.run;
double rise2 = this.rise * this.rise;
this.hypot = Math.sqrt(run2 + rise2);
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Scheduler.getInstance().add(new AngleTurn(this.angle));
Robot.driveTrain.resetRight();
if (Robot.driveTrain.getRightDistance(UnitTypes.INCHES) > this.hypot) {
Robot.driveTrain.adjustedTankDrive(0.3, 0.3);
} else {
this.isDone = true;
}
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return this.isDone;
}

// Called once after isFinished returns true
protected void end() {
this.isDone = false;
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,15 @@
import edu.wpi.first.wpilibj.command.Command;

/**
* Drives a given distance.
* Drives a given distance. Currently suffering from encoder issues.
*
* @see org.usfirst.frc.team3494.robot.subsystems.Drivetrain
* @since 0.0.2
*/
public class DistanceDrive extends Command {
double dist = 0;
UnitTypes unit;

private double dist;
private UnitTypes unit;

public DistanceDrive(double distance, UnitTypes unitType) {
// Use requires() here to declare subsystem dependencies
Expand All @@ -24,20 +28,21 @@ public DistanceDrive(double distance, UnitTypes unitType) {
// Called just before this Command runs the first time
@Override
protected void initialize() {
Robot.driveTrain.stopAll();
Robot.driveTrain.resetRight();
}

// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
Robot.driveTrain.TankDrive(0.2, 0.2);
System.out.println("Driving forward: " + this.dist);
Robot.driveTrain.adjustedTankDrive(0.3, 0.3);
System.out.println("Right distance: " + Robot.driveTrain.getRightDistance(this.unit));
}

// Make this return true when this Command no longer needs to run execute()
@Override
protected boolean isFinished() {
return Robot.driveTrain.getRightDistance(UnitTypes.INCHES) >= 8;
return (Robot.driveTrain.getRightDistance(this.unit) >= this.dist);
}

// Called once after isFinished returns true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,19 +29,23 @@ protected void initialize() {
@Override
protected void execute() {
if (Robot.prefs.getBoolean("xcontrol", true)) {
Robot.driveTrain.wpiDrive.arcadeDrive(Robot.oi.xbox.getY(Hand.kLeft) * -1,
Robot.oi.xbox.getX(Hand.kLeft) * -1);
if (Robot.prefs.getBoolean("arcade", true)) {
Robot.driveTrain.wpiDrive.arcadeDrive(Robot.oi.xbox.getY(Hand.kLeft), -Robot.oi.xbox.getX(Hand.kLeft));
} else {
Robot.driveTrain.adjustedTankDrive(-Robot.oi.xbox.getY(Hand.kLeft), -Robot.oi.xbox.getY(Hand.kRight));
}
} else {
Robot.driveTrain.TankDrive(Robot.oi.leftStick.getY(), Robot.oi.rightStick.getY());
Robot.driveTrain.TankDrive(-Robot.oi.leftStick.getY(), -Robot.oi.rightStick.getY());
}
double throttle = Robot.oi.xbox.getTriggerAxis(Hand.kRight);
if (Robot.oi.xbox.getPOV() == 0) {
Robot.driveTrain.adjustedTankDrive(0.4, 0.4);
Robot.driveTrain.adjustedTankDrive(throttle, throttle);
} else if (Robot.oi.xbox.getPOV() == 90) {
Robot.driveTrain.adjustedTankDrive(-0.4, 0.4);
Robot.driveTrain.adjustedTankDrive(-throttle, throttle);
} else if (Robot.oi.xbox.getPOV() == 180) {
Robot.driveTrain.adjustedTankDrive(-0.4, -0.4);
Robot.driveTrain.adjustedTankDrive(-throttle, -throttle);
} else if (Robot.oi.xbox.getPOV() == 270) {
Robot.driveTrain.adjustedTankDrive(0.4, -0.4);
Robot.driveTrain.adjustedTankDrive(throttle, -throttle);
}
}

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

import org.usfirst.frc.team3494.robot.Robot;

import edu.wpi.first.wpilibj.command.Command;

/**
* Runs the intake. Default command for Intake subsystem.
*/
public class RunIntake extends Command {

boolean running = false;
double speed;

public RunIntake() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.intake);
}

// 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 (Robot.oi.xbox_lt.get()) {
this.speed = 1;
this.running = !this.running;
} else if (Robot.oi.xbox_rt.get()) {
this.speed = -1;
this.running = !this.running;
}
if (running) {
Robot.intake.runIntake(this.speed);
} else {
Robot.intake.stopAll();
}
}

// 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() {
}
}
Loading

0 comments on commit 3d342dc

Please sign in to comment.