diff --git a/.settings/language.settings.xml b/.settings/language.settings.xml index 8d19c1e..7130758 100644 --- a/.settings/language.settings.xml +++ b/.settings/language.settings.xml @@ -5,7 +5,7 @@ - + diff --git a/Debug/src/IControl.o b/Debug/src/IControl.o index 15363f1..82f7a49 100644 Binary files a/Debug/src/IControl.o and b/Debug/src/IControl.o differ diff --git a/src/Components/RelayController.cpp b/src/Components/RelayController.cpp index 82f87b3..76ac6eb 100644 --- a/src/Components/RelayController.cpp +++ b/src/Components/RelayController.cpp @@ -14,54 +14,38 @@ const int RELAY_BLUE = 0; RelayController::RelayController() { // TODO Auto-generated constructor stub - Red = new Relay(RelayIO::RELAY_RED); - Blue = new Relay(RelayIO::RELAY_BLUE); + Red = new Relay(RelayIO::RELAY_RED, Relay::kForwardOnly); + Blue = new Relay(RelayIO::RELAY_BLUE, Relay::kForwardOnly); } RelayController::~RelayController() { // TODO Auto-generated destructor stub delete Red; delete Blue; - Red = 0; - Blue = 0; } -void RelayController::ToggleColor() { - switch (currnet) { - case RelayColor::neither: - break; //TODO - case RelayColor::blue: - break; //TODO - case RelayColor::red: - break; // TODO - } -} -void RelayController::setColor(RelayColor color) { - if(currnet != color){ - switch (color) { - case RelayColor::neither: +void RelayController::TeleopInit() +{ + DriverStation::Alliance alligent = DriverStation::GetInstance().GetAlliance(); + switch(alligent){ + case DriverStation::kBlue: Red->Set(Relay::kOff); - Blue->Set(Relay::kOff); + Blue->Set(Relay::kOn); break; - case RelayColor::red: + case DriverStation::kRed: Red->Set(Relay::kOn); Blue->Set(Relay::kOff); break; - case RelayColor::blue: + case DriverStation::kInvalid: Red->Set(Relay::kOff); Blue->Set(Relay::kOn); break; } - currnet = color; - } -} - -void RelayController::relayBlink(int speed) { - } -void RelayController::burnUp() { +void RelayController::AutonomousInit() +{ DriverStation::Alliance alligent = DriverStation::GetInstance().GetAlliance(); switch(alligent){ case DriverStation::kBlue: @@ -79,28 +63,42 @@ void RelayController::burnUp() { } } -void RelayController::stopBlink() { - burnUp(); -} - -void RelayController::TeleopInit() -{ - burnUp(); -} - -void RelayController::AutonomousInit() -{ - burnUp(); -} - void RelayController::RobotInit() { - burnUp(); + DriverStation::Alliance alligent = DriverStation::GetInstance().GetAlliance(); + switch(alligent){ + case DriverStation::kBlue: + Red->Set(Relay::kOff); + Blue->Set(Relay::kOn); + break; + case DriverStation::kRed: + Red->Set(Relay::kOn); + Blue->Set(Relay::kOff); + break; + case DriverStation::kInvalid: + Red->Set(Relay::kOff); + Blue->Set(Relay::kOn); + break; + } } void RelayController::DisabledInit() { - burnUp(); + DriverStation::Alliance alligent = DriverStation::GetInstance().GetAlliance(); + switch(alligent){ + case DriverStation::kBlue: + Red->Set(Relay::kOff); + Blue->Set(Relay::kOn); + break; + case DriverStation::kRed: + Red->Set(Relay::kOn); + Blue->Set(Relay::kOff); + break; + case DriverStation::kInvalid: + Red->Set(Relay::kOff); + Blue->Set(Relay::kOn); + break; + } } /* diff --git a/src/Robot.cpp b/src/Robot.cpp index 2364a7a..0b491be 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -127,6 +127,10 @@ class Robot: public IterativeRobot { test = test->parent; } + + // Turn??? + NavxSensorControl::AutonomousPeriodic(turn); + } void TeleopInit() { diff --git a/src/SensorControl/NavxSensorControl.cpp b/src/SensorControl/NavxSensorControl.cpp index dc0d890..90cad14 100644 --- a/src/SensorControl/NavxSensorControl.cpp +++ b/src/SensorControl/NavxSensorControl.cpp @@ -6,6 +6,7 @@ */ #include +#include NavxSensorControl::NavxSensorControl(IXbox *xboxInstance, IProfile *profileInstance, IVision *visionInstance) { @@ -79,7 +80,8 @@ void NavxSensorControl::TargetingStateMachine() { float motorSpeed = 0; switch (targetState) { case TargetingState::waitForButtonPress: - if (xbox->getLeftTriggerPressed()) { + if ((xbox->getLeftTriggerPressed() && !comp) + || (xbox->getLeftBumperPressed() && comp)) { commandDriveState = DriveSystemState::stopped; targetState = TargetingState::waitForStopped; } @@ -93,6 +95,9 @@ void NavxSensorControl::TargetingStateMachine() { } break; case TargetingState::waitForPicResult: + if (xbox->getStartPressed()) { + + } if (vision->getDoneAiming()) { visionTargetAngle = vision->getDegreesToTurn(); @@ -108,7 +113,7 @@ void NavxSensorControl::TargetingStateMachine() { } break; case TargetingState::driveToAngle: - if (fabs(turnController->GetError()) < 3) { + if (fabs(turnController->GetError()) < 1) { if (t == NULL) { t = new Timer(); t->Start(); @@ -159,9 +164,18 @@ void NavxSensorControl::TargetingStateMachine() { } void NavxSensorControl::PIDWrite(float output) { + bool positive=output>=0; + output=sqrt(fabs(output));//negative numbers don't have a real square root + if (!positive) + output*=-1; turnSpeed = output; } +void NavxSensorControl::RobotInit() { + SmartDashboard::PutNumber("P", 0); + SmartDashboard::PutNumber("I", 0); + SmartDashboard::PutNumber("D", 0); +} void NavxSensorControl::TeleopInit() { ahrs->ZeroYaw(); turnSpeed = 0; @@ -169,6 +183,7 @@ void NavxSensorControl::TeleopInit() { currentDriveState = DriveSystemState::running; commandDriveState = DriveSystemState::running; t = NULL; + turnController->SetPID(0.055, 0.0004, 0.0); left->Reset(); right->Reset(); diff --git a/src/SensorControl/NavxSensorControl.h b/src/SensorControl/NavxSensorControl.h index ca5b917..ec3c697 100644 --- a/src/SensorControl/NavxSensorControl.h +++ b/src/SensorControl/NavxSensorControl.h @@ -49,6 +49,7 @@ class NavxSensorControl: public ISensorControl, public PIDOutput { MotorCommand *UpdateMotorSpeeds(float leftMotorSpeed, float rightMotorSpeed); DriveSystemState DriveSystemControlUpdate(DriveSystemState currentState, DriveSystemState requestedState); + void RobotInit(); void TeleopInit(); void TeleopPeriodic(); void AutonomousInit(); @@ -72,6 +73,7 @@ class NavxSensorControl: public ISensorControl, public PIDOutput { float turnSpeed; int currentStep; + bool comp = true; bool inAutonomous; bool time; bool autoTime; diff --git a/src/Shooter/Shooter.cpp b/src/Shooter/Shooter.cpp index 8352564..d51caca 100644 --- a/src/Shooter/Shooter.cpp +++ b/src/Shooter/Shooter.cpp @@ -137,7 +137,7 @@ void Shooter::TeleopInit() { } void Shooter::TeleopPeriodic() { - readXboxState(); + readXboxComp(); updateMotor2(); setPnumatics(); @@ -181,7 +181,10 @@ void Shooter::TeleopPeriodic() { } }*/ - intakeSpeed = SmartDashboard::GetNumber("Intake Speed Change", -0.7); + intakeSpeed = SmartDashboard::GetNumber("Intake Speed Change", 0.7); + if(intakeDirection){ + intakeSpeed = -intakeSpeed; + } switch (sState) { case ready: @@ -317,6 +320,97 @@ void Shooter::readXboxState() { } } +void Shooter::readXboxComp() { + if (xbox->getRightBumperPressed()) { //Up + angle = !angle; + } + + if (xbox->getLeftTriggerPressed()) { + intakePos = !intakePos; + runIntake = !runIntake; + //TODO run motors for 2 sec after retract + } + + if(xbox->getAPressed()) + { + intakeDirection = !intakeDirection; + } + + if (xbox->getBackPressed()) { + runIntake = !runIntake; + } + + if(xbox->getYPressed()) + { + //TODO Reverse Motors + } + + switch (sState) { + case ready: + if (xbox->getRightTriggerPressed()) { + sState = windup; + } + break; + case windup: + runShoot = true; + if (xbox->getRightTriggerPressed()) { + sState = goShoot; + } + if (xbox->getBPressed()) { + sState = winddown; + } + break; + case goShoot: + runTrigger = true; + + if (t == NULL) { + t = new Timer(); + t->Start(); + } else { + if (t->Get() > 1) { + time = true; + } + } + + if (time) { + sState = winddown; + time = false; + delete t; + t = NULL; + } + + break; + case winddown: + runShoot = false; + runTrigger = false; + + if (t == NULL) { + t = new Timer(); + t->Start(); + } else { + if (t->Get() > 1) { + time = true; + } + } + + if (time) { + sState = ready; + time = false; + delete t; + t = NULL; + } + break; + } + + if (xbox->getXPressed()) { + if (shootPercentState < 4) { + shootPercentState++; + } else { + shootPercentState = 0; + } + } +} + void Shooter::setPnumatics() { if (angle) { @@ -349,11 +443,11 @@ void Shooter::updateMotor2() { } if (runIntake) { - /*if (intakeDirection) { - intakeSpeed = 1; - } else { - intakeSpeed = -1; - }*/ +// if (intakeDirection) { +// intakeSpeed = ; +// } else { +// intakeSpeed = -1; +// } } else { intakeSpeed = 0.0; } diff --git a/src/Shooter/Shooter.h b/src/Shooter/Shooter.h index b25360a..dc80a11 100644 --- a/src/Shooter/Shooter.h +++ b/src/Shooter/Shooter.h @@ -29,6 +29,7 @@ class Shooter: public IControl { //Input from Xbox Controller void readXbox(); void readXboxState(); + void readXboxComp(); // Lukas and Aaron layout void setPnumatics(); void updateMotor1(); // w/ encoders void updateMotor2(); // w/o encoders diff --git a/sysProps.xml b/sysProps.xml index ea4f7a3..d0a2eaf 100644 Binary files a/sysProps.xml and b/sysProps.xml differ