1
|
|
|
package org.usfirst.frc.team3695.robot.subsystems;
|
2
|
|
|
|
3
|
|
|
import com.ctre.phoenix.motorcontrol.ControlMode;
|
4
|
|
|
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
5
|
|
|
|
6
|
|
|
import edu.wpi.first.wpilibj.Joystick;
|
7
|
|
|
import edu.wpi.first.wpilibj.command.Subsystem;
|
8
|
|
|
|
9
|
|
|
import org.usfirst.frc.team3695.robot.Constants;
|
10
|
|
|
import org.usfirst.frc.team3695.robot.Robot;
|
11
|
|
|
import org.usfirst.frc.team3695.robot.enumeration.Bot;
|
12
|
|
|
import org.usfirst.frc.team3695.robot.util.Xbox;
|
13
|
|
|
|
14
|
|
|
/** VROOM VROOM */
|
15
|
|
|
public class SubsystemManipulator extends Subsystem {
|
16
|
|
|
|
17
|
|
|
|
18
|
|
|
private TalonSRX armLeft;
|
19
|
|
|
private TalonSRX armRight;
|
20
|
|
|
|
21
|
|
|
public Boolean revving;
|
22
|
|
|
|
23
|
|
|
public long redlineTime;
|
24
|
|
|
|
25
|
|
|
/** applies left arm motor invert */
|
26
|
|
|
public static final double leftArmify(double left) {
|
27
|
|
|
Boolean invert = Robot.bot == Bot.OOF ? Constants.OOF.LEFT_ARM_MOTOR_INVERT : Constants.TEUFELSKIND.LEFT_ARM_MOTOR_INVERT;
|
28
|
|
|
return left * (invert ? -1.0 : 1.0);
|
29
|
|
|
}
|
30
|
|
|
|
31
|
|
|
/** applies right arm motor invert */
|
32
|
|
|
public static final double rightArmify(double right) {
|
33
|
|
|
Boolean invert = Robot.bot == Bot.OOF ? Constants.OOF.RIGHT_ARM_MOTOR_INVERT : Constants.TEUFELSKIND.RIGHT_ARM_MOTOR_INVERT;
|
34
|
|
|
return right * (invert ? -1.0 : 1.0);
|
35
|
|
|
}
|
36
|
|
|
|
37
|
|
|
/** runs at robot boot */
|
38
|
|
|
public void initDefaultCommand() {}
|
39
|
|
|
|
40
|
|
|
/** gives birth to the CANTalons */
|
41
|
|
|
public SubsystemManipulator(){
|
42
|
|
|
armLeft = new TalonSRX(Constants.LEFT_FLYWHEEL);
|
43
|
|
|
armRight = new TalonSRX(Constants.RIGHT_FLYWHEEL);
|
44
|
|
|
}
|
45
|
|
|
|
46
|
|
|
/** eat the power cube */
|
47
|
|
|
public void eat() {
|
48
|
|
|
armLeft.set(ControlMode.PercentOutput, leftArmify(-1));
|
49
|
|
|
armRight.set(ControlMode.PercentOutput, rightArmify(-1));
|
50
|
|
|
}
|
51
|
|
|
|
52
|
|
|
/** spit out the power cube */
|
53
|
|
|
public void spit() {
|
54
|
|
|
armLeft.set(ControlMode.PercentOutput, leftArmify(1));
|
55
|
|
|
armRight.set(ControlMode.PercentOutput, rightArmify(1));
|
56
|
|
|
}
|
57
|
|
|
|
58
|
|
|
public void spinByJoystick(Joystick joy) {
|
59
|
|
|
int speed = 0;
|
60
|
|
|
speed += joy.getRawButton(Xbox.RB) ? 1d : 0d;
|
61
|
|
|
speed -= joy.getRawButton(Xbox.LB) ? 1d : 0d;
|
62
|
|
|
armLeft.set(ControlMode.PercentOutput, leftArmify(speed));
|
63
|
|
|
armRight.set(ControlMode.PercentOutput, rightArmify(speed));
|
64
|
|
|
}
|
65
|
|
|
|
66
|
|
|
/** STOP SPINNING ME RIGHT ROUND, BABY RIGHT ROUND */
|
67
|
|
|
public void stopSpinning() {
|
68
|
|
|
armLeft.set(ControlMode.PercentOutput, 0);
|
69
|
|
|
armRight.set(ControlMode.PercentOutput, 0);
|
70
|
|
|
}
|
71
|
|
|
|
72
|
|
|
/** imitates an engine revving and idling */
|
73
|
|
|
public void rev(Joystick joy) {
|
74
|
|
|
double intensity = Math.abs(Math.sqrt((Math.pow(Xbox.LEFT_X(joy), 2) + Math.pow(Xbox.LEFT_X(joy), 2)))); // intensity is 0.0-1.0, power of trigger
|
|
|
|
|
75
|
|
|
|
76
|
|
|
int rpm = (int) ((((double) Constants.REDLINE - (double) Constants.IDLE) * intensity) + Constants.IDLE); // rpm is the rpm being imitated
|
77
|
|
|
int miliseconds = (1 / rpm) * 60000; // length in miliseconds of each rev curve, based on rpm
|
|
|
|
|
78
|
|
|
|
79
|
|
|
if (!revving) { redlineTime = System.currentTimeMillis(); revving = true; } // reset rev curve if not revving
|
80
|
|
|
else if (System.currentTimeMillis() - redlineTime >= miliseconds) { revving = false; } // stop revving if time is up
|
81
|
|
|
|
82
|
|
|
double speed = (System.currentTimeMillis() - redlineTime) / (double) miliseconds; // set speed to progress from 0.0-1.0 of the curve
|
83
|
|
|
speed = speed > 1.0 ? 1.0 : speed; // quick concat the speed under 1.0
|
84
|
|
|
|
85
|
|
|
speed = generateCurve(speed, 0, .25 * (intensity * .8 + .2), (intensity * .8 + .2)); // find y value on curve, given x and parameters
|
|
|
|
|
86
|
|
|
|
87
|
|
|
armLeft.set(ControlMode.PercentOutput, leftArmify(speed));
|
88
|
|
|
armRight.set(ControlMode.PercentOutput, rightArmify(speed));
|
89
|
|
|
}
|
90
|
|
|
|
91
|
|
|
|
92
|
|
|
/** generates a quadratic curve based on the three points in constants */
|
93
|
|
|
public double generateRedlineCurve(double x) {
|
94
|
|
|
// TODO simplify this; I just plugged our variables into the equation for this
|
95
|
|
|
double y;
|
96
|
|
|
y = Constants.REDLINE_START * (((x - .5) * (x - 1))/(.5));
|
|
|
|
|
97
|
|
|
y += Constants.REDLINE_MID * ((x * (x - 1))/(-.25));
|
|
|
|
|
98
|
|
|
y += Constants.REDLINE_END * ((x * (x-.5))/(.5));
|
|
|
|
|
99
|
|
|
return y;
|
100
|
|
|
}
|
101
|
|
|
|
102
|
|
|
/** generates a quadratic curve based on the three points given */
|
103
|
|
|
public double generateCurve(double x, double start, double mid, double end) {
|
104
|
|
|
// TODO simplify this; I just plugged our variables into the equation for this
|
105
|
|
|
double y;
|
106
|
|
|
y = start * (((x - .5) * (x - 1))/(.5));
|
|
|
|
|
107
|
|
|
y += mid * ((x * (x - 1))/(-.25));
|
|
|
|
|
108
|
|
|
y += end * ((x * (x-.5))/(.5));
|
|
|
|
|
109
|
|
|
return y;
|
110
|
|
|
}
|
111
|
|
|
|
112
|
|
|
}
|
113
|
|
|
|
114
|
|
|
|
Using constants for hard-coded numbers is a best practice. A constant’s name can explain the rationale behind this magic number. It is also easier to find if you ever need to change it.