From fb39b56c900b6e11b3e0fe0f5d8d9cf85ad4c6f6 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 14:42:20 -0500 Subject: [PATCH 01/26] removed counter object in preparation for encoder over cantalon --- Robot2016/src/Robot.cpp | 4 +--- Robot2016/src/Shooter.h | 6 +----- 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 2cc4f0a..e63ffd9 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -19,16 +19,14 @@ class Robot: public IterativeRobot RobotDrive drive; Shooter shooter; Joystick driver_stick, operator_stick; - Counter ramp_height; public: Robot(): - left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-spliter + left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter right_drive(1), // Right DriveTrain Talons plug // left wheel 2 shooter1(10), // shooter drive 1 shooter2(11), // shooter drive 2 ramp(12), drive(&left_drive, &right_drive), - ramp_height(), shooter( // initialize Shooter object. &shooter1, &shooter2, &ramp, &ramp_height), driver_stick(0), // right stick (operator) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 8b7a833..7d498cd 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -34,12 +34,11 @@ public: * s2 is also for the pickup-mechanism and can be controlled independently. * */ - Shooter(CANTalon *s1, CANTalon *s2, CANTalon *r, Counter *h) { + Shooter(CANTalon *s1, CANTalon *s2, CANTalon *r) { shooterDrive = new RobotDrive(s1, s2); pickup = s2; ramp = r; rampState = Uncalibrated; - rampHeight = h; } /** @@ -58,7 +57,6 @@ public: delete shooterDrive; delete pickup; delete ramp; - delete rampHeight; } void PickUp(bool state = true) { @@ -77,7 +75,6 @@ public: } else { ramp->Set(0); - rampHeight->Reset(); } } } @@ -98,7 +95,6 @@ private: RobotDrive *shooterDrive; CANTalon *pickup; CANTalon *ramp; - Counter *rampHeight; RampState rampState; RampState targetState; From ef9db9032b681562b2143fb2229e9011f428da16 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 14:48:39 -0500 Subject: [PATCH 02/26] missed an instance of the counter --- Robot2016/src/Robot.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index e63ffd9..7d56368 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -52,7 +52,6 @@ private: chooser->AddDefault(autoNameDefault, (void*)&autoNameDefault); chooser->AddObject(autoNameCustom, (void*)&autoNameCustom); SmartDashboard::PutData("Auto Modes", chooser); - ramp_height.SetUpSource(1); ramp.Enable(); shooter1.Enable(); shooter2.Enable(); From b4d5ead23a923598afb054b6672c4c6617c83252 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 14:56:58 -0500 Subject: [PATCH 03/26] bugfix, debug code for encoder. --- Robot2016/src/Robot.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 7d56368..05563dd 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -28,7 +28,7 @@ public: ramp(12), drive(&left_drive, &right_drive), shooter( // initialize Shooter object. - &shooter1, &shooter2, &ramp, &ramp_height), + &shooter1, &shooter2, &ramp), driver_stick(0), // right stick (operator) operator_stick(1) // left stick (driver) { @@ -104,6 +104,7 @@ private: void TeleopPeriodic() { + std::cout << "Ramp position: "<< ramp.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); // This is shit code for testing. Replace it with real code. From 470a4b6f4bd624fd2d6a8295d2c07fc6c8a93542 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 15:23:07 -0500 Subject: [PATCH 04/26] impotent debug code! --- Robot2016/src/Shooter.h | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 7d498cd..7d7d618 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -35,7 +35,8 @@ public: * */ Shooter(CANTalon *s1, CANTalon *s2, CANTalon *r) { - shooterDrive = new RobotDrive(s1, s2); + // shooterDrive = new RobotDrive(s1, s2); + launcher = s1; pickup = s2; ramp = r; rampState = Uncalibrated; @@ -54,13 +55,14 @@ public: } virtual ~Shooter() { - delete shooterDrive; + delete launcher; delete pickup; delete ramp; } void PickUp(bool state = true) { pickup->Set((float) (state * PICKUP_POWER)); + std::cout << "picking up!\n"; } void SetRamp(RampState state) { @@ -88,11 +90,14 @@ public: } void SetPower(float power) { - shooterDrive->TankDrive(power, -power, false); + pickup->Set(power); + launcher->Set(power); + std::cout << "setting shooter power" << std::endl; } private: RobotDrive *shooterDrive; + CANTalon *launcher; CANTalon *pickup; CANTalon *ramp; From a8642a87d9358d7999037ad82067ac521e302787 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 18:56:38 -0500 Subject: [PATCH 05/26] Made sure shooter power from the throttle will only be used when the throttle is moved. Probably. --- Robot2016/src/Robot.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 05563dd..c7964b8 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -19,6 +19,7 @@ class Robot: public IterativeRobot RobotDrive drive; Shooter shooter; Joystick driver_stick, operator_stick; + float power; public: Robot(): left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter @@ -100,6 +101,7 @@ private: { shooter.CalibrateRamp(); shooter.SetRamp(Shoot); // start in the full up position! + power = 0; } void TeleopPeriodic() @@ -143,10 +145,14 @@ private: inverting = false; } - float power = (1.0 - operator_stick.GetThrottle()) / 2.0; - shooter.SetPower(power); + if(((1.0 - operator_stick.GetThrottle()) / 2.0) > power + 0.005||((1.0 - operator_stick.GetThrottle()) / 2.0) < power -0.005) + { + power = (1.0 - operator_stick.GetThrottle()) / 2.0; + shooter.SetPower(power); + } } + void TestPeriodic() { lw->Run(); From fbae5efebf9c985c0b76408036751cd97b04ea46 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 19:11:51 -0500 Subject: [PATCH 06/26] Switched the shooter controller addresses to reflect reality. --- Robot2016/src/Robot.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index c7964b8..4913f17 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -24,8 +24,8 @@ public: Robot(): left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter right_drive(1), // Right DriveTrain Talons plug // left wheel 2 - shooter1(10), // shooter drive 1 - shooter2(11), // shooter drive 2 + shooter1(11), // shooter drive 1 + shooter2(10), // shooter drive 2 ramp(12), drive(&left_drive, &right_drive), shooter( // initialize Shooter object. From c36024a86df5433edf721914d0ddf1ee92e1bcb7 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 19:55:20 -0500 Subject: [PATCH 07/26] placeholder for encoder code in Shooter.h --- Robot2016/src/Shooter.h | 22 +++++++++++++++++----- 1 file changed, 17 insertions(+), 5 deletions(-) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 7d7d618..83edd21 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -70,13 +70,25 @@ public: // Move the Ramp to the set position. switch (state) { - case Shoot: - if (ramp->GetForwardLimitOK()) + case Shoot: { - ramp->Set(1); - } else + if (ramp->GetForwardLimitOK()) + { + ramp->Set(1); + } else + { + ramp->Set(0); + } + } + case Half: { - ramp->Set(0); + //yeah, put something here when you get the encoder working. + std::cout << "Hey! Didja install an encoder? Because this is placeholder that Aidan would have removed if you had installed one and told him about it.\n"; + } + case Down: + { + //see half. + std::cout << "Hey! Didja install an encoder? Because this is placeholder that Aidan would have removed if you had installed one and told him about it.\n"; } } } From 2534f700f1e5e08e2fd8172676609dd08126c1b9 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Wed, 10 Feb 2016 20:13:33 -0500 Subject: [PATCH 08/26] raised PICKUP_POWER to 0.8 --- Robot2016/src/Shooter.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 83edd21..ccb3c9b 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -8,7 +8,7 @@ #ifndef SRC_SHOOTER_H_ #define SRC_SHOOTER_H_ -#define PICKUP_POWER 0.5 +#define PICKUP_POWER 0.8 #define RAMP_LOWER_DURATION 2 //Rotations. From 99fb8c19e6e6522e220952881cc38b3aee872ade Mon Sep 17 00:00:00 2001 From: Dieter Brehm Date: Wed, 10 Feb 2016 21:24:35 -0500 Subject: [PATCH 09/26] Changed todo to reflect lack of ramp. --- Robot2016/src/Shooter.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index ccb3c9b..fe94f43 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -48,8 +48,7 @@ public: */ RampState CalibrateRamp() { // TODO: - // Raise ramp until limit switch is triggered, - // then lower the ramp to its lower limit. + // Ramp no longer exists, replace with more wheels. return Down; } From eee7649da79df1fc7661aba792bca5b204dfd496 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Thu, 11 Feb 2016 16:18:58 -0500 Subject: [PATCH 10/26] Made shooter_power private instead of global because that actually makes sense. --- Robot2016/src/Robot.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 4913f17..2e61871 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -19,7 +19,6 @@ class Robot: public IterativeRobot RobotDrive drive; Shooter shooter; Joystick driver_stick, operator_stick; - float power; public: Robot(): left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter @@ -40,6 +39,7 @@ private: // instance variables bool pickupRunning; // don't want to spam the Talon with set messages. Toggle the pickup when a button is pressed or released. bool inverting; + float shooter_power; LiveWindow *lw = LiveWindow::GetInstance(); SendableChooser *chooser; @@ -145,10 +145,10 @@ private: inverting = false; } - if(((1.0 - operator_stick.GetThrottle()) / 2.0) > power + 0.005||((1.0 - operator_stick.GetThrottle()) / 2.0) < power -0.005) + if(((1.0 - operator_stick.GetThrottle()) / 2.0) > shooter_power + 0.005||((1.0 - operator_stick.GetThrottle()) / 2.0) < shooter_power -0.005) { - power = (1.0 - operator_stick.GetThrottle()) / 2.0; - shooter.SetPower(power); + shooter_power = (1.0 - operator_stick.GetThrottle()) / 2.0; + shooter.SetPower(shooter_power); } } From 8c91ac34dbca1c924ec6a10cd38352b0a819082e Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Thu, 11 Feb 2016 16:51:13 -0500 Subject: [PATCH 11/26] purged the concept of a ramp --- Robot2016/src/Robot.cpp | 9 ++---- Robot2016/src/Shooter.h | 64 +++-------------------------------------- 2 files changed, 6 insertions(+), 67 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 2e61871..a4073cb 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -53,12 +53,12 @@ private: chooser->AddDefault(autoNameDefault, (void*)&autoNameDefault); chooser->AddObject(autoNameCustom, (void*)&autoNameCustom); SmartDashboard::PutData("Auto Modes", chooser); - ramp.Enable(); shooter1.Enable(); shooter2.Enable(); left_drive.SetInverted(true); right_drive.SetInverted(true); inverting = false; + shooter_power = 0; } @@ -74,9 +74,6 @@ private: */ void AutonomousInit() { - shooter.CalibrateRamp(); - shooter.SetRamp(Shoot); - autoSelected = *((std::string*)chooser->GetSelected()); //std::string autoSelected = SmartDashboard::GetString("Auto Selector", autoNameDefault); std::cout << "Auto selected: " << autoSelected << std::endl; @@ -99,9 +96,7 @@ private: void TeleopInit() { - shooter.CalibrateRamp(); - shooter.SetRamp(Shoot); // start in the full up position! - power = 0; + } void TeleopPeriodic() diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index fe94f43..2486d8a 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -9,28 +9,11 @@ #define SRC_SHOOTER_H_ #define PICKUP_POWER 0.8 -#define RAMP_LOWER_DURATION 2 //Rotations. - - -/** - * You can use the values assigned to each of these values as the number - * of rotations to run the motor down from the "Shoot" position. - * - * This might not be the best way to do it, and also requires that we - * figure out how to read the Hall Effect signal from the motor. - */ -enum RampState { - Shoot = 0, // 0 rotations - Half = (RAMP_LOWER_DURATION / 2), // 1 rotation? - Down = RAMP_LOWER_DURATION, // 2 rotations? - Uncalibrated = -1, - Transitioning = -2 -}; class Shooter { public: /** - * Shooter talons and ramp talon. + * Shooter talons and launch-spinny talon. * s2 is also for the pickup-mechanism and can be controlled independently. * */ @@ -38,25 +21,18 @@ public: // shooterDrive = new RobotDrive(s1, s2); launcher = s1; pickup = s2; - ramp = r; - rampState = Uncalibrated; + launch_spinny = r; } /** * Call this method on TeleopInit so that the ramp is properly * set at the beginning of the match. */ - RampState CalibrateRamp() { - // TODO: - // Ramp no longer exists, replace with more wheels. - - return Down; - } virtual ~Shooter() { delete launcher; delete pickup; - delete ramp; + delete launch_spinny; } void PickUp(bool state = true) { @@ -64,34 +40,6 @@ public: std::cout << "picking up!\n"; } - void SetRamp(RampState state) { - // TODO: - // Move the Ramp to the set position. - switch (state) - { - case Shoot: - { - if (ramp->GetForwardLimitOK()) - { - ramp->Set(1); - } else - { - ramp->Set(0); - } - } - case Half: - { - //yeah, put something here when you get the encoder working. - std::cout << "Hey! Didja install an encoder? Because this is placeholder that Aidan would have removed if you had installed one and told him about it.\n"; - } - case Down: - { - //see half. - std::cout << "Hey! Didja install an encoder? Because this is placeholder that Aidan would have removed if you had installed one and told him about it.\n"; - } - } - } - /** * Call this to run the pickup backwards if the ball gets jammed somehow... */ @@ -110,11 +58,7 @@ private: RobotDrive *shooterDrive; CANTalon *launcher; CANTalon *pickup; - CANTalon *ramp; - - RampState rampState; - RampState targetState; - RampState previousState; + CANTalon *launch_spinny; }; #endif /* SRC_SHOOTER_H_ */ From 7b6b6f339720613ed06202a6faf2fbbc189cd06a Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Thu, 11 Feb 2016 17:17:42 -0500 Subject: [PATCH 12/26] launch spinny does stuff --- Robot2016/src/Robot.cpp | 14 +++++++------- Robot2016/src/Shooter.h | 3 ++- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index a4073cb..3111ca2 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -15,7 +15,7 @@ class Robot: public IterativeRobot { Talon left_drive, right_drive; CANTalon shooter1, shooter2, - ramp; + launch_spinny; RobotDrive drive; Shooter shooter; Joystick driver_stick, operator_stick; @@ -25,10 +25,10 @@ public: right_drive(1), // Right DriveTrain Talons plug // left wheel 2 shooter1(11), // shooter drive 1 shooter2(10), // shooter drive 2 - ramp(12), + launch_spinny(12), drive(&left_drive, &right_drive), shooter( // initialize Shooter object. - &shooter1, &shooter2, &ramp), + &shooter1, &shooter2, &launch_spinny), driver_stick(0), // right stick (operator) operator_stick(1) // left stick (driver) { @@ -101,21 +101,21 @@ private: void TeleopPeriodic() { - std::cout << "Ramp position: "<< ramp.GetEncPosition() << std::endl; + std::cout << "Ramp position: "<< launch_spinny.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); // This is shit code for testing. Replace it with real code. if(operator_stick.GetRawButton(RAMP_RAISE)) { - ramp.Set(1); + launch_spinny.Set(1); } else if(operator_stick.GetRawButton(RAMP_LOWER)) { - ramp.Set(-1); + launch_spinny.Set(-1); } else { - ramp.Set(0); + launch_spinny.Set(0); } if(operator_stick.GetRawButton(THUMB) && !pickupRunning) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 2486d8a..f63bdf1 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -8,7 +8,7 @@ #ifndef SRC_SHOOTER_H_ #define SRC_SHOOTER_H_ -#define PICKUP_POWER 0.8 +#define PICKUP_POWER 1.0 class Shooter { public: @@ -37,6 +37,7 @@ public: void PickUp(bool state = true) { pickup->Set((float) (state * PICKUP_POWER)); + launch_spinny->Set(-1.0*PICKUP_POWER); std::cout << "picking up!\n"; } From a51cdfcb079bd78789cd7b53705638adcc0bc0e1 Mon Sep 17 00:00:00 2001 From: Jason Date: Thu, 11 Feb 2016 20:40:41 -0500 Subject: [PATCH 13/26] Added comments about the use of the boolean variables in the TeleopPeriodic method --- Robot2016/src/Robot.cpp | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 3111ca2..8e4b800 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -118,6 +118,13 @@ private: launch_spinny.Set(0); } + /* + * Run the Shooter only while the THUMB button is held down on the operator stick. + * the 'pickupRunning' boolean is there to prevent the shooter from calling PickUp + * every itteration of the TeleopPeriodic method (once every 10ms!) + * The pickup is disabled when the thumb button is released, but the code still + * has 'pickupRunning' as true. + */ if(operator_stick.GetRawButton(THUMB) && !pickupRunning) { shooter.PickUp(); @@ -129,6 +136,12 @@ private: pickupRunning = false; } + /* + * The 'inverting' variable is used to make sure that the drive train isn't getting + * inverted every itteration of the TeleopPeriodic method while the button is held down. + * This is important because the TeleopPeriodic method executes something like once every 10ms. + * Thus, this if-else if pair make the button a toggle. + */ if(driver_stick.GetRawButton(THUMB) && !inverting) { left_drive.SetInverted(!left_drive.GetInverted()); @@ -140,7 +153,10 @@ private: inverting = false; } - if(((1.0 - operator_stick.GetThrottle()) / 2.0) > shooter_power + 0.005||((1.0 - operator_stick.GetThrottle()) / 2.0) < shooter_power -0.005) + + + if(((1.0 - operator_stick.GetThrottle()) / 2.0) > shooter_power + 0.005 + || ((1.0 - operator_stick.GetThrottle()) / 2.0) < shooter_power -0.005) { shooter_power = (1.0 - operator_stick.GetThrottle()) / 2.0; shooter.SetPower(shooter_power); From b4bbdf092b69c4be6a8e13a5946b95210f54f119 Mon Sep 17 00:00:00 2001 From: Jason Date: Thu, 11 Feb 2016 20:48:03 -0500 Subject: [PATCH 14/26] Added a define for DEADZONE_RADIUS and implemented it in the shooter power setting within TeleopPeriodic. --- Robot2016/src/Robot.cpp | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 8e4b800..36cef0c 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -9,6 +9,10 @@ #define RAMP_RAISE 3 // Button 3 for Raising Ramp #define RAMP_LOWER 4 // Button 4 to lower ramp. +#define DEADZONE_RADIUS 0.05 // Deadzone Radius prevents tiny twitches in the joystick's value from + // affecting the robot. Use this for cleaning up drive train and shooter. + // Also used for detecting changes in an axis' value. + #endif // BUTTON_LAYOUT class Robot: public IterativeRobot @@ -153,16 +157,23 @@ private: inverting = false; } + float opThrottle = SaneThrottle(operator_stick.GetThrottle()); - - if(((1.0 - operator_stick.GetThrottle()) / 2.0) > shooter_power + 0.005 - || ((1.0 - operator_stick.GetThrottle()) / 2.0) < shooter_power -0.005) + if( opThrottle > shooter_power + DEADZONE_RADIUS + || opThrottle < shooter_power - DEADZONE_RADIUS) { - shooter_power = (1.0 - operator_stick.GetThrottle()) / 2.0; - shooter.SetPower(shooter_power); + shooter.SetPower(opThrottle); } } + /** + * Takes the gross raw throttle input from joystick and returns a + * value between 0.0-1.0 (no negative values) + */ + float SaneThrottle(float rawThrottle) + { + return ((1.0 - rawThrottle) / 2.0); + } void TestPeriodic() { From 5211275da5f89ae97dedb8264b2799db95652988 Mon Sep 17 00:00:00 2001 From: Jason Date: Thu, 11 Feb 2016 21:24:32 -0500 Subject: [PATCH 15/26] Added comments and info for the shooter logic. I emailed you a flow chart also... --- Robot2016/src/Robot.cpp | 20 +++++++++++++++++- Robot2016/src/Shooter.h | 45 ++++++++++++++++++++++++++++++++++------- 2 files changed, 57 insertions(+), 8 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 36cef0c..6de81fa 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -62,6 +62,7 @@ private: left_drive.SetInverted(true); right_drive.SetInverted(true); inverting = false; + pickupRunning = false; shooter_power = 0; } @@ -156,7 +157,24 @@ private: { inverting = false; } - + + + /* + * Unlike the previous actions, this method does need to be called every itteration of + * TeleopPeriodic. This is because the logic running this operation needs to be checked + * Every time the method is called. This cannot be a loop in the Shoot method because + * that would lock the robot every time the trigger is hit. + */ + if(operator_stick.GetRawButton(TRIGGER)) + { + shooter.Shoot(); + } + else + { + shooter.StopShooter(); + } + + // This code will become obsolete after the Shooter logic is complete. float opThrottle = SaneThrottle(operator_stick.GetThrottle()); if( opThrottle > shooter_power + DEADZONE_RADIUS diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index f63bdf1..22e2eb8 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -10,18 +10,23 @@ #define PICKUP_POWER 1.0 -class Shooter { +class Shooter +{ public: + /** * Shooter talons and launch-spinny talon. * s2 is also for the pickup-mechanism and can be controlled independently. * */ - Shooter(CANTalon *s1, CANTalon *s2, CANTalon *r) { + Shooter(CANTalon *s1, CANTalon *s2, CANTalon *r) + { // shooterDrive = new RobotDrive(s1, s2); launcher = s1; pickup = s2; launch_spinny = r; + ready = true; + shotClock = Timer(); } /** @@ -29,13 +34,35 @@ public: * set at the beginning of the match. */ - virtual ~Shooter() { + virtual ~Shooter() + { delete launcher; delete pickup; delete launch_spinny; } - - void PickUp(bool state = true) { + + void StopShooter() + { + ready = true; + launch_spinny.Set(0); + launcher.Set(0); + pickup.Set(0); + } + + void Shoot() + { + // TODO: Shooter Logic should go as follows: + + /* + Assuming a ball is held in the shooter. When the trigger is pulled, + the launch-spinny should be STOPPED. Start a Timer object counting + When... too hard to write.. I emailed you a flow chart. + */ + + } + + void PickUp(bool state = true) + { pickup->Set((float) (state * PICKUP_POWER)); launch_spinny->Set(-1.0*PICKUP_POWER); std::cout << "picking up!\n"; @@ -49,17 +76,21 @@ public: pickup->Set(-1 * PICKUP_POWER); } - void SetPower(float power) { + void SetPower(float power) + { pickup->Set(power); launcher->Set(power); std::cout << "setting shooter power" << std::endl; } private: - RobotDrive *shooterDrive; + //RobotDrive *shooterDrive; CANTalon *launcher; CANTalon *pickup; CANTalon *launch_spinny; + + Timer shotClock; + bool ready; }; #endif /* SRC_SHOOTER_H_ */ From 3c3d14f01b1a763effbd008a1fc8a850bcb00c93 Mon Sep 17 00:00:00 2001 From: Jason Date: Thu, 11 Feb 2016 22:26:11 -0500 Subject: [PATCH 16/26] added SPINUP_TIME define for the shotClock Timer. Adjust the value of this define to wait longer before shooting the ball into the launch wheel. : --- Robot2016/src/Shooter.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 22e2eb8..f9892bd 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -9,6 +9,7 @@ #define SRC_SHOOTER_H_ #define PICKUP_POWER 1.0 +#define SPINUP_TIME 1.5 // seconds. class Shooter { @@ -89,7 +90,7 @@ private: CANTalon *pickup; CANTalon *launch_spinny; - Timer shotClock; + Timer shotClock; bool ready; }; From deef7fcf202d28ebf6d12d31c87fe7c882a08c9d Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Fri, 12 Feb 2016 19:37:36 -0500 Subject: [PATCH 17/26] ramp reinstated --- Robot2016/src/Robot.cpp | 12 ++++++++++-- Robot2016/src/Shooter.h | 23 +++++++++++++++++++---- 2 files changed, 29 insertions(+), 6 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 6de81fa..8826677 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -112,17 +112,25 @@ private: // This is shit code for testing. Replace it with real code. if(operator_stick.GetRawButton(RAMP_RAISE)) { - launch_spinny.Set(1); + //launch_spinny.Set(1); + shooter.RaiseRamp(); } else if(operator_stick.GetRawButton(RAMP_LOWER)) { - launch_spinny.Set(-1); + //launch_spinny.Set(-1); + shooter.LowerRamp(); + } + else if(operator_stick.GetRawButton(TRIGGER)) + { + shooter.BoostRamp(); } else { launch_spinny.Set(0); } + + /* * Run the Shooter only while the THUMB button is held down on the operator stick. * the 'pickupRunning' boolean is there to prevent the shooter from calling PickUp diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index f9892bd..b273940 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -45,9 +45,24 @@ public: void StopShooter() { ready = true; - launch_spinny.Set(0); - launcher.Set(0); - pickup.Set(0); + launch_spinny->Set(0); + launcher->Set(0); + pickup->Set(0); + } + + void LowerRamp() + { + launch_spinny->Set(-0.1); + } + + void RaiseRamp() + { + launch_spinny->Set(0.1); + } + + void BoostRamp() + { + launch_spinny->Set(0.5); } void Shoot() @@ -65,7 +80,7 @@ public: void PickUp(bool state = true) { pickup->Set((float) (state * PICKUP_POWER)); - launch_spinny->Set(-1.0*PICKUP_POWER); + //launch_spinny->Set(-1.0*PICKUP_POWER); std::cout << "picking up!\n"; } From 99d2397f9b5b441f3de9dc20b6fd5857fcff1534 Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Fri, 12 Feb 2016 21:17:45 -0500 Subject: [PATCH 18/26] Fixed a bunch of logic errors. --- Robot2016/src/Robot.cpp | 7 ++++--- Robot2016/src/Shooter.h | 5 ++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 8826677..6ec1e54 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -61,6 +61,7 @@ private: shooter2.Enable(); left_drive.SetInverted(true); right_drive.SetInverted(true); + launch_spinny.SetInverted(true); inverting = false; pickupRunning = false; shooter_power = 0; @@ -143,7 +144,7 @@ private: shooter.PickUp(); pickupRunning = true; } - else if(pickupRunning) + else if(!operator_stick.GetRawButton(THUMB) && pickupRunning) { shooter.PickUp(false); pickupRunning = false; @@ -185,8 +186,8 @@ private: // This code will become obsolete after the Shooter logic is complete. float opThrottle = SaneThrottle(operator_stick.GetThrottle()); - if( opThrottle > shooter_power + DEADZONE_RADIUS - || opThrottle < shooter_power - DEADZONE_RADIUS) + if(!pickupRunning && ( opThrottle > shooter_power + DEADZONE_RADIUS + || opThrottle < shooter_power - DEADZONE_RADIUS)) { shooter.SetPower(opThrottle); } diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index b273940..7b4705d 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -27,7 +27,6 @@ public: pickup = s2; launch_spinny = r; ready = true; - shotClock = Timer(); } /** @@ -52,12 +51,12 @@ public: void LowerRamp() { - launch_spinny->Set(-0.1); + launch_spinny->Set(-0.25); } void RaiseRamp() { - launch_spinny->Set(0.1); + launch_spinny->Set(0.25); } void BoostRamp() From 2ad0f975b30e9c3274cfa9e028c1cfecdb18dcc9 Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Sat, 13 Feb 2016 11:12:20 -0500 Subject: [PATCH 19/26] Fixed some really bad logic in the shooter... --- Robot2016/src/Robot.cpp | 24 +++++++++++++++++------- Robot2016/src/Shooter.h | 11 ++++++++--- 2 files changed, 25 insertions(+), 10 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 6ec1e54..6dd945d 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -43,6 +43,8 @@ private: // instance variables bool pickupRunning; // don't want to spam the Talon with set messages. Toggle the pickup when a button is pressed or released. bool inverting; + bool ramping; + bool shooting; float shooter_power; LiveWindow *lw = LiveWindow::GetInstance(); @@ -61,9 +63,11 @@ private: shooter2.Enable(); left_drive.SetInverted(true); right_drive.SetInverted(true); - launch_spinny.SetInverted(true); + //launch_spinny.SetInverted(true); inverting = false; pickupRunning = false; + ramping = false; + shooting = false; shooter_power = 0; } @@ -110,22 +114,26 @@ private: std::cout << "Ramp position: "<< launch_spinny.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); + //bool rampDoing = false; // This is shit code for testing. Replace it with real code. - if(operator_stick.GetRawButton(RAMP_RAISE)) + if(!ramping && operator_stick.GetRawButton(RAMP_RAISE)) { //launch_spinny.Set(1); shooter.RaiseRamp(); + ramping =true; } - else if(operator_stick.GetRawButton(RAMP_LOWER)) + else if(!ramping && operator_stick.GetRawButton(RAMP_LOWER)) { //launch_spinny.Set(-1); shooter.LowerRamp(); + ramping = true; } - else if(operator_stick.GetRawButton(TRIGGER)) + else if(!ramping && operator_stick.GetRawButton(TRIGGER)) { shooter.BoostRamp(); + ramping = true; } - else + else if(ramping) { launch_spinny.Set(0); } @@ -174,12 +182,14 @@ private: * Every time the method is called. This cannot be a loop in the Shoot method because * that would lock the robot every time the trigger is hit. */ - if(operator_stick.GetRawButton(TRIGGER)) + if(operator_stick.GetRawButton(TRIGGER) && !shooting) { + shooting = true; shooter.Shoot(); } - else + else if(shooting) { + shooting = false; shooter.StopShooter(); } diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 7b4705d..8dbdc57 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -51,17 +51,22 @@ public: void LowerRamp() { - launch_spinny->Set(-0.25); + launch_spinny->Set(-1); } void RaiseRamp() { - launch_spinny->Set(0.25); + launch_spinny->Set(1); + } + + void StopRamp() + { + launch_spinny->Set(0); } void BoostRamp() { - launch_spinny->Set(0.5); + launch_spinny->Set(1); } void Shoot() From eccd90ea8a0383c949b7703a79cfaf6a4f2bf59b Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Sat, 13 Feb 2016 11:26:07 -0500 Subject: [PATCH 20/26] Now has Sane pickup logic~ --- Robot2016/src/Robot.cpp | 14 +++++++++----- Robot2016/src/Shooter.h | 3 ++- 2 files changed, 11 insertions(+), 6 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 6dd945d..7688ac4 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -9,7 +9,7 @@ #define RAMP_RAISE 3 // Button 3 for Raising Ramp #define RAMP_LOWER 4 // Button 4 to lower ramp. -#define DEADZONE_RADIUS 0.05 // Deadzone Radius prevents tiny twitches in the joystick's value from +#define DEADZONE_RADIUS 0.01 // Deadzone Radius prevents tiny twitches in the joystick's value from // affecting the robot. Use this for cleaning up drive train and shooter. // Also used for detecting changes in an axis' value. @@ -118,24 +118,28 @@ private: // This is shit code for testing. Replace it with real code. if(!ramping && operator_stick.GetRawButton(RAMP_RAISE)) { + std::cout << "Raising Ramp."; //launch_spinny.Set(1); shooter.RaiseRamp(); ramping =true; } else if(!ramping && operator_stick.GetRawButton(RAMP_LOWER)) { + std::cout << "Lowering Ramp."; //launch_spinny.Set(-1); shooter.LowerRamp(); ramping = true; } - else if(!ramping && operator_stick.GetRawButton(TRIGGER)) + /*else if(!ramping && operator_stick.GetRawButton(TRIGGER)) { shooter.BoostRamp(); ramping = true; - } + }*/ else if(ramping) { - launch_spinny.Set(0); + std::cout << "Stopping Ramp."; + shooter.StopRamp(); + ramping = false; } @@ -182,7 +186,7 @@ private: * Every time the method is called. This cannot be a loop in the Shoot method because * that would lock the robot every time the trigger is hit. */ - if(operator_stick.GetRawButton(TRIGGER) && !shooting) + if(operator_stick.GetRawButton(TRIGGER)) { shooting = true; shooter.Shoot(); diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 8dbdc57..a388f33 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -8,7 +8,7 @@ #ifndef SRC_SHOOTER_H_ #define SRC_SHOOTER_H_ -#define PICKUP_POWER 1.0 +#define PICKUP_POWER 0.5 #define SPINUP_TIME 1.5 // seconds. class Shooter @@ -84,6 +84,7 @@ public: void PickUp(bool state = true) { pickup->Set((float) (state * PICKUP_POWER)); + launcher->Set((float) (state * PICKUP_POWER * -1)); //launch_spinny->Set(-1.0*PICKUP_POWER); std::cout << "picking up!\n"; } From c3a621a5c4b471cca19b33c64b55a449d0eb9a9c Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Sat, 13 Feb 2016 12:00:28 -0500 Subject: [PATCH 21/26] some more bug fixes. --- Robot2016/src/Robot.cpp | 20 ++++++++++++++++++-- 1 file changed, 18 insertions(+), 2 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 7688ac4..b356e3d 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -8,6 +8,7 @@ #define THUMB 2 // Thumb button number #define RAMP_RAISE 3 // Button 3 for Raising Ramp #define RAMP_LOWER 4 // Button 4 to lower ramp. +#define UNJAM 11 #define DEADZONE_RADIUS 0.01 // Deadzone Radius prevents tiny twitches in the joystick's value from // affecting the robot. Use this for cleaning up drive train and shooter. @@ -45,6 +46,7 @@ private: bool inverting; bool ramping; bool shooting; + bool unjamming; float shooter_power; LiveWindow *lw = LiveWindow::GetInstance(); @@ -68,6 +70,7 @@ private: pickupRunning = false; ramping = false; shooting = false; + unjamming = false; shooter_power = 0; } @@ -135,7 +138,9 @@ private: shooter.BoostRamp(); ramping = true; }*/ - else if(ramping) + else if(ramping + && !operator_stick.GetRawButton(RAMP_LOWER) + && !operator_stick.GetRawButton(RAMP_RAISE)) { std::cout << "Stopping Ramp."; shooter.StopRamp(); @@ -143,6 +148,17 @@ private: } + if(!unjamming && operator_stick.GetRawButton(UNJAM)) + { + unjamming = true; + shooter.Unjam(); + } + else if(unjamming && !operator_stick.GetRawButton(UNJAM)) + { + shooter.PickUp(false); + unjamming = false; + } + /* * Run the Shooter only while the THUMB button is held down on the operator stick. @@ -191,7 +207,7 @@ private: shooting = true; shooter.Shoot(); } - else if(shooting) + else if(shooting && !operator_stick.GetRawButton(TRIGGER)) { shooting = false; shooter.StopShooter(); From 71e2ec4eba2c78d40e9b6d476e5e9a658ae19080 Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Sat, 13 Feb 2016 12:09:08 -0500 Subject: [PATCH 22/26] removed old debug statements --- Robot2016/src/Robot.cpp | 3 ++- Robot2016/src/Shooter.h | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index b356e3d..cab8ba8 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -114,7 +114,7 @@ private: void TeleopPeriodic() { - std::cout << "Ramp position: "<< launch_spinny.GetEncPosition() << std::endl; + //std::cout << "Ramp position: "<< launch_spinny.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); //bool rampDoing = false; @@ -186,6 +186,7 @@ private: */ if(driver_stick.GetRawButton(THUMB) && !inverting) { + std::cout << "Inverting Drive Train."; left_drive.SetInverted(!left_drive.GetInverted()); right_drive.SetInverted(!right_drive.GetInverted()); inverting = true; diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index a388f33..2ec7e5f 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -86,7 +86,7 @@ public: pickup->Set((float) (state * PICKUP_POWER)); launcher->Set((float) (state * PICKUP_POWER * -1)); //launch_spinny->Set(-1.0*PICKUP_POWER); - std::cout << "picking up!\n"; + //std::cout << "picking up!\n"; } /** @@ -101,7 +101,7 @@ public: { pickup->Set(power); launcher->Set(power); - std::cout << "setting shooter power" << std::endl; + //std::cout << "setting shooter power" << std::endl; } private: From e6934c911785e43cf58b119693ccea731e72d000 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Sat, 13 Feb 2016 16:40:07 -0500 Subject: [PATCH 23/26] enum ShooterState, starts of associated switch, etc. --- Robot2016/src/Robot.cpp | 6 ++++- Robot2016/src/Shooter.h | 57 ++++++++++++++++++++++++++++++++++++++++- 2 files changed, 61 insertions(+), 2 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index cab8ba8..86b0612 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -35,7 +35,7 @@ public: shooter( // initialize Shooter object. &shooter1, &shooter2, &launch_spinny), driver_stick(0), // right stick (operator) - operator_stick(1) // left stick (driver) + operator_stick(1) // left stick (driver) { } @@ -117,6 +117,10 @@ private: //std::cout << "Ramp position: "<< launch_spinny.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); + if (operator_stick.GetRawButton(TRIGGER)) + { + + } //bool rampDoing = false; // This is shit code for testing. Replace it with real code. if(!ramping && operator_stick.GetRawButton(RAMP_RAISE)) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index 2ec7e5f..aeeab87 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -9,7 +9,9 @@ #define SRC_SHOOTER_H_ #define PICKUP_POWER 0.5 +#define LAUNCH_POWER 1 #define SPINUP_TIME 1.5 // seconds. +#define LAUNCH_TIME 0.5 class Shooter { @@ -20,13 +22,24 @@ public: * s2 is also for the pickup-mechanism and can be controlled independently. * */ - Shooter(CANTalon *s1, CANTalon *s2, CANTalon *r) + enum ShooterState + { + READY, + ON_FIRE, + SPINNINGUP, + LAUNCH, + LAUNCHING, + RESETTING + }; + + Shooter(CANTalon *s1, CANTalon *s2, CANTalon *r) { // shooterDrive = new RobotDrive(s1, s2); launcher = s1; pickup = s2; launch_spinny = r; ready = true; + state = READY; } /** @@ -78,6 +91,47 @@ public: the launch-spinny should be STOPPED. Start a Timer object counting When... too hard to write.. I emailed you a flow chart. */ + switch (state) + { + case READY: + { + state = SPINNINGUP; + launch_spinny->Set(-1); + launcher->Set(PICKUP_POWER); + pickup->Set(PICKUP_POWER); + shotClock.Reset(); + shotClock.Start(); + break; + } + case SPINNINGUP: + { + if (shotClock.Get() > SPINUP_TIME) + { + state = LAUNCH; + shotClock.Reset(); + shotClock.Start(); + } else + { + std::cout << "*Goku noises*\n"; + } + break; + } + case LAUNCH: + { + launch_spinny->Set(1); + state = LAUNCHING; + break; + } + case LAUNCHING: + { + if (shotClock.Get() > LAUNCH_TIME) + { + + state = RESETTING; + } + break; + } + } } @@ -109,6 +163,7 @@ private: CANTalon *launcher; CANTalon *pickup; CANTalon *launch_spinny; + ShooterState state; Timer shotClock; bool ready; From 38eb49a964710485b68c51d75da0669f0147f06b Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Sat, 13 Feb 2016 16:46:09 -0500 Subject: [PATCH 24/26] removed a redundant if statement because I'm a doofus. --- Robot2016/src/Robot.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index 86b0612..1af8deb 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -117,10 +117,6 @@ private: //std::cout << "Ramp position: "<< launch_spinny.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); - if (operator_stick.GetRawButton(TRIGGER)) - { - - } //bool rampDoing = false; // This is shit code for testing. Replace it with real code. if(!ramping && operator_stick.GetRawButton(RAMP_RAISE)) From 5bbbf1717ee34b69daab68e87ccaaef1e0549d43 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Mon, 15 Feb 2016 15:14:20 -0500 Subject: [PATCH 25/26] Finished shooter switch. --- Robot2016/src/Shooter.h | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index aeeab87..a8469b7 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -96,9 +96,9 @@ public: case READY: { state = SPINNINGUP; - launch_spinny->Set(-1); - launcher->Set(PICKUP_POWER); - pickup->Set(PICKUP_POWER); + launch_spinny->Set(0); + launcher->Set(LAUNCH_POWER); + pickup->Set(LAUNCH_POWER); shotClock.Reset(); shotClock.Start(); break; @@ -118,7 +118,7 @@ public: } case LAUNCH: { - launch_spinny->Set(1); + launch_spinny->Set(LAUNCH_POWER); state = LAUNCHING; break; } @@ -131,6 +131,19 @@ public: } break; } + case RESETTING: + { + launch_spinny->Set(0); + launcher->Set(0); + pickup->Set(0); + state = READY; + break; + } + case ON_FIRE: + { + std::cout << "Something is wrong with the launch sequence.\n"; + break; + } } } From 1b681a36107b186e1bed03c2ba31c187510df5e8 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Mon, 15 Feb 2016 20:14:48 -0500 Subject: [PATCH 26/26] fixed a typo --- Robot2016/src/Shooter.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Robot2016/src/Shooter.h b/Robot2016/src/Shooter.h index a8469b7..c8980f5 100644 --- a/Robot2016/src/Shooter.h +++ b/Robot2016/src/Shooter.h @@ -96,7 +96,7 @@ public: case READY: { state = SPINNINGUP; - launch_spinny->Set(0); + launch_spinny->Set(-1); launcher->Set(LAUNCH_POWER); pickup->Set(LAUNCH_POWER); shotClock.Reset();