From: Shivani Ghanta Date: Sat, 21 Jan 2017 21:50:27 +0000 (-0800) Subject: Delete StopWinch and Climber subsystem, edit javadoc comments X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=commitdiff_plain;h=411129cd6662a65b5a19f1392861c54a4c5ce698 Delete StopWinch and Climber subsystem, edit javadoc comments --- diff --git a/src/org/usfirst/frc/team3501/robot/Constants.java b/src/org/usfirst/frc/team3501/robot/Constants.java index bbbb4cc..c93d643 100644 --- a/src/org/usfirst/frc/team3501/robot/Constants.java +++ b/src/org/usfirst/frc/team3501/robot/Constants.java @@ -27,12 +27,6 @@ public class Constants { public static final int ENCODER_RIGHT_B = 3; } - public static class Climber { - // MOTOR CONTROLLERS - public static final int MOTOR = 1; - - } - public static enum Direction { LEFT, RIGHT, DOWN, UP, FORWARD, BACKWARD; } diff --git a/src/org/usfirst/frc/team3501/robot/Robot.java b/src/org/usfirst/frc/team3501/robot/Robot.java index 9d178da..b18f7a5 100644 --- a/src/org/usfirst/frc/team3501/robot/Robot.java +++ b/src/org/usfirst/frc/team3501/robot/Robot.java @@ -1,7 +1,6 @@ package org.usfirst.frc.team3501.robot; import org.usfirst.frc.team3501.robot.commands.driving.TimeDrive; -import org.usfirst.frc.team3501.robot.subsystems.Climber; import org.usfirst.frc.team3501.robot.subsystems.DriveTrain; import org.usfirst.frc.team3501.robot.subsystems.Shooter; @@ -11,14 +10,12 @@ import edu.wpi.first.wpilibj.command.Scheduler; public class Robot extends IterativeRobot { private static DriveTrain driveTrain; private static OI oi; - private static Climber climber; private static Shooter shooter; @Override public void robotInit() { driveTrain = DriveTrain.getDriveTrain(); oi = OI.getOI(); - climber = Climber.getClimber(); shooter = Shooter.getShooter(); } @@ -27,18 +24,10 @@ public class Robot extends IterativeRobot { return DriveTrain.getDriveTrain(); } - public static Climber getClimber() { - return Climber.getClimber(); - } - public static OI getOI() { return OI.getOI(); } - public static Climber getClimber() { - return Climber.getClimber(); - } - public static Shooter getShooter() { return Shooter.getShooter(); } diff --git a/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinch.java b/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinch.java index 5acd6d1..f02ed62 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinch.java +++ b/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinch.java @@ -7,7 +7,7 @@ import edu.wpi.first.wpilibj.command.Command; /** * This command runs the winch at a specified speed and time in seconds when the - * button triggering it is pressed. + * button triggering it is pressed. This command also runs the drive train. * * pre-condition: This command is run by a button in OI. The robot must be * attached to the rope. @@ -28,12 +28,15 @@ public class RunWinch extends Command { private double motorVal; /** + * See JavaDoc comment in class for details * - * @author shivanighanta - * + * @param time + * time in seconds to run the winch + * @param motorVal + * value range is from -1 to 1 */ public RunWinch(double time, double motorVal) { - requires(Robot.getClimber()); + requires(Robot.getDriveTrain()); this.time = time; this.motorVal = motorVal; } @@ -41,11 +44,11 @@ public class RunWinch extends Command { @Override protected void initialize() { timer.start(); - Robot.getClimber().setMotorValue(motorVal); } @Override protected void execute() { + Robot.getDriveTrain().setMotorValues(motorVal, motorVal); } @@ -56,7 +59,8 @@ public class RunWinch extends Command { @Override protected void end() { - Robot.getClimber().stop(); + Robot.getDriveTrain().stop(); + } @Override diff --git a/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinchContinuous.java b/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinchContinuous.java index f99af49..6b8209b 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinchContinuous.java +++ b/src/org/usfirst/frc/team3501/robot/commands/climber/RunWinchContinuous.java @@ -6,7 +6,7 @@ import edu.wpi.first.wpilibj.command.Command; /** * This command will run the winch motor continuously until the button - * triggering it is released. + * triggering it is released. This command also runs the drive train. * * pre-condition: This command must be run by a button in OI. The robot must be * attached to the rope. @@ -23,17 +23,19 @@ public class RunWinchContinuous extends Command { private double motorVal; /** - * + * See JavaDoc comment in class for details + * * @param motorVal + * value range is from -1 to 1 */ public RunWinchContinuous(double motorVal) { - requires(Robot.getClimber()); + requires(Robot.getDriveTrain()); this.motorVal = motorVal; } @Override protected void initialize() { - Robot.getClimber().setMotorValue(motorVal); + Robot.getDriveTrain().setMotorValues(motorVal, motorVal); } @@ -44,12 +46,12 @@ public class RunWinchContinuous extends Command { @Override protected boolean isFinished() { - return !Robot.getOI().toggleWinch.get(); + return false; } @Override protected void end() { - Robot.getClimber().stop(); + } @Override diff --git a/src/org/usfirst/frc/team3501/robot/commands/climber/StopWinch.java b/src/org/usfirst/frc/team3501/robot/commands/climber/StopWinch.java deleted file mode 100644 index a119c91..0000000 --- a/src/org/usfirst/frc/team3501/robot/commands/climber/StopWinch.java +++ /dev/null @@ -1,47 +0,0 @@ -package org.usfirst.frc.team3501.robot.commands.climber; - -import org.usfirst.frc.team3501.robot.Robot; - -import edu.wpi.first.wpilibj.command.Command; - -/** - * This command stops the winch - * - * post-condition: the motor values are set to 0. - * - * @author shivanighanta - * - */ -public class StopWinch extends Command { - /** - * - */ - public StopWinch() { - requires(Robot.getClimber()); - - } - - @Override - protected void initialize() { - } - - @Override - protected void execute() { - } - - @Override - protected boolean isFinished() { - return true; - } - - @Override - protected void end() { - Robot.getClimber().stop(); - - } - - @Override - protected void interrupted() { - end(); - } -} diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/Climber.java b/src/org/usfirst/frc/team3501/robot/subsystems/Climber.java deleted file mode 100644 index 3d49f90..0000000 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Climber.java +++ /dev/null @@ -1,32 +0,0 @@ -package org.usfirst.frc.team3501.robot.subsystems; - -import org.usfirst.frc.team3501.robot.Constants; - -import com.ctre.CANTalon; - -import edu.wpi.first.wpilibj.command.Subsystem; - -public class Climber extends Subsystem { - private static Climber climber; - private final CANTalon motor; - - private Climber() { - motor = new CANTalon(Constants.Climber.MOTOR); - } - - public static Climber getClimber() { - if (climber == null) { - climber = new Climber(); - } - return climber; - } - - public void stop() { - setMotorValue(0); - } - - public void setMotorValue(final double val) { - motor.set(MOTOR); - - } -}