From 1938d4b935fcba83cc79ed026637906a08a303df Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Mon, 15 Feb 2016 20:54:20 -0500 Subject: [PATCH 01/11] tweaks - untested --- src/Robot.cpp | 8 ++++++-- src/Shooter.h | 19 +++++++++++-------- 2 files changed, 17 insertions(+), 10 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 1af8deb..b12359c 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -163,7 +163,7 @@ private: /* * 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!) + * every iteration 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. */ @@ -177,10 +177,14 @@ private: shooter.PickUp(false); pickupRunning = false; } + else if(launch_spinny.Get() != 1) + { + launch_spinny.Set(1); + } /* * 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. + * inverted every iteration 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. */ diff --git a/src/Shooter.h b/src/Shooter.h index c8980f5..9c8af1e 100644 --- a/src/Shooter.h +++ b/src/Shooter.h @@ -84,13 +84,10 @@ public: 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. - */ + if (shotClock.Get() > (SPINUP_TIME + 0.1)) + { + state = RESETTING; + } switch (state) { case READY: @@ -152,7 +149,13 @@ public: { pickup->Set((float) (state * PICKUP_POWER)); launcher->Set((float) (state * PICKUP_POWER * -1)); - //launch_spinny->Set(-1.0*PICKUP_POWER); + if (state) + { + launch_spinny->Set(-1.0); + } else + { + launch_spinny->Set(1); + } //std::cout << "picking up!\n"; } From 9ac893271f93f9e22db4daeac43756aed33531c6 Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Wed, 17 Feb 2016 15:22:25 -0500 Subject: [PATCH 02/11] Added check on limit switches to prevent uneccessary motor power setting on the RAMP --- src/Shooter.h | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/Shooter.h b/src/Shooter.h index 9c8af1e..f948abe 100644 --- a/src/Shooter.h +++ b/src/Shooter.h @@ -64,12 +64,14 @@ public: void LowerRamp() { - launch_spinny->Set(-1); + if(launch_spinny->GetReverseLimitOK()) + launch_spinny->Set(-1); } void RaiseRamp() { - launch_spinny->Set(1); + if(launch_spinny->GetForwardLimitOK()) + launch_spinny->Set(1); } void StopRamp() @@ -109,7 +111,7 @@ public: shotClock.Start(); } else { - std::cout << "*Goku noises*\n"; + //std::cout << "*Goku noises*\n"; } break; } From 139ae70b1bf625f6549dee09fe41383bdc9f110e Mon Sep 17 00:00:00 2001 From: Jason Cox Date: Wed, 17 Feb 2016 15:28:33 -0500 Subject: [PATCH 03/11] auto raising ramp test --- src/Robot.cpp | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index b12359c..3e4dc1b 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -119,14 +119,7 @@ private: //bool rampDoing = false; // 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)) + if(operator_stick.GetRawButton(RAMP_LOWER)) { std::cout << "Lowering Ramp."; //launch_spinny.Set(-1); @@ -140,10 +133,12 @@ private: }*/ else if(ramping && !operator_stick.GetRawButton(RAMP_LOWER) - && !operator_stick.GetRawButton(RAMP_RAISE)) + && launch_spinny.GetForwardLimitOK()) + { + shooter.RaiseRamp(); + } + else { - std::cout << "Stopping Ramp."; - shooter.StopRamp(); ramping = false; } From 3584fc46340ac9aea85bd5d99d8fe7c6cc517668 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Sat, 20 Feb 2016 13:58:35 -0500 Subject: [PATCH 04/11] untested one-touch shooting --- src/Robot.cpp | 2 +- src/Shooter.h | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 3e4dc1b..790269d 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -202,7 +202,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)) + if(operator_stick.GetRawButton(TRIGGER) || (shooter.GetState() != 0)) { shooting = true; shooter.Shoot(); diff --git a/src/Shooter.h b/src/Shooter.h index f948abe..cffe153 100644 --- a/src/Shooter.h +++ b/src/Shooter.h @@ -175,6 +175,11 @@ public: launcher->Set(power); //std::cout << "setting shooter power" << std::endl; } + + int GetState() + { + return state; + } private: //RobotDrive *shooterDrive; From fea200cca5bf2b1e2ccc3c212026f6d4b74a6eb4 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Sat, 20 Feb 2016 14:05:01 -0500 Subject: [PATCH 05/11] SPELLING --- src/Robot.cpp | 19 +++++++++---------- src/Shooter.h | 30 +++++++++++++++--------------- 2 files changed, 24 insertions(+), 25 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 790269d..cc6010f 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -20,7 +20,7 @@ class Robot: public IterativeRobot { Talon left_drive, right_drive; CANTalon shooter1, shooter2, - launch_spinny; + ramp; RobotDrive drive; Shooter shooter; Joystick driver_stick, operator_stick; @@ -30,10 +30,10 @@ public: right_drive(1), // Right DriveTrain Talons plug // left wheel 2 shooter1(11), // shooter drive 1 shooter2(10), // shooter drive 2 - launch_spinny(12), + ramp(12), drive(&left_drive, &right_drive), shooter( // initialize Shooter object. - &shooter1, &shooter2, &launch_spinny), + &shooter1, &shooter2, &ramp), driver_stick(0), // right stick (operator) operator_stick(1) // left stick (driver) { @@ -65,7 +65,7 @@ private: shooter2.Enable(); left_drive.SetInverted(true); right_drive.SetInverted(true); - //launch_spinny.SetInverted(true); + //ramp.SetInverted(true); inverting = false; pickupRunning = false; ramping = false; @@ -114,7 +114,7 @@ private: void TeleopPeriodic() { - //std::cout << "Ramp position: "<< launch_spinny.GetEncPosition() << std::endl; + //std::cout << "Ramp position: "<< ramp.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); //bool rampDoing = false; @@ -122,7 +122,7 @@ private: if(operator_stick.GetRawButton(RAMP_LOWER)) { std::cout << "Lowering Ramp."; - //launch_spinny.Set(-1); + //ramp.Set(-1); shooter.LowerRamp(); ramping = true; } @@ -133,7 +133,7 @@ private: }*/ else if(ramping && !operator_stick.GetRawButton(RAMP_LOWER) - && launch_spinny.GetForwardLimitOK()) + && ramp.GetForwardLimitOK()) { shooter.RaiseRamp(); } @@ -172,9 +172,9 @@ private: shooter.PickUp(false); pickupRunning = false; } - else if(launch_spinny.Get() != 1) + else if(ramp.Get() != 1) { - launch_spinny.Set(1); + ramp.Set(1); } /* @@ -197,7 +197,6 @@ private: /* - * 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. diff --git a/src/Shooter.h b/src/Shooter.h index cffe153..5c04da7 100644 --- a/src/Shooter.h +++ b/src/Shooter.h @@ -37,7 +37,7 @@ public: // shooterDrive = new RobotDrive(s1, s2); launcher = s1; pickup = s2; - launch_spinny = r; + ramp = r; ready = true; state = READY; } @@ -51,37 +51,37 @@ public: { delete launcher; delete pickup; - delete launch_spinny; + delete ramp; } void StopShooter() { ready = true; - launch_spinny->Set(0); + ramp->Set(0); launcher->Set(0); pickup->Set(0); } void LowerRamp() { - if(launch_spinny->GetReverseLimitOK()) - launch_spinny->Set(-1); + if(ramp->GetReverseLimitOK()) + ramp->Set(-1); } void RaiseRamp() { - if(launch_spinny->GetForwardLimitOK()) - launch_spinny->Set(1); + if(ramp->GetForwardLimitOK()) + ramp->Set(1); } void StopRamp() { - launch_spinny->Set(0); + ramp->Set(0); } void BoostRamp() { - launch_spinny->Set(1); + ramp->Set(1); } void Shoot() @@ -95,7 +95,7 @@ public: case READY: { state = SPINNINGUP; - launch_spinny->Set(-1); + ramp->Set(-1); launcher->Set(LAUNCH_POWER); pickup->Set(LAUNCH_POWER); shotClock.Reset(); @@ -117,7 +117,7 @@ public: } case LAUNCH: { - launch_spinny->Set(LAUNCH_POWER); + ramp->Set(LAUNCH_POWER); state = LAUNCHING; break; } @@ -132,7 +132,7 @@ public: } case RESETTING: { - launch_spinny->Set(0); + ramp->Set(0); launcher->Set(0); pickup->Set(0); state = READY; @@ -153,10 +153,10 @@ public: launcher->Set((float) (state * PICKUP_POWER * -1)); if (state) { - launch_spinny->Set(-1.0); + ramp->Set(-1.0); } else { - launch_spinny->Set(1); + ramp->Set(1); } //std::cout << "picking up!\n"; } @@ -185,7 +185,7 @@ private: //RobotDrive *shooterDrive; CANTalon *launcher; CANTalon *pickup; - CANTalon *launch_spinny; + CANTalon *ramp; ShooterState state; Timer shotClock; From 8327823bd12143689878bf052a81ab7d99938ae0 Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Sat, 20 Feb 2016 14:05:56 -0500 Subject: [PATCH 06/11] SPELLING --- src/Robot.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/Robot.cpp b/src/Robot.cpp index cc6010f..98f4375 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -197,6 +197,7 @@ private: /* + * Unlike the previous actions, this method does need to be called every iteration 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. From 904a30ab8bf5a06331f8c27498a297b24baed2ca Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Sat, 20 Feb 2016 14:08:32 -0500 Subject: [PATCH 07/11] vomits ramp current onto console --- src/Robot.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 98f4375..49aeff1 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -114,7 +114,7 @@ private: void TeleopPeriodic() { - //std::cout << "Ramp position: "<< ramp.GetEncPosition() << std::endl; + std::cout << "Ramp current: "<< ramp.GetOutputCurrent() << std::endl; drive.ArcadeDrive(&driver_stick, true); //bool rampDoing = false; From 8f8c64a4500d2a37ffdcbfb7caabd8998fbd572a Mon Sep 17 00:00:00 2001 From: Aidan Ferguson Date: Sat, 20 Feb 2016 14:51:59 -0500 Subject: [PATCH 08/11] TalonSRX, not Talon --- src/Robot.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 49aeff1..7117b87 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -18,7 +18,7 @@ class Robot: public IterativeRobot { - Talon left_drive, right_drive; + TalonSRX left_drive, right_drive; CANTalon shooter1, shooter2, ramp; RobotDrive drive; From 220862a63e3fec993449a70c41f2066cd77c5ec8 Mon Sep 17 00:00:00 2001 From: dkbug Date: Sat, 20 Feb 2016 15:45:47 -0500 Subject: [PATCH 09/11] added good ramp code --- src/Robot.cpp | 17 +++++++---------- src/Shooter.h | 4 ++-- 2 files changed, 9 insertions(+), 12 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 7117b87..196bdc1 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -119,26 +119,23 @@ private: //bool rampDoing = false; // This is shit code for testing. Replace it with real code. - if(operator_stick.GetRawButton(RAMP_LOWER)) + if(!ramping && operator_stick.GetRawButton(RAMP_LOWER)) { std::cout << "Lowering Ramp."; //ramp.Set(-1); shooter.LowerRamp(); ramping = true; } - /*else if(!ramping && operator_stick.GetRawButton(TRIGGER)) - { - shooter.BoostRamp(); - ramping = true; - }*/ - else if(ramping - && !operator_stick.GetRawButton(RAMP_LOWER) - && ramp.GetForwardLimitOK()) + else if(!ramping + && !operator_stick.GetRawButton(RAMP_RAISE)) { shooter.RaiseRamp(); + ramping = true; } - else + else if(ramping && !operator_stick.GetRawButton(RAMP_RAISE) + && !operator_stick.GetRawButton(RAMP_LOWER)) { + shooter.StopRamp(); ramping = false; } diff --git a/src/Shooter.h b/src/Shooter.h index 562bf75..257d661 100644 --- a/src/Shooter.h +++ b/src/Shooter.h @@ -64,7 +64,7 @@ public: void LowerRamp() { - ramp->Set(-1); + ramp->Set(-0.5); if(ramp->Limits::kReverseLimit){ SmartDashboard::PutNumber("ramp", 2); //going to put a circlar dial to show where the ramp could be } else { @@ -74,7 +74,7 @@ public: void RaiseRamp() { - ramp->Set(1); + ramp->Set(0.5); if(ramp->Limits::kForwardLimit){ SmartDashboard::PutNumber("ramp", 0); //going to put a circlar dial to show where the ramp could be } else { From cca8a07f6859ca50ae02958cad74be259de23987 Mon Sep 17 00:00:00 2001 From: dkbug Date: Sat, 20 Feb 2016 16:02:05 -0500 Subject: [PATCH 10/11] button mis-choice. --- src/Robot.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 196bdc1..28872a0 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -6,8 +6,8 @@ #define TRIGGER 1 // Trigger button number #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 RAMP_RAISE 5 // Button 3 for Raising Ramp +#define RAMP_LOWER 3 // Button 4 to lower ramp. #define UNJAM 11 #define DEADZONE_RADIUS 0.01 // Deadzone Radius prevents tiny twitches in the joystick's value from From de785512d6e51f5aedded76339dd4b09c713b84f Mon Sep 17 00:00:00 2001 From: dkbug Date: Sat, 20 Feb 2016 16:07:26 -0500 Subject: [PATCH 11/11] fixed a stupid logic error if ramp is not raising, raise the ramp :P --- src/Robot.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/Robot.cpp b/src/Robot.cpp index 28872a0..34a3fc5 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -169,11 +169,6 @@ private: shooter.PickUp(false); pickupRunning = false; } - else if(ramp.Get() != 1) - { - ramp.Set(1); - } - /* * The 'inverting' variable is used to make sure that the drive train isn't getting * inverted every iteration of the TeleopPeriodic method while the button is held down.