Skip to content

Initial Ports and Controls #58

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 62 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
62 commits
Select commit Hold shift + click to select a range
a96db47
Initial Controls
TaeSeanDo Feb 29, 2020
be7f727
Add second flywheel motor, delete indexer piston
TaeSeanDo Mar 5, 2020
44a2050
Add arm lock piston
TaeSeanDo Mar 5, 2020
e6298ee
Add second shifter to drive base
TaeSeanDo Mar 5, 2020
a4371ad
Add second deployer piston
TaeSeanDo Mar 5, 2020
4e2955c
Ports for pwm and pcm
TaeSeanDo Mar 5, 2020
4a6347f
Climb motor ports
TaeSeanDo Mar 5, 2020
cdf8357
Update WPILib version and add Phoenix libs
docprofsky Mar 5, 2020
49585f5
Speed controller versatility
TaeSeanDo Mar 5, 2020
35d2b9e
Merge remote-tracking branch 'origin/meh' into Initial-Ports-and-Cont…
TaeSeanDo Mar 5, 2020
80970da
CAN work.
TaeSeanDo Mar 5, 2020
01c60ba
Changes to run. Driving does not work.
docprofsky Mar 5, 2020
4231bc7
Initial work on rotator limit switch incorporation
TaeSeanDo Mar 6, 2020
fb876bc
Use setInverted method for drive base
TaeSeanDo Mar 6, 2020
2069ae6
Lower climb power temporarily
TaeSeanDo Mar 6, 2020
eb8c617
Clean up imports, formatting
TaeSeanDo Mar 6, 2020
69773f8
Merge branch 'make-drive' into Initial-Ports-and-Controls
docprofsky Mar 7, 2020
75faa8a
Delete extra limit switch call
TaeSeanDo Mar 7, 2020
c5cb118
Fix drive base signs
TaeSeanDo Mar 7, 2020
030eb69
Make the non-(turret, flywheel) motor work with the correct direction
docprofsky Mar 7, 2020
e2227df
21st amendment -- delete unnecessary 2nd encoder.
TaeSeanDo Mar 7, 2020
363275a
Dependency injection in the RainbowDJ
TaeSeanDo Mar 7, 2020
411ab26
More reasonable controls
TaeSeanDo Mar 7, 2020
1e8f19b
Format DriveBase
TaeSeanDo Mar 7, 2020
09cce6a
Update climb arm port.
TaeSeanDo Mar 7, 2020
71d6e54
Rename intake pistons
TaeSeanDo Mar 7, 2020
7a7209f
Update pneumatic ports
TaeSeanDo Mar 7, 2020
c21679e
Add toggle thing for the drive shifter
docprofsky Mar 7, 2020
de76805
Simplify Drivebase toggle code
TaeSeanDo Mar 7, 2020
1e84090
Fix delpoyIntake name typo
TaeSeanDo Mar 7, 2020
2a32f43
Make shifter, intake deployer, and winch lock toggles
TaeSeanDo Mar 7, 2020
490f862
Fix rainbowDJMotor name
TaeSeanDo Mar 7, 2020
310ae7e
Delete ballchucker max limit switch port
TaeSeanDo Mar 7, 2020
d7f3019
Rename ballchucker motor methods
TaeSeanDo Mar 7, 2020
01677a8
Update ball chucker encoder code.
TaeSeanDo Mar 7, 2020
4287a1f
Use rotator encoder for rotator limiting
TaeSeanDo Mar 7, 2020
40c710b
Put winch lock logic in runWinch method
TaeSeanDo Mar 7, 2020
9d39398
Rotator encoder comment
TaeSeanDo Mar 7, 2020
1fcbbf1
Encapsulation for piston getters
TaeSeanDo Mar 7, 2020
65d15f1
Delete empty 2020-FRC-robot folder
TaeSeanDo Mar 9, 2020
6975b58
Monday, 3/9. I'm lazy
TaeSeanDo Mar 11, 2020
42549ca
invert winch lock piston
TaeSeanDo Mar 11, 2020
faf8a88
Controls work for tuesday, 3/10
TaeSeanDo Mar 11, 2020
5a29437
Code for testing climb tomorrow
TaeSeanDo Mar 11, 2020
de319df
Organize motor inversions
TaeSeanDo Mar 11, 2020
4547f10
Fix testing code
TaeSeanDo Mar 12, 2020
f7ecd9c
Adjust harvester and chimney speed
TaeSeanDo Mar 12, 2020
5dbed86
Fix rightDrive inversion
TaeSeanDo Mar 12, 2020
a7b6261
Initial work on better controls
TaeSeanDo Mar 14, 2020
f58d130
Initial work on better controls
TaeSeanDo Mar 14, 2020
cb600bd
Rotator Ports
TaeSeanDo Mar 14, 2020
3dfedd1
Merge branch 'better-controls' of https://github.com/TeamCautionRobot…
TaeSeanDo Mar 14, 2020
ad8b2ef
Rotator sensor ports
TaeSeanDo Mar 14, 2020
ff0b990
Rotator sensor ports, but correct this time
TaeSeanDo Mar 14, 2020
e833b96
Rename driveBase.shifterEngaged to getShifterState
TaeSeanDo Mar 15, 2020
cc8b5d3
Modify auto
TaeSeanDo Mar 15, 2020
b790b85
Put shifter state on smart dashboard
TaeSeanDo Mar 15, 2020
72fd7f9
Clean up and invert winch
TaeSeanDo Mar 15, 2020
f5b361a
Use arcade drive.
TaeSeanDo Mar 15, 2020
997bc23
Merge branch 'better-controls' into Initial-Ports-and-Controls
TaeSeanDo Mar 15, 2020
96c4d26
Limit rotator speed in BallChucker class
TaeSeanDo Mar 15, 2020
28c1905
Bester rotator power limiting.
TaeSeanDo Mar 17, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion 2020-FRC-robot
Submodule 2020-FRC-robot deleted from 53dc25
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2020.1.2"
id "edu.wpi.first.GradleRIO" version "2020.3.2"
}

sourceCompatibility = JavaVersion.VERSION_11
Expand Down
58 changes: 29 additions & 29 deletions src/main/java/frc/robot/BallChucker9000.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,48 +21,45 @@

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.VictorSP;
import edu.wpi.first.wpilibj.SpeedController;

public class BallChucker9000 {

// ESC declarations
private final VictorSP rotatorMotor;
private final VictorSP flywheelMotor;
private final VictorSP indexerMotor;
private final SpeedController leftFlywheelMotor;
private final SpeedController rightFlywheelMotor;
private final SpeedController rotatorMotor;
private final SpeedController indexerMotor;

// Encoder declarations
private final Encoder rotatorEncoder;
private final Encoder flywheelEncoder;

// Piston declarations
private final Solenoid indexerPiston;

// Limit switches
private final DigitalInput rotatorAtZeroSwitch;

// Class initializer
public BallChucker9000(int flywheelMotorPort, int rotatorMotorPort, int indexerMotorPort,
int rotatorEncoderChannelA, int rotatorEncoderChannelB, int flywheelEncoderChannelA,
int flywheelEncoderChannelB, int indexerPistonPort, int rotatorAtZeroSwitchPort) {
public BallChucker9000(SpeedController leftFlywheelMotor, SpeedController rightFlywheelMotor,
SpeedController rotatorMotor, SpeedController indexerMotor, int rotatorEncoderChannelA,
int rotatorEncoderChannelB, int flywheelEncoderChannelA, int flywheelEncoderChannelB,
int rotatorAtZeroSwitchPort) {

// ESCs
flywheelMotor = new VictorSP(flywheelMotorPort);
rotatorMotor = new VictorSP(rotatorMotorPort);
indexerMotor = new VictorSP(indexerMotorPort);
this.leftFlywheelMotor = leftFlywheelMotor;
this.rightFlywheelMotor = rightFlywheelMotor;
this.rotatorMotor = rotatorMotor;
this.indexerMotor = indexerMotor;

// Encoders
rotatorEncoder = new Encoder(rotatorEncoderChannelA, rotatorEncoderChannelB);
flywheelEncoder = new Encoder(flywheelEncoderChannelA, flywheelEncoderChannelB);
rotatorEncoder.setDistancePerPulse(1.0 / 1024.0);
flywheelEncoder.setDistancePerPulse(1.0 / 1024.0);

// Piston
indexerPiston = new Solenoid(indexerPistonPort);
// 50 to 1 gearbox. Gear on output shaft has 15 teeth, sprocket has 124 teeth
rotatorEncoder.setDistancePerPulse(15.0 * 360.0 / (50.0 * 124.0 * 1024.0));
flywheelEncoder.setDistancePerPulse(1.0 / 1024.0);

// Limit switches
rotatorAtZeroSwitch = new DigitalInput(rotatorAtZeroSwitchPort);

}

// Reset the encoder to zero when called
Expand All @@ -74,25 +71,29 @@ public void update() {

// Setters

// ESC
public void rotatorMotorControl(double power) {
/**
*
* @param power positive is counter clockwise, scaled down by a factor of 10
*/
public void moveRotator(double power) {
power = 0.1 * Math.copySign(Math.min(Math.abs(power), 1), power);
rotatorMotor.set(power);
}

public void flywheelMotorControl(double power) {
flywheelMotor.set(power);
public void moveFlywheel(double power) {
leftFlywheelMotor.set(power);
rightFlywheelMotor.set(power);
}

public void indexerMotorControl(double power) {
public void moveIndexer(double power) {
indexerMotor.set(power);
}

// Pistons
public void indexerPistonOut(boolean state) {
indexerPiston.set(state);
// Getters
public double getRotatorEncoder() {
return rotatorEncoder.getDistance();
}

// Getters
public double getFlywheelEncoder() {
return flywheelEncoder.getRate();
}
Expand All @@ -101,5 +102,4 @@ public double getFlywheelEncoder() {
public boolean getRotatorAtZeroSwitch() {
return !rotatorAtZeroSwitch.get();
}

}
11 changes: 6 additions & 5 deletions src/main/java/frc/robot/BallTransfer.java
Original file line number Diff line number Diff line change
@@ -1,18 +1,19 @@
package frc.robot;

import edu.wpi.first.wpilibj.VictorSP;
import edu.wpi.first.wpilibj.SpeedController;

public class BallTransfer {

private final VictorSP beltMotor;
private final SpeedController beltMotor;

public BallTransfer(int beltMotorPort) {
beltMotor = new VictorSP(beltMotorPort);
public BallTransfer(SpeedController beltMotor) {
this.beltMotor = beltMotor;
}

/**
*
* @param power positive to move ball towards Ball Chucker 9000, negative to move ball towards Harvester
* @param power positive to move ball towards Ball Chucker 9000, negative to
* move ball towards Harvester
*/
public void moveBalls(double power) {
beltMotor.set(power);
Expand Down
37 changes: 29 additions & 8 deletions src/main/java/frc/robot/Climb.java
Original file line number Diff line number Diff line change
@@ -1,29 +1,50 @@
package frc.robot;

import edu.wpi.first.wpilibj.VictorSP;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.SpeedController;

public class Climb {

private final VictorSP winchMotor;
private final VictorSP armMotor;
private final SpeedController winchMotor;
private final SpeedController armMotor;

private final Solenoid winchLockPiston;

private DigitalInput armLimitSwitch;

public Climb(int winchMotorPort, int armMotorPort, int armLimitSwitchPort) {
winchMotor = new VictorSP(winchMotorPort);
armMotor = new VictorSP(armMotorPort);
public Climb(SpeedController winchMotor, SpeedController armMotor, int armLockPistonPort, int armLimitSwitchPort) {
this.winchMotor = winchMotor;
this.armMotor = armMotor;
winchLockPiston = new Solenoid(armLockPistonPort);

armLimitSwitch = new DigitalInput(armLimitSwitchPort);
}

public void runWinch(double power) {
winchMotor.set(power);
if (!lockLocked()) {
winchMotor.set(power);
} else {
winchMotor.set(0);
}
}

public void moveArms(double power) {
public void moveArm(double power) {
armMotor.set(power);
}

public void lock(boolean on) {
winchLockPiston.set(!on);
}

public void toggleLock() {
lock(!lockLocked());
}

public boolean lockLocked() {
return !winchLockPiston.get();
}

public boolean getArmLimitSwitchValue() {
return !armLimitSwitch.get();
}
Expand Down
62 changes: 41 additions & 21 deletions src/main/java/frc/robot/DriveBase.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,63 +2,83 @@

import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.CounterBase.EncodingType;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.VictorSP;
import edu.wpi.first.wpilibj.SpeedControllerGroup;

public class DriveBase {
public class DriveBase extends DifferentialDrive {

private final VictorSP driveLeft;
private final VictorSP driveRight;
private final Solenoid shifter;
private final SpeedControllerGroup driveLeft;
private final SpeedControllerGroup driveRight;

private final Solenoid leftShifter;
private final Solenoid rightShifter;

private final Encoder leftEncoder;
private final Encoder rightEncoder;

private final ADXRS450_Gyro gyro;

private boolean usingLeftEncoder = false;

private double heading;
public double courseHeading;

public DriveBase(int left, int right, int leftA, int leftB, int rightA, int rightB, int shifterChannel) {
driveLeft = new VictorSP(left);
driveRight = new VictorSP(right);
/**
*
* @param driveLeft positive moves forward. the front of the robot is
* opposite the intake.
* @param driveRight
* @param leftShifterChannel
* @param rightShifterChannel
* @param leftA
* @param leftB
* @param rightA
* @param rightB
*/
public DriveBase(SpeedControllerGroup driveLeft, SpeedControllerGroup driveRight, int leftShifterChannel,
int rightShifterChannel, int leftA, int leftB, int rightA, int rightB) {
super(driveLeft, driveRight);
this.driveLeft = driveLeft;
this.driveRight = driveRight;

leftShifter = new Solenoid(leftShifterChannel);
rightShifter = new Solenoid(rightShifterChannel);

leftEncoder = new Encoder(leftA, leftB, false, EncodingType.k4X);
rightEncoder = new Encoder(rightA, rightB, true, EncodingType.k4X);

leftEncoder.setDistancePerPulse((4 * Math.PI) / 1024.0);
rightEncoder.setDistancePerPulse((4 * Math.PI) / 1024.0);

shifter = new Solenoid(shifterChannel);

gyro = new ADXRS450_Gyro();
gyro.calibrate();
heading = gyro.getAngle();
courseHeading = heading;
}

public void drive(double leftPower, double rightPower) {
driveLeft.set(leftPower);
driveRight.set(-rightPower);
driveRight.set(rightPower);
}

public void drive(double power) {
drive(power, power);
}

public void useHighGear(boolean highGear) {
shifter.set(highGear);
leftShifter.set(highGear);
rightShifter.set(highGear);
}

public boolean getShifterState() {
return leftShifter.get();
}

public void toggleHighGear() {
useHighGear(!getShifterState());
}

public void resetGyro() {
gyro.reset();
// TODO: NOPE
}

public double getGyroAngle() {
return gyro.getAngle();
return 0;
}

public void resetEncoders() {
Expand Down
38 changes: 27 additions & 11 deletions src/main/java/frc/robot/Harvester.java
Original file line number Diff line number Diff line change
@@ -1,21 +1,28 @@
package frc.robot;

import edu.wpi.first.wpilibj.VictorSP;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.SpeedController;

public class Harvester {

// ESC declarations
private final VictorSP intakeMotor;
private final SpeedController intakeMotor;

// Piston declarations
private final Solenoid deployerPiston;
private final Solenoid portDeployerPiston;
private final Solenoid starboardDeployerPiston;


// class initializer
public Harvester(int intakeMotorPort, int deployPistonPort) {
intakeMotor = new VictorSP(intakeMotorPort);
deployerPiston = new Solenoid(deployPistonPort);
/**
*
* @param intakeMotor
* @param portDeployPistonPort This is the left piston, relative to the
* front being the climb side of the robot
* @param starboardDeployerPistonPort This is the right piston.
*/
public Harvester(SpeedController intakeMotor, int portDeployPistonPort, int starboardDeployerPistonPort) {
this.intakeMotor = intakeMotor;
portDeployerPiston = new Solenoid(portDeployPistonPort);
starboardDeployerPiston = new Solenoid(starboardDeployerPistonPort);
}

// Setters
Expand All @@ -28,8 +35,17 @@ public void intakeMotorControl(double power) {
intakeMotor.set(power);
}

// Piston
public void delpoyIntake(boolean deployed) {
deployerPiston.set(deployed);
// Pistons
public void deployIntake(boolean deployed) {
portDeployerPiston.set(deployed);
starboardDeployerPiston.set(deployed);
}

public boolean deployerDeployed() {
return portDeployerPiston.get();
}

public void toggleDeployer() {
deployIntake(!deployerDeployed());
}
}
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/Main.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@

/**
* Do NOT add any static variables to this class, or any initialization at all.
* Unless you know what you are doing, do not modify this file except to
* change the parameter class to the startRobot call.
* Unless you know what you are doing, do not modify this file except to change
* the parameter class to the startRobot call.
*/
public final class Main {
private Main() {
Expand All @@ -21,7 +21,8 @@ private Main() {
/**
* Main initialization function. Do not perform any initialization here.
*
* <p>If you change your main robot class, change the parameter type.
* <p>
* If you change your main robot class, change the parameter type.
*/
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
Expand Down
Loading