Added support for PacGoat robot for artf2591.

This also includes support for solenoids (artf2592) in the gazebo plugin and WPILibJavaSim, fixes a concurrency issue with JavaGazebo.

Change-Id: I5bd19556a7511387852c98414e4a29fdfd68b8cd
This commit is contained in:
Alex Henning
2014-06-23 14:43:45 -07:00
parent 0f8c83f693
commit 40628a817d
34 changed files with 1807 additions and 62 deletions

View File

@@ -1,6 +1,6 @@
package $package.subsystems;
import edu.wpi.first.wpilibj.AnalogChannel;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick.AxisType;
import edu.wpi.first.wpilibj.Gyro;
@@ -24,7 +24,7 @@ public class DriveTrain extends Subsystem {
front_right_motor, back_right_motor;
private RobotDrive drive;
private Encoder left_encoder, right_encoder;
private AnalogChannel rangefinder;
private AnalogInput rangefinder;
private Gyro gyro;
public DriveTrain() {
@@ -55,7 +55,7 @@ public class DriveTrain extends Subsystem {
left_encoder.start();
right_encoder.start();
rangefinder = new AnalogChannel(6);
rangefinder = new AnalogInput(6);
gyro = new Gyro(1);
// Let's show everything on the LiveWindow

View File

@@ -0,0 +1,48 @@
package $package;
import $package.commands.Collect;
import $package.commands.DriveForward;
import $package.commands.LowGoal;
import $package.commands.SetCollectionSpeed;
import $package.commands.SetPivotSetpoint;
import $package.commands.Shoot;
import $package.subsystems.Collector;
import $package.subsystems.Pivot;
import $package.triggers.DoubleButton;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.buttons.JoystickButton;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/**
* The operator interface of the robot, it has been simplified from the real
* robot to allow control with a single PS3 joystick. As a result, not all
* functionality from the real robot is available.
*/
public class OI {
public Joystick joystick;
public OI() {
joystick = new Joystick(1);
new JoystickButton(joystick, 12).whenPressed(new LowGoal());
new JoystickButton(joystick, 10).whenPressed(new Collect());
new JoystickButton(joystick, 11).whenPressed(new SetPivotSetpoint(Pivot.SHOOT));
new JoystickButton(joystick, 9).whenPressed(new SetPivotSetpoint(Pivot.SHOOT_NEAR));
new DoubleButton(joystick, 2, 3).whenActive(new Shoot());
// SmartDashboard Buttons
SmartDashboard.putData("Drive Forward", new DriveForward(2.25));
SmartDashboard.putData("Drive Backward", new DriveForward(-2.25));
SmartDashboard.putData("Start Rollers", new SetCollectionSpeed(Collector.FORWARD));
SmartDashboard.putData("Stop Rollers", new SetCollectionSpeed(Collector.STOP));
SmartDashboard.putData("Reverse Rollers", new SetCollectionSpeed(Collector.REVERSE));
}
public Joystick getJoystick() {
return joystick;
}
}

View File

@@ -0,0 +1,122 @@
package $package;
import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import $package.commands.DriveAndShootAutonomous;
import $package.commands.DriveForward;
import $package.subsystems.Collector;
import $package.subsystems.DriveTrain;
import $package.subsystems.Pivot;
import $package.subsystems.Pneumatics;
import $package.subsystems.Shooter;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/**
* This is the main class for running the PacGoat code.
*
* The VM is configured to automatically run this class, and to call the
* functions corresponding to each mode, as described in the IterativeRobot
* documentation. If you change the name of this class or the package after
* creating this project, you must also update the manifest file in the resource
* directory.
*/
public class Robot extends IterativeRobot {
Command autonomousCommand;
public static OI oi;
public static DriveTrain drivetrain;
public static Collector collector;
public static Shooter shooter;
public static Pneumatics pneumatics;
public static Pivot pivot;;
public SendableChooser autoChooser;
public SendableChooser autonomousDirectionChooser;
// This function is run when the robot is first started up and should be
// used for any initialization code.
public void robotInit() {
// Initialize the subsystems
drivetrain = new DriveTrain();
collector = new Collector();
shooter = new Shooter();
pneumatics = new Pneumatics();
pivot = new Pivot();
SmartDashboard.putData(drivetrain);
SmartDashboard.putData(collector);
SmartDashboard.putData(shooter);
SmartDashboard.putData(pneumatics);
SmartDashboard.putData(pivot);
// This MUST be here. If the OI creates Commands (which it very likely
// will), constructing it during the construction of CommandBase (from
// which commands extend), subsystems are not guaranteed to be
// yet. Thus, their requires() statements may grab null pointers. Bad
// news. Don't move it.
oi = new OI();
// instantiate the command used for the autonomous period
autoChooser = new SendableChooser();
autoChooser.addDefault("Drive and Shoot", new DriveAndShootAutonomous());
autoChooser.addObject("Drive Forward", new DriveForward());
SmartDashboard.putData("Auto Mode", autoChooser);
pneumatics.start(); // Pressurize the pneumatics.
}
public void autonomousInit() {
Command auto = (Command) autoChooser.getSelected();
auto.start();
}
// This function is called periodically during autonomous
public void autonomousPeriodic() {
Scheduler.getInstance().run();
log();
}
public void teleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (autonomousCommand != null) {
autonomousCommand.cancel();
}
}
// This function is called periodically during operator control
public void teleopPeriodic() {
Scheduler.getInstance().run();
log();
}
// This function called periodically during test mode
public void testPeriodic() {
LiveWindow.run();
}
public void disabledInit() {
Robot.shooter.unlatch();
}
// This function is called periodically while disabled
public void disabledPeriodic() {
log();
}
/**
* Log interesting values to the SmartDashboard.
*/
private void log() {
Robot.pneumatics.writePressure();
SmartDashboard.putNumber("Pivot Pot Value", Robot.pivot.getAngle());
SmartDashboard.putNumber("Left Distance", drivetrain.getLeftEncoder().getDistance());
SmartDashboard.putNumber("Right Distance", drivetrain.getRightEncoder().getDistance());
}
}

View File

@@ -0,0 +1,37 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* This command looks for the hot goal and waits until it's detected or timed
* out. The timeout is because it's better to shoot and get some autonomous
* points than get none. When called sequentially, this command will block until
* the hot goal is detected or until it is timed out.
*/
public class CheckForHotGoal extends Command {
public CheckForHotGoal(double time) {
setTimeout(time);
}
// Called just before this Command runs the first time
protected void initialize() {}
// 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 isTimedOut() || Robot.shooter.goalIsHot();
}
// 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() {
end();
}
}

View File

@@ -0,0 +1,39 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* Close the claw.
*
* NOTE: It doesn't wait for the claw to close since their is no sensor to
* detect that.
*/
public class CloseClaw extends Command {
public CloseClaw() {
requires(Robot.collector);
}
// Called just before this Command runs the first time
protected void initialize() {
Robot.collector.close();
}
// 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 true;
}
// 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() {}
}

View File

@@ -0,0 +1,18 @@
package $package.commands;
import $package.subsystems.Collector;
import $package.subsystems.Pivot;
import edu.wpi.first.wpilibj.command.CommandGroup;
/**
* Get the robot set to collect balls.
*/
public class Collect extends CommandGroup {
public Collect() {
addSequential(new SetCollectionSpeed(Collector.FORWARD));
addParallel(new CloseClaw());
addSequential(new SetPivotSetpoint(Pivot.COLLECT));
addSequential(new WaitForBall());
}
}

View File

@@ -0,0 +1,23 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.CommandGroup;
/**
* Drive over the line and then shoot the ball. If the hot goal is not detected,
* it will wait briefly.
*/
public class DriveAndShootAutonomous extends CommandGroup {
public DriveAndShootAutonomous() {
addSequential(new WaitForPressure(), 2);
if (Robot.isReal()) {
// NOTE: Simulation doesn't currently have the concept of hot.
addSequential(new CheckForHotGoal(2));
}
addSequential(new CloseClaw());
addSequential(new SetPivotSetpoint(45));
addSequential(new DriveForward(8, 0.4));
addSequential(new Shoot());
}
}

View File

@@ -0,0 +1,58 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* This command drives the robot over a given distance with simple proportional
* control This command will drive a given distance limiting to a maximum speed.
*/
public class DriveForward extends Command {
private double driveForwardSpeed;
private double distance;
private final double tolerance = .1; // TODO: Was 5
private double error;
private final double Kp = -1.0 / 5.0;
public DriveForward() {
this(10, 0.5);
}
public DriveForward(double dist) {
this(dist, 0.5);
}
public DriveForward(double dist, double maxSpeed) {
requires(Robot.drivetrain);
distance = dist;
driveForwardSpeed = maxSpeed;
}
protected void initialize() {
Robot.drivetrain.getRightEncoder().reset();
setTimeout(2);
}
protected void execute() {
error = (distance - Robot.drivetrain.getRightEncoder().getDistance());
if (driveForwardSpeed * Kp * error >= driveForwardSpeed) {
Robot.drivetrain.tankDrive(driveForwardSpeed, driveForwardSpeed);
} else {
Robot.drivetrain.tankDrive(driveForwardSpeed * Kp * error,
driveForwardSpeed * Kp * error);
}
}
protected boolean isFinished() {
return (Math.abs(error) <= tolerance) || isTimedOut();
}
protected void end() {
Robot.drivetrain.stop();
}
protected void interrupted() {
end();
}
}

View File

@@ -0,0 +1,34 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* This command allows PS3 joystick to drive the robot. It is always running
* except when interrupted by another command.
*/
public class DriveWithJoystick extends Command {
public DriveWithJoystick() {
requires(Robot.drivetrain);
}
protected void initialize() {
}
protected void execute() {
Robot.drivetrain.tankDrive(Robot.oi.getJoystick());
}
protected boolean isFinished() {
return false;
}
protected void end() {
Robot.drivetrain.stop();
}
protected void interrupted() {
end();
}
}

View File

@@ -0,0 +1,41 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* Extend the shooter and then retract it after a second.
*/
public class ExtendShooter extends Command {
public ExtendShooter() {
requires(Robot.shooter);
setTimeout(1);
}
// Called just before this Command runs the first time
protected void initialize() {
Robot.shooter.extendBoth();
}
// 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 isTimedOut();
}
// Called once after isFinished returns true
protected void end() {
Robot.shooter.retractBoth();
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}

View File

@@ -0,0 +1,17 @@
package $package.commands;
import $package.subsystems.Collector;
import $package.subsystems.Pivot;
import edu.wpi.first.wpilibj.command.CommandGroup;
/**
* Spit the ball out into the low goal assuming that the robot is in front of it.
*/
public class LowGoal extends CommandGroup {
public LowGoal() {
addSequential(new SetPivotSetpoint(Pivot.LOW_GOAL));
addSequential(new SetCollectionSpeed(Collector.REVERSE));
addSequential(new ExtendShooter());
}
}

View File

@@ -0,0 +1,36 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* Opens the claw
*/
public class OpenClaw extends Command {
public OpenClaw() {
requires(Robot.collector);
}
// Called just before this Command runs the first time
protected void initialize() {
Robot.collector.open();
}
// 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 Robot.collector.isOpen();
}
// 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() {}
}

View File

@@ -0,0 +1,39 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* This command sets the collector rollers spinning at the given speed. Since
* there is no sensor for detecting speed, it finishes immediately. As a result,
* the spinners may still be adjusting their speed.
*/
public class SetCollectionSpeed extends Command {
private double speed;
public SetCollectionSpeed(double speed) {
requires(Robot.collector);
this.speed = speed;
}
// Called just before this Command runs the first time
protected void initialize() {
Robot.collector.setSpeed(speed);
}
// 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 true;
}
// 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() {}
}

View File

@@ -0,0 +1,44 @@
/*
* To change this template, choose Tools | Templates
* and open the template in the editor.
*/
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* Moves the pivot to a given angle. This command finishes when it is within
* the tolerance, but leaves the PID loop running to maintain the position.
* Other commands using the pivot should make sure they disable PID!
*/
public class SetPivotSetpoint extends Command {
private double setpoint;
public SetPivotSetpoint(double setpoint) {
this.setpoint = setpoint;
requires(Robot.pivot);
}
// Called just before this Command runs the first time
protected void initialize() {
Robot.pivot.enable();
Robot.pivot.setSetpoint(setpoint);
}
// 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 Robot.pivot.onTarget();
}
// 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() {}
}

View File

@@ -0,0 +1,17 @@
package $package.commands;
import $package.subsystems.Collector;
import edu.wpi.first.wpilibj.command.CommandGroup;
/**
* Shoot the ball at the current angle.
*/
public class Shoot extends CommandGroup {
public Shoot() {
addSequential(new WaitForPressure());
addSequential(new SetCollectionSpeed(Collector.STOP));
addSequential(new OpenClaw());
addSequential(new ExtendShooter());
}
}

View File

@@ -0,0 +1,35 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* Wait until the collector senses that it has the ball. This command does
* nothing and is intended to be used in command groups to wait for this
* condition.
*/
public class WaitForBall extends Command {
public WaitForBall() {
requires(Robot.collector);
}
// Called just before this Command runs the first time
protected void initialize() {}
// 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 Robot.collector.hasBall();
}
// 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() {}
}

View File

@@ -0,0 +1,34 @@
package $package.commands;
import $package.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
* Wait until the pneumatics are fully pressurized. This command does nothing
* and is intended to be used in command groups to wait for this condition.
*/
public class WaitForPressure extends Command {
public WaitForPressure() {
requires(Robot.pneumatics);
}
// Called just before this Command runs the first time
protected void initialize() {}
// 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 Robot.pneumatics.isPressurized();
}
// 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() {}
}

View File

@@ -0,0 +1,91 @@
package $package.subsystems;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
* The Collector subsystem has one motor for the rollers, a limit switch for ball
* detection, a piston for opening and closing the claw, and a reed switch to
* check if the piston is open.
*/
public class Collector extends Subsystem {
// Constants for some useful speeds
public static final double FORWARD = 1;
public static final double STOP = 0;
public static final double REVERSE = -1;
// Subsystem devices
private SpeedController rollerMotor;
private DigitalInput ballDetector;
private Solenoid piston;
private DigitalInput openDetector;
public Collector() {
// Configure devices
rollerMotor = new Victor(6);
ballDetector = new DigitalInput(10);
openDetector = new DigitalInput(6);
piston = new Solenoid(1, 1);
// Put everything to the LiveWindow for testing.
LiveWindow.addActuator("Collector", "Roller Motor", (Victor) rollerMotor);
LiveWindow.addSensor("Collector", "Ball Detector", ballDetector);
LiveWindow.addSensor("Collector", "Claw Open Detector", openDetector);
LiveWindow.addActuator("Collector", "Piston", piston);
}
/**
* NOTE: The current simulation model uses the the lower part of the claw
* since the limit switch wasn't exported. At some point, this will be
* updated.
*
* @return Whether or not the robot has the ball.
*/
public boolean hasBall() {
return ballDetector.get(); // TODO: prepend ! to reflect real robot
}
/**
* @param speed The speed to spin the rollers.
*/
public void setSpeed(double speed) {
rollerMotor.set(-speed);
}
/**
* Stop the rollers from spinning
*/
public void stop() {
rollerMotor.set(0);
}
/**
* @return Whether or not the claw is open.
*/
public boolean isOpen() {
return openDetector.get(); // TODO: prepend ! to reflect real robot
}
/**
* Open the claw up. (For shooting)
*/
public void open() {
piston.set(true);
}
/**
* Close the claw. (For collecting and driving)
*/
public void close() {
piston.set(false);
}
/**
* No default command.
*/
@Override protected void initDefaultCommand() {}
}

View File

@@ -0,0 +1,129 @@
package $package.subsystems;
import $package.Robot;
import $package.commands.DriveWithJoystick;
import edu.wpi.first.wpilibj.CounterBase.EncodingType;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Gyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PIDSource.PIDSourceParameter;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
* The DriveTrain subsystem controls the robot's chassis and reads in
* information about it's speed and position.
*/
public class DriveTrain extends Subsystem {
// Subsystem devices
private SpeedController frontLeftCIM, frontRightCIM;
private SpeedController backLeftCIM, backRightCIM;
private RobotDrive drive;
private Encoder rightEncoder, leftEncoder;
private Gyro gyro;
public DriveTrain() {
// Configure drive motors
frontLeftCIM = new Victor(1);
frontRightCIM = new Victor(2);
backLeftCIM = new Victor(3);
backRightCIM = new Victor(4);
LiveWindow.addActuator("DriveTrain", "Front Left CIM", (Victor) frontLeftCIM);
LiveWindow.addActuator("DriveTrain", "Front Right CIM", (Victor) frontRightCIM);
LiveWindow.addActuator("DriveTrain", "Back Left CIM", (Victor) backLeftCIM);
LiveWindow.addActuator("DriveTrain", "Back Right CIM", (Victor) backRightCIM);
// Configure the RobotDrive to reflect the fact that all our motors are
// wired backwards and our drivers sensitivity preferences.
drive = new RobotDrive(frontLeftCIM, backLeftCIM, frontRightCIM, backRightCIM);
drive.setSafetyEnabled(true);
drive.setExpiration(0.1);
drive.setSensitivity(0.5);
drive.setMaxOutput(1.0);
drive.setInvertedMotor(RobotDrive.MotorType.kFrontLeft, true);
drive.setInvertedMotor(RobotDrive.MotorType.kRearLeft, true);
drive.setInvertedMotor(RobotDrive.MotorType.kFrontRight, true);
drive.setInvertedMotor(RobotDrive.MotorType.kRearRight, true);
// Configure encoders
rightEncoder = new Encoder(1, 2, true, EncodingType.k4X);
leftEncoder = new Encoder(5, 6, false, EncodingType.k4X); // XXX: Module 2
rightEncoder.setPIDSourceParameter(PIDSourceParameter.kDistance);
leftEncoder.setPIDSourceParameter(PIDSourceParameter.kDistance);
if (Robot.isReal()) { // Converts to feet
rightEncoder.setDistancePerPulse(0.0785398);
leftEncoder.setDistancePerPulse(0.0785398);
} else { // Convert to feet 4in diameter wheels with 360 tick simulated encoders
rightEncoder.setDistancePerPulse((4.0/*in*/*Math.PI)/(360.0*12.0/*in/ft*/));
leftEncoder.setDistancePerPulse((4.0/*in*/*Math.PI)/(360.0*12.0/*in/ft*/));
}
rightEncoder.start();
leftEncoder.start();
LiveWindow.addSensor("DriveTrain", "Right Encoder", rightEncoder);
LiveWindow.addSensor("DriveTrain", "Left Encoder", leftEncoder);
// Configure gyro
gyro = new Gyro(2);
if (Robot.isReal()) {
gyro.setSensitivity(0.007); // TODO: Handle more gracefully?
}
LiveWindow.addSensor("DriveTrain", "Gyro", gyro);
}
/**
* When other commands aren't using the drivetrain, allow tank drive with
* the joystick.
*/
public void initDefaultCommand() {
setDefaultCommand(new DriveWithJoystick());
}
/**
* @param joy PS3 style joystick to use as the input for tank drive.
*/
public void tankDrive(Joystick joy) {
drive.tankDrive(joy.getY(), joy.getRawAxis(4));
}
/**
* @param leftAxis Left sides value
* @param rightAxis Right sides value
*/
public void tankDrive(double leftAxis, double rightAxis) {
drive.tankDrive(leftAxis, rightAxis);
}
/**
* Stop the drivetrain from moving.
*/
public void stop() {
drive.tankDrive(0, 0);
}
/**
* @return The encoder getting the distance and speed of left side of the drivetrain.
*/
public Encoder getLeftEncoder() {
return leftEncoder;
}
/**
* @return The encoder getting the distance and speed of right side of the drivetrain.
*/
public Encoder getRightEncoder() {
return rightEncoder;
}
/**
* @return The current angle of the drivetrain.
*/
public double getAngle() {
return gyro.getAngle();
}
}

View File

@@ -0,0 +1,94 @@
package $package.subsystems;
import $package.Robot;
import edu.wpi.first.wpilibj.*;
import edu.wpi.first.wpilibj.command.PIDSubsystem;
import edu.wpi.first.wpilibj.interfaces.Potentiometer;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
* The Pivot subsystem contains the Van-door motor and the pot for PID control
* of angle of the pivot and claw.
*/
public class Pivot extends PIDSubsystem {
// Constants for some useful angles
public static final double COLLECT = 105;
public static final double LOW_GOAL = 90;
public static final double SHOOT = 45;
public static final double SHOOT_NEAR = 30;
// Subsystem devices
private DigitalInput upperLimitSwitch;
private DigitalInput lowerLimitSwitch;
private Potentiometer pot;
private SpeedController motor;
public Pivot() {
super("Pivot", 7.0, 0.0, 8.0);
setAbsoluteTolerance(0.005);
getPIDController().setContinuous(false);
if (Robot.isSimulation()) { // PID is different in simulation.
getPIDController().setPID(0.5, 0.00001, 4.5);
setAbsoluteTolerance(2.5);
}
// Motor to move the pivot.
motor = new Victor(5);
// Sensors for measuring the position of the pivot.
upperLimitSwitch = new DigitalInput(13);
lowerLimitSwitch = new DigitalInput(12);
// 0 degrees is vertical facing up.
// Angle increases the more forward the pivot goes.
pot = new AnalogPotentiometer(1);
// Put everything to the LiveWindow for testing.
LiveWindow.addSensor("Pivot", "Upper Limit Switch", upperLimitSwitch);
LiveWindow.addSensor("Pivot", "Lower Limit Switch", lowerLimitSwitch);
LiveWindow.addSensor("Pivot", "Pot", (AnalogPotentiometer) pot);
LiveWindow.addActuator("Pivot", "Motor", (Victor) motor);
LiveWindow.addActuator("Pivot", "PIDSubsystem Controller", getPIDController());
}
/**
* No default command, if PID is enabled, the current setpoint will be maintained.
*/
public void initDefaultCommand() {}
/**
* @return The angle read in by the potentiometer
*/
protected double returnPIDInput() {
return pot.get();
}
/**
* Set the motor speed based off of the PID output
*/
protected void usePIDOutput(double output) {
motor.pidWrite(output);
}
/**
* @return If the pivot is at its upper limit.
*/
public boolean isAtUpperLimit() {
return upperLimitSwitch.get(); // TODO: inverted from real robot (prefix with !)
}
/**
* @return If the pivot is at its lower limit.
*/
public boolean isAtLowerLimit() {
return lowerLimitSwitch.get(); // TODO: inverted from real robot (prefix with !)
}
/**
* @return The current angle of the pivot.
*/
public double getAngle() {
return pot.get();
}
}

View File

@@ -0,0 +1,61 @@
package $package.subsystems;
import $package.Robot;
import edu.wpi.first.wpilibj.*;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/**
* The Pneumatics subsystem contains the compressor and a pressure sensor.
*
* NOTE: The simulator currently doesn't support the compressor or pressure sensors.
*/
public class Pneumatics extends Subsystem {
AnalogInput pressureSensor;
Compressor compressor;
private static final double MAX_PRESSURE = 2.55;
public Pneumatics() {
pressureSensor = new AnalogInput(3);
if (Robot.isReal()) {
compressor = new Compressor();
}
LiveWindow.addSensor("Pneumatics", "Pressure Sensor", pressureSensor);
}
/**
* No default command
*/
public void initDefaultCommand() {}
/**
* Start the compressor going. The compressor automatically starts and stops as it goes above and below maximum pressure.
*/
public void start() {
if (Robot.isReal()) {
compressor.start();
}
}
/**
* @return Whether or not the system is fully pressurized.
*/
public boolean isPressurized() {
if (Robot.isReal()) {
return MAX_PRESSURE <= pressureSensor.getVoltage();
} else {
return true; // NOTE: Simulation always has full pressure
}
}
/**
* Puts the pressure on the SmartDashboard.
*/
public void writePressure() {
SmartDashboard.putNumber("Pressure", pressureSensor.getVoltage());
}
}

View File

@@ -0,0 +1,166 @@
package $package.subsystems;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
* The Shooter subsystem handles shooting. The mechanism for shooting is
* slightly complicated because it has to pneumatic cylinders for shooting, and
* a third latch to allow the pressure to partially build up and reduce the
* effect of the airflow. For shorter shots, when full power isn't needed, only
* one cylinder fires.
*
* NOTE: Simulation currently approximates this as as single pneumatic cylinder
* and ignores the latch.
*/
public class Shooter extends Subsystem {
// Devices
DoubleSolenoid piston1;
DoubleSolenoid piston2;
Solenoid latchPiston;
DigitalInput piston1ReedSwitchFront;
DigitalInput piston1ReedSwitchBack;
DigitalInput hotGoalSensor; // NOTE: Currently ignored in simulation
public Shooter() {
// Configure Devices
hotGoalSensor = new DigitalInput(3);
piston1 = new DoubleSolenoid(1, 3, 4);
piston2 = new DoubleSolenoid(1, 5, 6);
latchPiston = new Solenoid(1, 2);
piston1ReedSwitchFront = new DigitalInput(9);
piston1ReedSwitchBack = new DigitalInput(11);
// Put everything to the LiveWindow for testing.
LiveWindow.addSensor("Shooter", "Hot Goal Sensor", hotGoalSensor);
LiveWindow.addSensor("Shooter", "Piston1 Reed Switch Front ",
piston1ReedSwitchFront);
LiveWindow.addSensor("Shooter", "Piston1 Reed Switch Back ",
piston1ReedSwitchBack);
LiveWindow.addActuator("Shooter", "Latch Piston", latchPiston);
}
/**
* No default command.
*/
public void initDefaultCommand() {}
/**
* Extend both solenoids to shoot.
*/
public void extendBoth() {
piston1.set(DoubleSolenoid.Value.kForward);
piston2.set(DoubleSolenoid.Value.kForward);
}
/**
* Retract both solenoids to prepare to shoot.
*/
public void retractBoth() {
piston1.set(DoubleSolenoid.Value.kReverse);
piston2.set(DoubleSolenoid.Value.kReverse);
}
/**
* Extend solenoid 1 to shoot.
*/
public void extend1() {
piston1.set(DoubleSolenoid.Value.kForward);
}
/**
* Retract solenoid 1 to prepare to shoot.
*/
public void retract1() {
piston1.set(DoubleSolenoid.Value.kReverse);
}
/**
* Extend solenoid 2 to shoot.
*/
public void extend2() {
piston2.set(DoubleSolenoid.Value.kReverse);
}
/**
* Retract solenoid 2 to prepare to shoot.
*/
public void retract2() {
piston2.set(DoubleSolenoid.Value.kForward);
}
/**
* Turns off the piston1 double solenoid. This won't actuate anything
* because double solenoids preserve their state when turned off. This
* should be called in order to reduce the amount of time that the coils are
* powered.
*/
public void off1() {
piston1.set(DoubleSolenoid.Value.kOff);
}
/**
* Turns off the piston1 double solenoid. This won't actuate anything
* because double solenoids preserve their state when turned off. This
* should be called in order to reduce the amount of time that the coils are
* powered.
*/
public void off2() {
piston2.set(DoubleSolenoid.Value.kOff);
}
/**
* Release the latch so that we can shoot
*/
public void unlatch() {
latchPiston.set(true);
}
/**
* Latch so that pressure can build up and we aren't limited by air flow.
*/
public void latch() {
latchPiston.set(false);
}
/**
* Toggles the latch postions
*/
public void toggleLatchPosition() {
latchPiston.set(!latchPiston.get());
}
/**
* @return Whether or not piston 1 is fully extended.
*/
public boolean piston1IsExtended() {
return !piston1ReedSwitchFront.get();
}
/**
* @return Whether or not piston 1 is fully retracted.
*/
public boolean piston1IsRetracted() {
return !piston1ReedSwitchBack.get();
}
/**
* Turns off all double solenoids. Double solenoids hold their position when
* they are turned off. We should turn them off whenever possible to extend
* the life of the coils
*/
public void offBoth() {
piston1.set(DoubleSolenoid.Value.kOff);
piston2.set(DoubleSolenoid.Value.kOff);
}
/**
* @return Whether or not the goal is hot as read by the banner sensor
*/
public boolean goalIsHot() {
return hotGoalSensor.get();
}
}

View File

@@ -0,0 +1,23 @@
package $package.triggers;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.buttons.*;
/**
* A custom button that is triggered when two buttons on a Joystick are
* simultaneously pressed.
*/
public class DoubleButton extends Trigger {
private Joystick joy;
private int button1, button2;
public DoubleButton(Joystick joy, int button1, int button2) {
this.joy = joy;
this.button1 = button1;
this.button2 = button2;
}
public boolean get() {
return joy.getRawButton(button1) && joy.getRawButton(button2);
}
}

View File

@@ -84,4 +84,66 @@
<file source="examples/GearsBot/src/org/usfirst/frc/team190/robot/subsystems/Wrist.java" destination="src/$package-dir/subsystems/Wrist.java"></file>
</files>
</example>
<example>
<name>PacGoat</name>
<description>A fully functional example CommandBased program for FRC Team 190&#39;s 2014 robot. This code can run on your computer if it supports simulation.</description>
<tags>
<tag>CommandBased Robot</tag>
<tag>Simulation</tag>
<tag>2014 Season</tag>
</tags>
<packages>
<package>src/$package-dir</package>
<package>src/$package-dir/commands</package>
<package>src/$package-dir/subsystems</package>
<package>src/$package-dir/triggers</package>
</packages>
<files>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/OI.java"
destination="src/$package-dir/OI.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/Robot.java"
destination="src/$package-dir/Robot.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/CheckForHotGoal.java"
destination="src/$package-dir/commands/CheckForHotGoal.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/CloseClaw.java"
destination="src/$package-dir/commands/CloseClaw.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/Collect.java"
destination="src/$package-dir/commands/Collect.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/DriveAndShootAutonomous.java"
destination="src/$package-dir/commands/DriveAndShootAutonomous.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/DriveForward.java"
destination="src/$package-dir/commands/DriveForward.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/DriveWithJoystick.java"
destination="src/$package-dir/commands/DriveWithJoystick.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/ExtendShooter.java"
destination="src/$package-dir/commands/ExtendShooter.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/LowGoal.java"
destination="src/$package-dir/commands/LowGoal.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/OpenClaw.java"
destination="src/$package-dir/commands/OpenClaw.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/SetCollectionSpeed.java"
destination="src/$package-dir/commands/SetCollectionSpeed.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/SetPivotSetpoint.java"
destination="src/$package-dir/commands/SetPivotSetpoint.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/Shoot.java"
destination="src/$package-dir/commands/Shoot.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/WaitForBall.java"
destination="src/$package-dir/commands/WaitForBall.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/commands/WaitForPressure.java"
destination="src/$package-dir/commands/WaitForPressure.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/subsystems/Collector.java"
destination="src/$package-dir/subsystems/Collector.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/subsystems/DriveTrain.java"
destination="src/$package-dir/subsystems/DriveTrain.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/subsystems/Pivot.java"
destination="src/$package-dir/subsystems/Pivot.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/subsystems/Pneumatics.java"
destination="src/$package-dir/subsystems/Pneumatics.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/subsystems/Shooter.java"
destination="src/$package-dir/subsystems/Shooter.java"></file>
<file source="examples/PacGoat/src/org/usfirst/frc/team190/pacgoat/triggers/DoubleButton.java"
destination="src/$package-dir/triggers/DoubleButton.java"></file>
</files>
</example>
</examples>