Skip to content

Commit

Permalink
Merge pull request #103 from NicoletFEAR/Duluth-Thursday
Browse files Browse the repository at this point in the history
Duluth thursday
  • Loading branch information
Noah-Kennedy authored Mar 8, 2017
2 parents bb1a395 + 7f67178 commit 6d6e7c0
Show file tree
Hide file tree
Showing 14 changed files with 312 additions and 41 deletions.
11 changes: 9 additions & 2 deletions Steamworks/src/org/usfirst/frc/team4786/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,9 @@ public class OI {
private static Button kRightJoy10Button;
private static Button kLeftJoy11Button;
private static Button kRightJoy11Button;
private static Button leftJoystickTrigger;
private static Button rightJoystickTrigger;


private static Button rightBumper;
private static Button leftBumper;
Expand All @@ -47,6 +50,8 @@ public OI(){
leftDriveJoy = new Joystick(0);
rightDriveJoy = new Joystick(1);
xbox = new XboxController(2);
leftJoystickTrigger = new JoystickButton(leftDriveJoy, 1);
rightJoystickTrigger = new JoystickButton(rightDriveJoy, 1);
kLeftJoy6Button = new JoystickButton(leftDriveJoy, 6);
kRightJoy6Button = new JoystickButton(rightDriveJoy, 6);
kLeftJoy7Button = new JoystickButton(leftDriveJoy, 7);
Expand All @@ -69,6 +74,8 @@ public OI(){
limitSwitch4 = new DigitalInput(RobotMap.limitSwitch4Port);

//We map a bunch of buttons to switch the front side for Andy's convenience ;)
rightJoystickTrigger.whenPressed(new SwitchFrontSide());
leftJoystickTrigger.whenPressed(new SwitchFrontSide());
kLeftJoy6Button.whenPressed(new SwitchFrontSide());
kRightJoy6Button.whenPressed(new SwitchFrontSide());
kLeftJoy7Button.whenPressed(new SwitchFrontSide());
Expand All @@ -79,8 +86,8 @@ public OI(){
kRightJoy11Button.whenPressed(new SwitchFrontSide());


rightBumper.whenPressed(new OpenBridge());
leftBumper.whenPressed(new CloseBridge());
//rightBumper.whenPressed(new OpenBridge());
//leftBumper.whenPressed(new CloseBridge());
}
/*public void checkXboxButtonStates() {
if (xbox.getBButton() && Robot.climber.getCurrentCommand() == null) {
Expand Down
40 changes: 26 additions & 14 deletions Steamworks/src/org/usfirst/frc/team4786/robot/Robot.java
Original file line number Diff line number Diff line change
@@ -1,36 +1,37 @@
package org.usfirst.frc.team4786.robot;

import org.usfirst.frc.team4786.robot.commands.DoNothing;
import org.usfirst.frc.team4786.robot.commands.DriveArcSpeed;
import org.usfirst.frc.team4786.robot.commands.DriveToLeftGearPeg;
import org.usfirst.frc.team4786.robot.commands.DriveToPosition;
import org.usfirst.frc.team4786.robot.commands.DriveToRightGearPeg;
import org.usfirst.frc.team4786.robot.commands.OpenLoopDrive;
import org.usfirst.frc.team4786.robot.commands.SwitchFrontSide;
import org.usfirst.frc.team4786.robot.commands.TurnToAngle;
import org.usfirst.frc.team4786.robot.subsystems.Arduino;
import org.usfirst.frc.team4786.robot.subsystems.Climber;
import org.usfirst.frc.team4786.robot.subsystems.DrawBridge;
import org.usfirst.frc.team4786.robot.subsystems.DriveTrain;
import org.usfirst.frc.team4786.robot.subsystems.Gear;
//import org.usfirst.frc.team4786.robot.subsystems.FrameData;
import org.usfirst.frc.team4786.robot.subsystems.Intake;
import org.usfirst.frc.team4786.robot.subsystems.SwitchState;
//import org.usfirst.frc.team4786.robot.subsystems.Test;
//import org.usfirst.frc.team4786.robot.subsystems.VisionImage;
import org.usfirst.frc.team4786.robot.subsystems.VisionImage;
import org.usfirst.frc.team4786.robot.subsystems.SwitchState;

import org.usfirst.frc.team4786.robot.subsystems.Gear;

import edu.wpi.cscore.CvSink;
import edu.wpi.cscore.CvSource;
import edu.wpi.cscore.UsbCamera;
import edu.wpi.first.wpilibj.CameraServer;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.Timer;


public class Robot extends IterativeRobot {
Expand All @@ -39,6 +40,8 @@ public class Robot extends IterativeRobot {

//We setup our subsystem objects here

public static String frontSide;

public static DriveTrain driveTrain = new DriveTrain();
public static Intake intake = new Intake();
public static DrawBridge drawBridge = new DrawBridge();
Expand Down Expand Up @@ -80,23 +83,25 @@ public void robotInit() {
gearPlacementCamera.setResolution(RobotMap.cameraFOVWidth,RobotMap.cameraFOVHeight);
ballPlacementCamera.setResolution(RobotMap.cameraFOVWidth, RobotMap.cameraFOVHeight);
cvSink = CameraServer.getInstance().getVideo();
timer = new Timer();


frontSide = "Gear";

oi = new OI();
arduino = new Arduino(RobotMap.ledArduinoPort);



sendableChooser = new SendableChooser<Command>();
sendableChooser.addDefault("Do Nothing!", new DoNothing());
sendableChooser.addObject("Drive to Baseline", new DriveToPosition(6));
sendableChooser.addObject("Drive to Center Gear Peg", new DriveToPosition(4));
sendableChooser.addDefault("Drive to Center Gear Peg", new DriveToPosition(7));
sendableChooser.addObject("Do Nothing!", new DoNothing());
sendableChooser.addObject("Drive to Baseline", new DriveToPosition(10));
sendableChooser.addObject("Drive to Left Gear Peg", new DriveToLeftGearPeg());
sendableChooser.addObject("Drive to Right Gear Peg", new DriveToRightGearPeg());
//sendableChooser.addObject("GetToGearTest", new GearFromOffset());
SmartDashboard.putData("Autonomous Selector", sendableChooser);

/*Command initial = new SwitchFrontSide();
initial.start();*/
}
@Override
public void disabledInit() {
Expand All @@ -118,6 +123,8 @@ public void disabledPeriodic() {
arduino.writeStringData(allianceColorVal);
}
SmartDashboard.putString("Alliance", allianceColorVal);*/



Scheduler.getInstance().run();
}
Expand All @@ -142,12 +149,16 @@ public void autonomousInit() {

//camera.setExposureManual(RobotMap.exposure);
autonomousCommand = (Command) sendableChooser.getSelected();

//autonomousCommand = new GearFromOffset();

if (autonomousCommand != null)
autonomousCommand.start();
}

//autonomousCommand = new GearFromOffset();

//autonomousCommand = new DriveToLeftGearPeg();
// if (autonomousCommand != null)
// autonomousCommand.start();
//}

/**
* This function is called periodically during autonomous
Expand Down Expand Up @@ -211,10 +222,11 @@ public void testInit(){
@Override
public void testPeriodic() {
LiveWindow.run();

/*Robot.driveTrain.openLoopDrive(1, 1);
Robot.intake.collectBalls(1);
Robot.climber.startOpenClimbing(1);*/


//shows smartdashboard values
/*Command visionTest = new VisionSetup();
visionTest.start();*/

Expand Down
35 changes: 22 additions & 13 deletions Steamworks/src/org/usfirst/frc/team4786/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,10 @@ public class RobotMap {

//CANTalon ports, use instead of random numbers

public static final int frontLeftPort = 14;
public static final int frontRightPort = 13;
/*public static final int frontLeftPort = 14;
public static final int frontRightPort = 13;*/
public static final int frontLeftPort = 13;
public static final int frontRightPort = 14;

//Our CANTalon game mech ports
//Change these mech Talon IDs, do not know final CANTalon ids yet
Expand All @@ -28,26 +30,31 @@ public class RobotMap {

//General PID Constants
public static final int ERROR_CONSTANT_LEFT = 40; //In native units
public static final int ERROR_CONSTANT_RIGHT = 40;
public static final int ERROR_CONSTANT_RIGHT = 20;
public static final int ALLOWABLE_TURN_ERROR = 1; //In degrees
public static final int DRIVETRAIN_ENCODER_CODES_PER_REV_LEFT = 512;
public static final int DRIVETRAIN_ENCODER_CODES_PER_REV_LEFT = 1024;
public static final int DRIVETRAIN_ENCODER_CODES_PER_REV_RIGHT = 1024;
/*public static final int DRIVETRAIN_ENCODER_CODES_PER_REV_LEFT = 360;
public static final int DRIVETRAIN_ENCODER_CODES_PER_REV_RIGHT = 360;*/
public static final double CLOSED_LOOP_RAMP_RATE = 0.015625;
public static final int IZONE = 0;
public static final int DRIVEBASE_PROFILE = 0;
public static final double MAXIMUM_SPEED_VELOCITY_PID = 0.6;
public static final double fudgeFactor = 1;
public static final double turnFudgeFactor = 0.75;
//Wheel Radius measured in feet
public static final double WHEEL_RADIUS = 0.25;
//Distance between wheels measured in feet
public static final double WHEEL_SEPARATION = 2;
//Game Mech Costants, Not final
public static final double INTAKE_TALON_COLLECT_SPEED = -1;
public static final double INTAKE_TALON_COLLECT_SPEED = 1;
public static final double INTAKE_TALON_SPIT_SPEED = 1;
public static final double INTAKE_COLLECT_SPEED_SCALING = -1;
public static final double INTAKE_COLLECT_SPEED_SCALING = - 1;
public static final double INTAKE_SPIT_SPEED_SCALING = 1;
//public static final double OPEN_LOOP_CLIMBING_SPEED = 0.5;
public static final double OPEN_LOOP_CLIMBING_SPEED_SCALING = -.5;
public static final double OPEN_BRIDGE_ANGLE = 180;
public static final double CLOSED_BRIDGE_ANGLE = -180;
public static final double OPEN_LOOP_CLIMBING_SPEED_SCALING = -1;
public static final double OPEN_BRIDGE_ANGLE = 90;
public static final double CLOSED_BRIDGE_ANGLE = -90;
//Left GearBox PID Constants
/*
* For PID tuning next time:
Expand All @@ -56,13 +63,15 @@ public class RobotMap {
* Then add a tiny I value to push it up a little bit
* If needed, add a D value to smooth it out
*/
public static final double LeftP = 0.1;
public static final double LeftI = 0.0;
//public static final double LeftP = 0.1;
public static final double LeftP = 0.004;
public static final double LeftI = 0.00015;
public static final double LeftD = 0.0;
public static final double LeftF = 0.0;
//Right GearBox PID Constants
public static final double RightP = 0.1;
public static final double RightI = 0.0;
//public static final double RightP = 0.1;
public static final double RightP = 0.004;
public static final double RightI = 0.00015;
public static final double RightD = 0.0;
public static final double RightF = 0.0;
//Left GearBox Velocity PID Constants
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ protected void execute() {
// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {

return (Robot.drawBridge.getServoAngle() == RobotMap.CLOSED_BRIDGE_ANGLE) || this.timeSinceInitialized() >= 5;
return (Robot.drawBridge.getServoAngle() == RobotMap.CLOSED_BRIDGE_ANGLE)/* || this.timeSinceInitialized() >= 5*/;
}

// Called once after isFinished returns true
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
package org.usfirst.frc.team4786.robot.commands;

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

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

/**
*
*/
public class DriveArc extends Command {

private double horizontalDist, theta;

/**
* @param horizontalDist - Distance between start and end points measured along a line perpendicular to the starting orientation. Negative turns left, positive turns right.
* @param theta - Angle in degrees between start and end orientations.
*/
public DriveArc(double horizontalDist, double theta) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.driveTrain);
this.horizontalDist = horizontalDist;
this.theta = theta;
}

// Called just before this Command runs the first time
protected void initialize() {
Robot.driveTrain.driveArcInit(horizontalDist, theta);
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
//This is called instead of a special "driveArcIsFinished()" because it will do the same thing
return Robot.driveTrain.driveToPositionIsFinished();
}

// Called once after isFinished returns true
protected void end() {
//This is called instead of a special "driveArcEnd()" because it will do the same thing
Robot.driveTrain.driveToPositionEnd();
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
package org.usfirst.frc.team4786.robot.commands;

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

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

/**
*
*/
public class DriveArcSpeed extends Command {

private double leftSpeed, rightSpeed, time;

public DriveArcSpeed(double leftSpeed, double rightSpeed, double time) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
requires(Robot.driveTrain);
this.leftSpeed = leftSpeed;
this.rightSpeed = rightSpeed;
this.time = time;
}

// Called just before this Command runs the first time
protected void initialize() {
Robot.driveTrain.driveArcSpeedInit(leftSpeed, rightSpeed);
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
}

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

// Called once after isFinished returns true
protected void end() {
Robot.driveTrain.driveArcSpeedEnd();
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package org.usfirst.frc.team4786.robot.commands;

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

/**
*
*/
public class DriveArcYTurns extends CommandGroup {

public DriveArcYTurns() {
// Add Commands here:
// e.g. addSequential(new Command1());
// addSequential(new Command2());
// these will run in order.

// To run multiple commands at the same time,
// use addParallel()
// e.g. addParallel(new Command1());
// addSequential(new Command2());
// Command1 and Command2 will run in parallel.

// A command group will require all of the subsystems that each member
// would require.
// e.g. if Command1 requires chassis, and Command2 requires arm,
// a CommandGroup containing them would require both the chassis and the
// arm.
addSequential(new DriveArc(2, 20));
addSequential(new DriveArc(2, -20));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,17 @@
public class DriveToLeftGearPeg extends CommandGroup {

public DriveToLeftGearPeg() {
/*
addSequential(new DriveToPosition(3));
addSequential(new TurnToAngle(60));
addSequential(new DriveToPosition(1));
addSequential(new DriveToPosition(1));*/

//initial drive straight in feet
addSequential(new DriveToPosition(2));
//turning degrees via .22 power ratio on inside of turn for .75 seconds
addSequential(new DriveArcSpeed(1, 1 * 0.22, 0.75));
//final drive straight to target
addSequential(new DriveToPosition(3));

// To run multiple commands at the same time,
// use addParallel()
Expand Down
Loading

0 comments on commit 6d6e7c0

Please sign in to comment.