Skip to content

Commit 2be49c9

Browse files
Changes from practice field on 20 Feb 2020: (1) Draft of "ShooterReadyAimFire" (2) More complete motor configuration in Shooter.java (3) better calibration of Azimuth angle from Camera Positioning (4) regular use of voltage compensation (5) enable CTRE Voltage Compensation at 11.0 volts
1 parent c17f55d commit 2be49c9

File tree

4 files changed

+32
-38
lines changed

4 files changed

+32
-38
lines changed

src/main/java/org/mayheminc/robot2020/commands/ShooterReadyAimFire.java

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,13 @@ public ShooterReadyAimFire() {
2222
// super(new FooCommand(), new BarCommand());
2323
super();
2424
addCommands(new TargetingIsOnTarget());
25+
addCommands(new ShooterFireWhenReady());
26+
addCommands(new ShooterSetFeeder(1.0));
27+
addCommands(new ChimneySetChimney(0.5));
2528
addCommands(new MagazineSetTurntable(0.3));
26-
addCommands(new ChimneySetChimney(0.3));
27-
addCommands(new ParallelRaceGroup(new ShooterFireWhenReady(), new Wait(5.0)));
29+
30+
addCommands(new Wait(4.0));
31+
2832
addCommands(new MagazineSetTurntable(0.0));
2933
addCommands(new ChimneySetChimney(0.0));
3034
}

src/main/java/org/mayheminc/robot2020/subsystems/Shooter.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ public void init() {
6868

6969
private void configureFeederTalon() {
7070
feederTalon.changeControlMode(ControlMode.PercentOutput);
71-
71+
feederTalon.setNeutralMode(NeutralMode.Brake);
7272
feederTalon.configNominalOutputVoltage(+0.0f, -0.0f);
7373
feederTalon.configPeakOutputVoltage(+6.0, -6.0);
7474
}
@@ -80,6 +80,7 @@ private void configureHoodTalon() {
8080
hoodTalon.config_kF(0, 0.0, 0);
8181

8282
hoodTalon.changeControlMode(ControlMode.Position);
83+
feederTalon.setNeutralMode(NeutralMode.Coast);
8384
hoodTalon.configSelectedFeedbackSensor(FeedbackDevice.QuadEncoder);
8485

8586
hoodTalon.configNominalOutputVoltage(+0.0f, -0.0f);
@@ -93,14 +94,6 @@ private void configureHoodTalon() {
9394
hoodTalon.configReverseSoftLimitEnable(true);
9495
}
9596

96-
private void configureWheelTalon() {
97-
98-
shooterWheelTalon.setFeedbackDevice(FeedbackDevice.IntegratedSensor);
99-
100-
shooterWheelTalon.configNominalOutputVoltage(+0.0f, -0.0f);
101-
shooterWheelTalon.configPeakOutputVoltage(+12.0, 0.0);
102-
}
103-
10497
void configureTurretTalon() {
10598
turretTalon.config_kP(0, 1.0, 0);
10699
turretTalon.config_kI(0, 0.0, 0);
@@ -120,6 +113,13 @@ void configureTurretTalon() {
120113
this.setTurretVBus(0.0);
121114
}
122115

116+
private void configureWheelTalon() {
117+
shooterWheelTalon.setFeedbackDevice(FeedbackDevice.IntegratedSensor);
118+
shooterWheelTalon.setNeutralMode(NeutralMode.Coast);
119+
shooterWheelTalon.configNominalOutputVoltage(+0.0f, -0.0f);
120+
shooterWheelTalon.configPeakOutputVoltage(+12.0, 0.0);
121+
}
122+
123123
@Override
124124
public void periodic() {
125125
// This method will be called once per scheduler run

src/main/java/org/mayheminc/robot2020/subsystems/Targeting.java

Lines changed: 15 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,19 @@
2222
*/
2323

2424
public class Targeting extends SubsystemBase {
25-
// Put methods for controlling this subsystem
26-
// here. Call these from Commands.
25+
26+
// Logitech C920 Field of View Information:
27+
// Diagonal FOV = 78.0
28+
// Horizontal FOV = 70.42
29+
// Vertical FOV = 43.3
30+
private final static double FOV_HORIZ_CAMERA_IN_DEGREES = 78.0;
31+
32+
// Define the "target location" to be halfway from left to right
33+
private final double CENTER_OF_TARGET_X = 0.5;
34+
35+
// Calculate ticks per degree.
36+
// encoder ticks * turret pulley teeth / drive pulley teeth / 360 degrees
37+
private final double TICKS_PER_DEGREE = (4096.0 * 225.0 / 18.0 / 360.0); // was 6300 / 45
2738

2839
private static final double SPEED_EQ_M = -4.115;
2940
private static final double SPEED_EQ_B = 2.244;
@@ -37,7 +48,7 @@ public class Targeting extends SubsystemBase {
3748
private int m_priorFrameCount;
3849
private double m_priorFrameTime;
3950
private double[] ARRAY_OF_NEG_ONE = { -1.0 };
40-
private final static double FOV_CAMERA_IN_DEGREES = 78.0;
51+
4152
private double m_bestY = 0.0;
4253
private double m_bestX = 0.0;
4354
private double m_tilt = 0.0;
@@ -155,9 +166,6 @@ public double getRecommendedSpeed() {
155166
return speed;
156167
}
157168

158-
private final double CENTER_OF_TARGET_X = 0.5;
159-
private final double TICKS_PER_DEGREE = (6300.0 / 45.0);
160-
161169
/**
162170
* Return the desired turrent encoder ticks in the turret for the center of the
163171
* target.
@@ -178,7 +186,7 @@ public double findDesiredAzimuth(double X, double Y, double tilt, double area) {
178186
// compute the "x error" based upon the center for shooting
179187
xError = X - CENTER_OF_TARGET_X;
180188
// Find the angle error
181-
angleError = FOV_CAMERA_IN_DEGREES * xError;
189+
angleError = FOV_HORIZ_CAMERA_IN_DEGREES * xError;
182190
// convert the angle error into ticks
183191
ticksError = angleError * TICKS_PER_DEGREE;
184192

src/main/java/org/mayheminc/util/MayhemTalonSRX.java

Lines changed: 2 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,8 @@ public MayhemTalonSRX(int deviceNumber) {
2323
this.configNominalOutputReverse(0.0, 0);
2424
this.configPeakOutputForward(1.0, 0);
2525
this.configPeakOutputReverse(-1.0, 0);
26+
this.configVoltageCompSaturation(12.0); // "full output" scaled to 12.0V for all modes when enabled.
27+
this.enableVoltageCompensation(true); // turn on voltage compensation
2628

2729
this.setNeutralMode(NeutralMode.Coast);
2830

@@ -91,10 +93,6 @@ public void setFeedbackDevice(FeedbackDevice feedback) {
9193
this.configSelectedFeedbackSensor(feedback, 0, 0);
9294
}
9395

94-
// public void reverseSensor(boolean b) {
95-
96-
// }
97-
9896
public void configNominalOutputVoltage(float f, float g) {
9997
this.configNominalOutputForward(f / 12.0, 1000);
10098
this.configNominalOutputReverse(g / 12.0, 1000);
@@ -114,18 +112,10 @@ public void setPID(double wheelP, double wheelI, double wheelD, double wheelF, i
114112
this.config_kF(pidProfile, wheelF, 1000);
115113
}
116114

117-
// public double getSetpoint() {
118-
// return 0;
119-
// }
120-
121115
public double getError() {
122116
return this.getClosedLoopError(0);
123117
}
124118

125-
// public float getOutputVoltage() {
126-
// return (float) this.getMotorOutputVoltage();
127-
// }
128-
129119
int pidProfile;
130120

131121
public void setProfile(int pidSlot) {
@@ -141,10 +131,6 @@ public void setVoltageRampRate(double d) {
141131
this.configClosedloopRamp(0, 0);
142132
}
143133

144-
// public void enableControl() {
145-
146-
// }
147-
148134
public void setPosition(int zeroPositionCount) {
149135
this.setSelectedSensorPosition(zeroPositionCount, 0, 1000);
150136
}
@@ -160,8 +146,4 @@ public double getSpeed() {
160146
public void setEncPosition(int i) {
161147
setPosition(i);
162148
}
163-
164-
// public double get() {
165-
// return this.getOutputCurrent();
166-
// }
167149
}

0 commit comments

Comments
 (0)