File tree Expand file tree Collapse file tree 3 files changed +187
-1
lines changed Expand file tree Collapse file tree 3 files changed +187
-1
lines changed Original file line number Diff line number Diff line change
1
+ {
2
+ "version": 1.0,
3
+ "startingPose": {
4
+ "position": {
5
+ "x": 0.77,
6
+ "y": 6.66
7
+ },
8
+ "rotation": 60.0
9
+ },
10
+ "command": {
11
+ "type": "sequential",
12
+ "data": {
13
+ "commands": [
14
+ {
15
+ "type": "named",
16
+ "data": {
17
+ "name": "ShootSubwooferShot"
18
+ }
19
+ },
20
+ {
21
+ "type": "wait",
22
+ "data": {
23
+ "waitTime": 10.0
24
+ }
25
+ },
26
+ {
27
+ "type": "path",
28
+ "data": {
29
+ "pathName": "Amp Start to Amp Spike"
30
+ }
31
+ },
32
+ {
33
+ "type": "race",
34
+ "data": {
35
+ "commands": [
36
+ {
37
+ "type": "wait",
38
+ "data": {
39
+ "waitTime": 2.0
40
+ }
41
+ },
42
+ {
43
+ "type": "deadline",
44
+ "data": {
45
+ "commands": [
46
+ {
47
+ "type": "named",
48
+ "data": {
49
+ "name": "IntakeUntilNoteDetected"
50
+ }
51
+ },
52
+ {
53
+ "type": "named",
54
+ "data": {
55
+ "name": "AutoOrientToSpeaker"
56
+ }
57
+ },
58
+ {
59
+ "type": "named",
60
+ "data": {
61
+ "name": "SetShooterContinuous"
62
+ }
63
+ },
64
+ {
65
+ "type": "wait",
66
+ "data": {
67
+ "waitTime": 2.0
68
+ }
69
+ }
70
+ ]
71
+ }
72
+ }
73
+ ]
74
+ }
75
+ },
76
+ {
77
+ "type": "named",
78
+ "data": {
79
+ "name": "ShootAtCurrentRPM"
80
+ }
81
+ },
82
+ {
83
+ "type": "path",
84
+ "data": {
85
+ "pathName": "Amp Spike to Amp Note"
86
+ }
87
+ },
88
+ {
89
+ "type": "race",
90
+ "data": {
91
+ "commands": [
92
+ {
93
+ "type": "wait",
94
+ "data": {
95
+ "waitTime": 2.0
96
+ }
97
+ },
98
+ {
99
+ "type": "named",
100
+ "data": {
101
+ "name": "IntakeUntilNoteDetectedNoAutoCentering"
102
+ }
103
+ }
104
+ ]
105
+ }
106
+ },
107
+ {
108
+ "type": "path",
109
+ "data": {
110
+ "pathName": "Amp Note to Amp Farshot"
111
+ }
112
+ },
113
+ {
114
+ "type": "race",
115
+ "data": {
116
+ "commands": [
117
+ {
118
+ "type": "wait",
119
+ "data": {
120
+ "waitTime": 2.0
121
+ }
122
+ },
123
+ {
124
+ "type": "named",
125
+ "data": {
126
+ "name": "ShootAmpFarShot"
127
+ }
128
+ }
129
+ ]
130
+ }
131
+ },
132
+ {
133
+ "type": "path",
134
+ "data": {
135
+ "pathName": "Amp Farshot to Mid Amp Note"
136
+ }
137
+ },
138
+ {
139
+ "type": "race",
140
+ "data": {
141
+ "commands": [
142
+ {
143
+ "type": "wait",
144
+ "data": {
145
+ "waitTime": 3.0
146
+ }
147
+ },
148
+ {
149
+ "type": "named",
150
+ "data": {
151
+ "name": "IntakeUntilNoteDetectedNoAutoCentering"
152
+ }
153
+ }
154
+ ]
155
+ }
156
+ },
157
+ {
158
+ "type": "path",
159
+ "data": {
160
+ "pathName": "Mid Amp Note To Amp Farshot"
161
+ }
162
+ },
163
+ {
164
+ "type": "named",
165
+ "data": {
166
+ "name": "ShootAmpFarShot"
167
+ }
168
+ }
169
+ ]
170
+ }
171
+ },
172
+ "folder": null,
173
+ "choreoAuto": false
174
+ }
Original file line number Diff line number Diff line change 10
10
import edu .wpi .first .wpilibj .PowerDistribution ;
11
11
import edu .wpi .first .wpilibj .PowerDistribution .ModuleType ;
12
12
import edu .wpi .first .wpilibj .TimedRobot ;
13
+ import edu .wpi .first .wpilibj .Timer ;
13
14
import edu .wpi .first .wpilibj2 .command .Command ;
14
15
import edu .wpi .first .wpilibj2 .command .CommandScheduler ;
15
16
@@ -23,6 +24,7 @@ public class Robot extends TimedRobot {
23
24
24
25
private Command autonomousCommand ;
25
26
PowerDistribution powerDistribution = new PowerDistribution (1 , ModuleType .kRev );
27
+ private Timer gcTimer = new Timer ();
26
28
27
29
private RobotContainer robotContainer ;
28
30
@@ -40,6 +42,7 @@ public void robotInit() {
40
42
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
41
43
// autonomous chooser on the dashboard.
42
44
robotContainer = new RobotContainer ();
45
+ gcTimer .start ();
43
46
}
44
47
45
48
/**
@@ -57,6 +60,9 @@ public void robotPeriodic() {
57
60
// and running subsystem periodic() methods. This must be called from the robot's periodic
58
61
// block in order for anything in the Command-based framework to work.
59
62
CommandScheduler .getInstance ().run ();
63
+ if (gcTimer .advanceIfElapsed (5 )) {
64
+ System .gc ();
65
+ }
60
66
}
61
67
62
68
/** This function is called once each time the robot enters Disabled mode. */
Original file line number Diff line number Diff line change @@ -36,13 +36,15 @@ public class ClimberSubsystem extends SubsystemBase {
36
36
37
37
private final StatusSignal <Double > rightEncoder = winchRightMotor .getPosition ();
38
38
private double currentPosition ;
39
+ private double positionOffset ;
39
40
40
41
/** Creates a new ClimberSubsystem. */
41
42
public ClimberSubsystem () {
42
43
winchLeftMotor .setInverted (true );
43
44
winchRightMotor .setInverted (false );
44
45
winchLeftMotor .setNeutralMode (NeutralModeValue .Brake );
45
46
winchRightMotor .setNeutralMode (NeutralModeValue .Brake );
47
+ resetCurrentPosition ();
46
48
47
49
// TalonFXConfiguration config = new TalonFXConfiguration();
48
50
// config.CurrentLimits =
@@ -70,7 +72,11 @@ public void stopMotors() {
70
72
}
71
73
72
74
public double getCurrentPosition () {
73
- return currentPosition ;
75
+ return currentPosition - positionOffset ;
76
+ }
77
+
78
+ public void resetCurrentPosition () {
79
+ positionOffset = rightEncoder .refresh ().getValueAsDouble ();
74
80
}
75
81
76
82
@ Override
You can’t perform that action at this time.
0 commit comments