added roller code

This commit is contained in:
Adam Long 2016-09-12 21:42:04 +00:00
parent 670de6a143
commit 877b7aaf8d
7 changed files with 98 additions and 2 deletions

View File

@ -8,6 +8,8 @@ import org.usfirst.frc.team2059.robot.commands.MoveArm;
import org.usfirst.frc.team2059.robot.commands.SetArmPosition;
import org.usfirst.frc.team2059.robot.commands.SetShooterState;
import org.usfirst.frc.team2059.robot.commands.SetArmStopState;
import org.usfirst.frc.team2059.robot.commands.ShootAtSpeed;
import org.usfirst.frc.team2059.robot.commands.SpinRollers;
import org.usfirst.frc.team2059.robot.RobotMap;
/**
* This class is the glue that binds the controls on the physical operator
@ -29,7 +31,8 @@ public class OI {
}
// Print log when button 1 pressed
//joystickButtons[0][0].whenPressed(new LogEncoder());
joystickButtons[0][0].whileHeld(new SetShooterState(true));
joystickButtons[0][0].whileHeld(new SpinRollers(1));
joystickButtons[0][1].whileHeld(new SetShooterState(true));
joystickButtons[1][0].whileHeld(new MoveArm(0.5));
joystickButtons[1][1].whileHeld(new MoveArm(-0.5));

View File

@ -17,6 +17,8 @@ public class Robot extends IterativeRobot {
SmartDashboard.putData("Auto mode", chooser);
SmartDashboard.putData("MainArm",CommandBase.mainArm.getPIDController());
SmartDashboard.putBoolean("CompressorEnabled",true);
//Automatically determine if rolling in or rolling out
SmartDashboard.putBoolean("SmartRollers",true);
}
public void disabledInit() {
}
@ -37,6 +39,7 @@ public class Robot extends IterativeRobot {
autonomousCommand.cancel();
}
CommandBase.pneumatics.setCompressorEnabled(true);
CommandBase.pneumatics.setArmStopState(false);
}
public void teleopPeriodic() {
Scheduler.getInstance().run();

View File

@ -25,7 +25,7 @@ public class RobotMap {
public static int armStopSolenoidOne = 4;
public static int armStopSolenoidTwo = 5;
//Misc
public static int mainArmPresetCollect = 0;
public static int mainArmPresetCollect = -3;
public static int mainArmPresetTraverse = 11;
public static int mainArmPresetCloseShot = 90;
public static int mainArmPresetFarShot = 70;

View File

@ -3,17 +3,20 @@ import org.usfirst.frc.team2059.robot.subsystems.DriveBase;
import org.usfirst.frc.team2059.robot.subsystems.EncoderBase;
import org.usfirst.frc.team2059.robot.subsystems.MainArm;
import org.usfirst.frc.team2059.robot.subsystems.Pneumatics;
import org.usfirst.frc.team2059.robot.subsystems.Shooter;
import edu.wpi.first.wpilibj.command.Command;
public abstract class CommandBase extends Command {
public static EncoderBase encoderBase;
public static DriveBase driveBase;
public static MainArm mainArm;
public static Pneumatics pneumatics;
public static Shooter shooter;
public static void init() {
encoderBase = new EncoderBase();
driveBase = new DriveBase();
mainArm = new MainArm();
pneumatics = new Pneumatics();
shooter = new Shooter();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,34 @@
package org.usfirst.frc.team2059.robot.commands;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
import org.usfirst.frc.team2059.robot.RobotMap;
/**
*
*/
public class ShootAtSpeed extends CommandBase {
double speed;
public ShootAtSpeed(double s) {
speed=s;
}
// Called just before this Command runs the first time
protected void initialize() {
}
// Called repeatedly when this Command is scheduled to run
protected void execute() {
shooter.shootAtSpeed(speed);
}
// 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() {
shooter.shootAtSpeed(0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,38 @@
package org.usfirst.frc.team2059.robot.commands;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.Robot;
/**
*
*/
public class SpinRollers extends CommandBase {
double speed;
public SpinRollers(double s) {
speed=s;
}
// 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(SmartDashboard.getBoolean("SmartRollers") && mainArm.getDegrees()<5){
shooter.shootAtSpeed(-.5);
}else{
shooter.shootAtSpeed(speed);
}
}
// 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() {
shooter.shootAtSpeed(0);
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -0,0 +1,15 @@
package org.usfirst.frc.team2059.robot.subsystems;
import org.usfirst.frc.team2059.robot.RobotMap;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.CANTalon;
public class Shooter extends Subsystem {
CANTalon shooterMotorLeft = new CANTalon(RobotMap.shooterLeftMotor);
CANTalon shooterMotorRight = new CANTalon(RobotMap.shooterRightMotor);
public void initDefaultCommand() {
}
public void shootAtSpeed(double speed){
shooterMotorRight.set(speed);
shooterMotorLeft.set(speed);
}
}
// vim: sw=2:ts=2:sts=2