#include "WPILib.h" #include "Shooter.h" #ifndef BUTTON_LAYOUT #define BUTTON_LAYOUT #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. #endif // BUTTON_LAYOUT class Robot: public IterativeRobot { Talon left_drive; Talon right_drive; CANTalon shooter1; CANTalon shooter2; CANTalon ramp; RobotDrive drive; Shooter shooter; Joystick driver_stick, operator_stick; public: Robot(): left_drive(1), // Left DriveTrain Talons plug into PWM channel 1 with a Y-spliter right_drive(2), // Right DriveTrain Talons plug // left wheel 2 shooter1(10), // shooter drive 1 shooter2(11), // shooter drive 2 ramp(12), drive(&left_drive, &right_drive), shooter( // initialize Shooter object. &shooter1, &shooter2, &ramp), driver_stick(0), // right stick (operator) operator_stick(1) // left stick (driver) { } 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. LiveWindow *lw = LiveWindow::GetInstance(); SendableChooser *chooser; const std::string autoNameDefault = "Default"; const std::string autoNameCustom = "My Auto"; std::string autoSelected; void RobotInit() { chooser = new SendableChooser(); chooser->AddDefault(autoNameDefault, (void*)&autoNameDefault); chooser->AddObject(autoNameCustom, (void*)&autoNameCustom); SmartDashboard::PutData("Auto Modes", chooser); } /** * This autonomous (along with the chooser code above) shows how to select between different autonomous modes * using the dashboard. The sendable chooser code works with the Java SmartDashboard. If you prefer the LabVIEW * Dashboard, remove all of the chooser code and uncomment the GetString line to get the auto name from the text box * below the Gyro * * You can add additional auto modes by adding additional comparisons to the if-else structure below with additional strings. * If using the SendableChooser make sure to add them to the chooser code above as well. */ 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; if(autoSelected == autoNameCustom){ //Custom Auto goes here } else { //Default Auto goes here } } void AutonomousPeriodic() { if(autoSelected == autoNameCustom){ //Custom Auto goes here } else { //Default Auto goes here } } void TeleopInit() { shooter.CalibrateRamp(); shooter.SetRamp(Shoot); // start in the full up position! } void TeleopPeriodic() { drive.ArcadeDrive(&driver_stick); // This is shit code for testing. Replace it with real code. if(operator_stick.GetRawButton(RAMP_RAISE)) { ramp.Set(1); } else if(operator_stick.GetRawButton(RAMP_LOWER)) { ramp.Set(-1); } else { ramp.Set(0); } if(operator_stick.GetRawButton(THUMB) && !pickupRunning) { shooter.PickUp(); pickupRunning = true; } else if(pickupRunning) { shooter.PickUp(false); pickupRunning = false; } float power = (1.0 - operator_stick.GetThrottle()) / 2.0; shooter.SetPower(power); } void TestPeriodic() { lw->Run(); } }; START_ROBOT_CLASS(Robot)