@@ -38,6 +38,7 @@ public class ShooterPivotSubsystem extends SubsystemBase {
38
38
private boolean alliance ; //true equals red alliance
39
39
private boolean autoAim ;
40
40
private double currentEncoderAngle ;
41
+ private double currentDistance ;
41
42
private Pose2d currentField = new Pose2d ();
42
43
43
44
//center of red speaker: (652.73 218.42)
@@ -92,34 +93,31 @@ public void setAngle(double angle){ //check if it works
92
93
public void setFieldPosition (Pose2d field ){
93
94
//System.out.println("setting field position");
94
95
currentField = field ;
95
- }
96
-
97
- public double getAutoAimAngle (double distance ){
98
- double speakerHeight = Units .inchesToMeters (80.51 );
99
- //System.out.println("Angle of shooter" + Math.atan(speakerHeight/distance));
100
- return Math .atan (speakerHeight /distance );
101
- }
102
-
103
- public void printCurrentAngle (){
104
- System .out .println ("radians: " + rotationEncoder .getPosition () + "degrees: " + rotationEncoder .getPosition () * 57.29 );
105
- }
106
-
107
- public double getDistance (){
108
96
109
97
if (alliance ){ //true = red
110
98
double xLength = Math .pow (currentField .getX ()-RED_X , 2 );
111
99
double yLength = Math .pow (currentField .getY ()-RED_Y , 2 );
112
100
//System.out.println("alliance red:" + alliance);
113
- return Math .sqrt (xLength + yLength );
101
+ currentDistance = Math .sqrt (xLength + yLength );
114
102
115
103
} else {
116
104
double xLength = Math .pow (currentField .getX ()-BLUE_X , 2 );
117
105
double yLength = Math .pow (currentField .getY ()-BLUE_Y , 2 );
118
106
119
- return Math .sqrt (xLength + yLength );
107
+ currentDistance = Math .sqrt (xLength + yLength );
120
108
}
121
109
}
122
110
111
+ public double getAutoAimAngle (){
112
+ double speakerHeight = Units .inchesToMeters (80.51 );
113
+ //System.out.println("Angle of shooter" + Math.atan(speakerHeight/distance));
114
+ return Math .atan (speakerHeight /currentDistance );
115
+ }
116
+
117
+ public void printCurrentAngle (){
118
+ System .out .println ("radians: " + rotationEncoder .getPosition () + "degrees: " + rotationEncoder .getPosition () * 57.29 );
119
+ }
120
+
123
121
public double getPosition (){
124
122
//System.out.println("rotation encoder position: " + rotationEncoder.getPosition());
125
123
return rotationEncoder .getPosition ();
@@ -142,7 +140,7 @@ public void periodic(){
142
140
// }
143
141
144
142
if (autoAim ){
145
- setAngle (getAutoAimAngle (getDistance () ));
143
+ setAngle (getAutoAimAngle ());
146
144
}
147
145
148
146
// printCurrentAngle();
0 commit comments