Skip to content

Commit

Permalink
Added IntakeGrip subsystem and controls
Browse files Browse the repository at this point in the history
  • Loading branch information
briansemrau committed Feb 28, 2018
1 parent 97772f5 commit a1bfac3
Show file tree
Hide file tree
Showing 8 changed files with 185 additions and 42 deletions.
20 changes: 12 additions & 8 deletions src/org/usfirst/frc/team4737/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,10 @@
import org.usfirst.frc.team4737.lib.Gamepad;
import org.usfirst.frc.team4737.lib.XboxController;
import org.usfirst.frc.team4737.lib.F310Gamepad;
import org.usfirst.frc.team4737.robot.commands.drivetrain.TeleopRacingDrive;
import org.usfirst.frc.team4737.robot.commands.elevator.ControlElevator;
import org.usfirst.frc.team4737.robot.commands.elevator.RelaxElevator;
import org.usfirst.frc.team4737.robot.commands.intake.ControlIntake;
import org.usfirst.frc.team4737.robot.commands.drivetrain.*;
import org.usfirst.frc.team4737.robot.commands.elevator.*;
import org.usfirst.frc.team4737.robot.commands.intake.*;
import org.usfirst.frc.team4737.robot.commands.intakegrip.*;

import edu.wpi.first.wpilibj.buttons.Trigger;

Expand Down Expand Up @@ -78,12 +78,16 @@ public boolean get() {
return operator.getAxis("LS_Y").get() != 0;
}
}.whileActive(new ControlElevator());

// Allow operator to instantly relax elevator in case of motor overheat
operator.getButton("Y").whileHeld(new RelaxElevator());

// operator.getDPad("DPAD").LEFT.whileActive(new TwistIntake(1));
// operator.getDPad("DPAD").RIGHT.whileActive(new TwistIntake(-1));

// Take control of intake grip
operator.getButton("A").whileHeld(new ControlIntakeGrip());
operator.getButton("B").whileHeld(new ControlIntakeGrip());

// operator.getDPad("DPAD").LEFT.whileActive(new TwistIntake(1));
// operator.getDPad("DPAD").RIGHT.whileActive(new TwistIntake(-1));

}

Expand Down
1 change: 1 addition & 0 deletions src/org/usfirst/frc/team4737/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ public class Robot extends TimedRobot {
public static final Drivetrain DRIVETRAIN = new Drivetrain();
public static final Elevator ELEVATOR = new Elevator();
public static final Intake INTAKE = new Intake();
public static final IntakeGrip INTAKEGRIP = new IntakeGrip();
public static final Climber CLIMBER = new Climber();
public static final ControlSystem CONTROLSYSTEM = new ControlSystem();

Expand Down
13 changes: 10 additions & 3 deletions src/org/usfirst/frc/team4737/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
*/
public class RobotMap {

// ################
// TalonSRX CAN IDs
// ################
// #####################
// Actuator IDs/Channels
// #####################

// Drivetrain
public static final int DRIVE_LEFT_MASTER = 11;
Expand All @@ -29,6 +29,13 @@ public class RobotMap {
public static final int INTAKE_LEFT = 15;
public static final int INTAKE_RIGHT = 16;

public static final int INTAKE_LEFT_PISTON_MODULE = 0;
public static final int INTAKE_LEFT_PISTON_FORWARD_CHANNEL = 0;
public static final int INTAKE_LEFT_PISTON_REVERSE_CHANNEL = 1;
public static final int INTAKE_RIGHT_PISTON_MODULE = 0;
public static final int INTAKE_RIGHT_PISTON_FORWARD_CHANNEL = 2;
public static final int INTAKE_RIGHT_PISTON_REVERSE_CHANNEL = 3;

// Elevator
public static final int ELEVATOR_MOTOR = 17;

Expand Down
60 changes: 30 additions & 30 deletions src/org/usfirst/frc/team4737/robot/commands/intake/TwistIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,34 +10,34 @@
public class TwistIntake extends Command {

private double speed;
public TwistIntake(double speed) {
requires(Robot.INTAKE);
this.speed = speed;
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.INTAKE.setLRSpeed(speed, -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() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}

public TwistIntake(double speed) {
requires(Robot.INTAKE);

this.speed = speed;
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.INTAKE.setLRSpeed(speed, -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() {
}

// 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,46 @@
package org.usfirst.frc.team4737.robot.commands.intakegrip;

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

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

/**
*
*/
public class ControlIntakeGrip extends Command {

public ControlIntakeGrip() {
requires(Robot.INTAKEGRIP);
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
boolean grab = Robot.OI.operator.getButton("A").get();
boolean release = Robot.OI.operator.getButton("B").get();

if (grab) {
Robot.INTAKEGRIP.closePneumatics();
} else if (release) {
Robot.INTAKEGRIP.openPneumatics();
}
}

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

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
package org.usfirst.frc.team4737.robot.commands.intakegrip;

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

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

/**
*
*/
public class StopIntakeGrip extends Command {

public StopIntakeGrip() {
requires(Robot.INTAKEGRIP);
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.INTAKEGRIP.disablePneumatics();
}

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

}
2 changes: 1 addition & 1 deletion src/org/usfirst/frc/team4737/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ public void initDefaultCommand() {
public void setSpeed(double speed) {
setLRSpeed(speed, speed);
}

public void setLRSpeed(double left, double right) {
leftMotor.set(left);
rightMotor.set(right);
Expand Down
46 changes: 46 additions & 0 deletions src/org/usfirst/frc/team4737/robot/subsystems/IntakeGrip.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
package org.usfirst.frc.team4737.robot.subsystems;

import org.usfirst.frc.team4737.robot.RobotMap;
import org.usfirst.frc.team4737.robot.commands.intakegrip.StopIntakeGrip;

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.command.Subsystem;

/**
*
*/
public class IntakeGrip extends Subsystem {

private DoubleSolenoid leftPneumatic;
private DoubleSolenoid rightPneumatic;

public IntakeGrip() {
leftPneumatic = new DoubleSolenoid(RobotMap.INTAKE_LEFT_PISTON_MODULE,
RobotMap.INTAKE_LEFT_PISTON_FORWARD_CHANNEL, RobotMap.INTAKE_LEFT_PISTON_REVERSE_CHANNEL);
rightPneumatic = new DoubleSolenoid(RobotMap.INTAKE_RIGHT_PISTON_MODULE,
RobotMap.INTAKE_RIGHT_PISTON_FORWARD_CHANNEL, RobotMap.INTAKE_RIGHT_PISTON_REVERSE_CHANNEL);
}

public void initDefaultCommand() {
setDefaultCommand(new StopIntakeGrip());
}

public void closePneumatics() {
setPneumatics(Value.kReverse, Value.kReverse);
}

public void openPneumatics() {
setPneumatics(Value.kForward, Value.kForward);
}

public void disablePneumatics() {
setPneumatics(Value.kOff, Value.kOff);
}

public void setPneumatics(DoubleSolenoid.Value left, DoubleSolenoid.Value right) {
leftPneumatic.set(left);
rightPneumatic.set(right);
}

}

0 comments on commit a1bfac3

Please sign in to comment.