Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
pietroglyph committed Feb 13, 2019
2 parents f818146 + 8832bfb commit 36c740f
Show file tree
Hide file tree
Showing 4 changed files with 55 additions and 35 deletions.
33 changes: 17 additions & 16 deletions src/main/java/com/spartronics4915/frc2019/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ public class Constants

public static final double kLooperDt = 0.01;

public static final Pose2d[] kVisionTargetLocations =
public static final Pose2d[] kVisionTargetLocations =
{
new Pose2d(0, 0, Rotation2d.identity()),
};
Expand Down Expand Up @@ -118,7 +118,7 @@ public class Constants
public static final int kMainButtonBoardPort = 1;
public static final double kJoystickThreshold = 0.5;

// PWMs
// PCMs
public static final int kCargoHatchArmPCMId = 0;
public static final int kClimberPCMId = 1;

Expand All @@ -131,29 +131,30 @@ public class Constants
public static final int kCargoIntakeMotorRight = 6;
public static final int kCargoIntakeMotorLeft = 7;
public static final int kCargoIntakeSensor = 7;
public static final int kCargoIntakeSensorMinDistance = 100; //TODO: unit/value
public static final int kCargoIntakeSensorMaxDistance = 1000; //TODO: unit/value
public static final int kCargoIntakeSensorMinDistance = 100; // TODO: unit/value
public static final int kCargoIntakeSensorMaxDistance = 1000; // TODO: unit/value
public static final double kShootTime = 4;
public static final double kTransitionTime = 1;

// Cargo Ramp
// Cargo Chute
public static final int kRampMotorId = 5;
public static final int kFlipperSolenoidId = 3;
public static final int kRampSolenoidId = 3;
public static final int kRampSensorId = 6;
public static final double kRampSpeed = 1.0;
public static final double kShootSpeed = 1.0; // tune
public static final double kRampSpeed = 1.0; // TODO: tune
public static final double kShootSpeed = 1.0; // TODO: tune
public static final double kMaxChuteBallDistanceThreshold = 1.0; // TODO: tune
public static final boolean kRampSolenoidExtend = false;
public static final boolean kRampSolenoidRetract = true;

// Climber
public static final int kFrontLeftSolenoidId1 = 0; //Extend
public static final int kFrontLeftSolenoidId2 = 1; //Retract
public static final int kFrontRightSolenoidId1 = 2; //Extend
public static final int kFrontRightSolenoidId2 = 3; //Retract
public static final int kRearLeftSolenoidId1 = 4; //Extend
public static final int kRearLeftSolenoid2 = 5; //Retract
public static final int kRearRightSolenoidId1 = 6; //Extend
public static final int kRearRightSolenoidId2 = 7; //Retract
public static final int kFrontLeftSolenoidId1 = 0; // Extend
public static final int kFrontLeftSolenoidId2 = 1; // Retract
public static final int kFrontRightSolenoidId1 = 2; // Extend
public static final int kFrontRightSolenoidId2 = 3; // Retract
public static final int kRearLeftSolenoidId1 = 4; // Extend
public static final int kRearLeftSolenoid2 = 5; // Retract
public static final int kRearRightSolenoidId1 = 6; // Extend
public static final int kRearRightSolenoidId2 = 7; // Retract
public static final int kFrontLeftIRSensorId = 0;
public static final int kFrontRightIRSensorId = 1;
public static final int kDownwardFrontRightIRSensorId = 2;
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/com/spartronics4915/frc2019/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -332,19 +332,19 @@ public void teleopPeriodic()
// command.scale(Constants.kDriveRightKv * (Constants.kDriveWheelDiameterInches / 2)).getRight() + Math.copySign(Constants.kDriveRightVIntercept, command.getRight())
// )); XXX Conversions on Kv are wrong

if(mControlBoard.getEjectPanel())//1: 6
if(mControlBoard.getEjectPanel())// 1: 6
mPanelHandler.setWantedState(PanelHandler.WantedState.EJECT);

if(mControlBoard.getIntake())//1: 2
if (mControlBoard.getIntake()) // 1: 2
mCargoIntake.setWantedState(CargoIntake.WantedState.INTAKE);

if(mControlBoard.getTestButtonOne())//2: 5
if (mControlBoard.getTestButtonOne()) // 2: 5
mCargoIntake.setWantedState(CargoIntake.WantedState.HOLD);

if(mControlBoard.getTestButtonThree())//2: 7
if (mControlBoard.getTestButtonThree()) // 2: 7
mCargoIntake.setWantedState(CargoIntake.WantedState.EJECT);

if(mControlBoard.getTestButtonTwo())
if (mControlBoard.getTestButtonTwo())
mCargoIntake.setWantedState(CargoIntake.WantedState.CLIMB);

if (mControlBoard.getClimb())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,21 @@
* ✔ Don't keep shooting states running forever?
* ✔ Fill out atTarget()
* ✔ Fill out outputTelemetry()
* Fix the BRING_BALL_TO_TOP: when checking to actually go into it, don't if in either manual wantedstate
* cool, the chute can break the arm now. we gotta write code to stop that from happening.
* the chute can break the arm now. we gotta write code to stop that from happening.
* Mechanics have determined that we need ejecting wheels again.
* T E S T
* - Both SHOOTs should... shoot. Solenoids and the ejecting wheels should work too.
* - Need to integrate with CargoIntake to prevent arm damage. (!!!thisisimportant!!!)
* - A21IR sensor should give us correct data (Austin has checked his A21s, but it's really really good to make sure)
* - BRING_BALL_TO_TOP should correctly transition with IR sensors (make sure readings are accurate beforehand)
* - MANUALs should correctly override
* - If RampMotor moving at all go into MANUAL_HOLDING
* - If RampMotor not moving go into MANUAL_RAMPING
* - MUST not be overriden ~~by the A21 sensor detecting a ball~~ scratch that for now we afaik we aren't going to detect cargo
* - Should switch with a click of a button
* - There should be a quick transition so that ramp motors do not go from full speed ahead to full speed behind
*
* After all this is completed: code review
*/

package com.spartronics4915.frc2019.subsystems;
Expand All @@ -25,7 +37,6 @@
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;

import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand Down Expand Up @@ -60,7 +71,8 @@ private enum SystemState
private TalonSRX mRampMotor = null;
private Solenoid mRampSolenoid = null;
private A21IRSensor mRampSensor = null;
private Timer mShootTimer = new Timer();

private Timer mCargoTimer = new Timer();

private boolean mStateChanged;

Expand All @@ -72,7 +84,7 @@ private CargoChute()
if (!CANProbe.getInstance().validatePCMId(Constants.kCargoHatchArmPCMId)) throw new RuntimeException("CargoChute PCM isn't on the CAN bus!");

mRampMotor = TalonSRXFactory.createDefaultTalon(Constants.kRampMotorId);
mRampSolenoid = new Solenoid(Constants.kCargoHatchArmPCMId, Constants.kFlipperSolenoidId);
mRampSolenoid = new Solenoid(Constants.kCargoHatchArmPCMId, Constants.kRampSolenoidId);
mRampSensor = new A21IRSensor(Constants.kRampSensorId);
}
catch (Exception e)
Expand Down Expand Up @@ -119,38 +131,46 @@ public void onLoop(double timestamp)
break;
case EJECTING:
if (mStateChanged)
{
mCargoTimer.start();
mRampMotor.set(ControlMode.PercentOutput, 0);
}
if (mCargoTimer.hasPeriodPassed(Constants.kTransitionTime))
{
mCargoTimer.stop();
mRampMotor.set(ControlMode.PercentOutput, -Constants.kRampSpeed);
}
break;
case LOWERING:
if (mStateChanged)
mRampSolenoid.set(Constants.kRampSolenoidRetract);
case SHOOTING_BAY:
if (mStateChanged)
{
mShootTimer.start();
mRampSolenoid.set(Constants.kRampSolenoidRetract);
mCargoTimer.start();
mRampMotor.set(ControlMode.PercentOutput, Constants.kShootSpeed);
}
if (mShootTimer.hasPeriodPassed(Constants.kShootTime) && newState == mSystemState)
if (mCargoTimer.hasPeriodPassed(Constants.kShootTime) && newState == mSystemState)
newState = SystemState.HOLDING;
break;
case SHOOTING_ROCKET:
if (mStateChanged)
{
mShootTimer.start();
mRampSolenoid.set(Constants.kRampSolenoidExtend);
mCargoTimer.start();
mRampMotor.set(ControlMode.PercentOutput, Constants.kShootSpeed);
}
if (mShootTimer.hasPeriodPassed(Constants.kShootTime) && newState == mSystemState)
if (mCargoTimer.hasPeriodPassed(Constants.kShootTime) && newState == mSystemState)
newState = SystemState.HOLDING;
break;
default:
logError("Unhandled system state!");
}
if (newState != mSystemState)
{
mShootTimer.stop();
mShootTimer.reset();
mCargoTimer.stop();
mCargoTimer.reset();
mStateChanged = true;
}
else
Expand Down Expand Up @@ -238,7 +258,7 @@ public synchronized boolean atTarget()
case LOWER:
return mSystemState == SystemState.LOWERING;
case SHOOT_BAY:
return mSystemState == SystemState.SHOOTING_BAY && mShootTimer.hasPeriodPassed(Constants.kShootTime);
return mSystemState == SystemState.SHOOTING_BAY && mCargoTimer.hasPeriodPassed(Constants.kShootTime);
case SHOOT_ROCKET:
return mSystemState == SystemState.SHOOTING_ROCKET;
default:
Expand Down Expand Up @@ -332,4 +352,4 @@ public void stop()
mRampMotor.set(ControlMode.PercentOutput, 0.0);
mRampSolenoid.set(Constants.kRampSolenoidRetract);
}
}
}
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package com.spartronics4915.frc2019.subsystems;

import com.spartronics4915.frc2019.Constants;
import com.spartronics4915.lib.drivers.A21IRSensor;
import com.spartronics4915.lib.drivers.A41IRSensor;
import com.spartronics4915.lib.drivers.IRSensor;
import com.spartronics4915.lib.drivers.TalonSRXFactory;
Expand Down

0 comments on commit 36c740f

Please sign in to comment.