Skip to content

Commit 6ee2cc7

Browse files
NRG948DriverStationedreed
authored andcommitted
Final comp changes.
1 parent 34a92cc commit 6ee2cc7

File tree

3 files changed

+187
-1
lines changed

3 files changed

+187
-1
lines changed
Lines changed: 174 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,174 @@
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+
}

src/main/java/frc/robot/Robot.java

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
import edu.wpi.first.wpilibj.PowerDistribution;
1111
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
1212
import edu.wpi.first.wpilibj.TimedRobot;
13+
import edu.wpi.first.wpilibj.Timer;
1314
import edu.wpi.first.wpilibj2.command.Command;
1415
import edu.wpi.first.wpilibj2.command.CommandScheduler;
1516

@@ -23,6 +24,7 @@ public class Robot extends TimedRobot {
2324

2425
private Command autonomousCommand;
2526
PowerDistribution powerDistribution = new PowerDistribution(1, ModuleType.kRev);
27+
private Timer gcTimer = new Timer();
2628

2729
private RobotContainer robotContainer;
2830

@@ -40,6 +42,7 @@ public void robotInit() {
4042
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
4143
// autonomous chooser on the dashboard.
4244
robotContainer = new RobotContainer();
45+
gcTimer.start();
4346
}
4447

4548
/**
@@ -57,6 +60,9 @@ public void robotPeriodic() {
5760
// and running subsystem periodic() methods. This must be called from the robot's periodic
5861
// block in order for anything in the Command-based framework to work.
5962
CommandScheduler.getInstance().run();
63+
if (gcTimer.advanceIfElapsed(5)) {
64+
System.gc();
65+
}
6066
}
6167

6268
/** This function is called once each time the robot enters Disabled mode. */

src/main/java/frc/robot/subsystems/ClimberSubsystem.java

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,15 @@ public class ClimberSubsystem extends SubsystemBase {
3636

3737
private final StatusSignal<Double> rightEncoder = winchRightMotor.getPosition();
3838
private double currentPosition;
39+
private double positionOffset;
3940

4041
/** Creates a new ClimberSubsystem. */
4142
public ClimberSubsystem() {
4243
winchLeftMotor.setInverted(true);
4344
winchRightMotor.setInverted(false);
4445
winchLeftMotor.setNeutralMode(NeutralModeValue.Brake);
4546
winchRightMotor.setNeutralMode(NeutralModeValue.Brake);
47+
resetCurrentPosition();
4648

4749
// TalonFXConfiguration config = new TalonFXConfiguration();
4850
// config.CurrentLimits =
@@ -70,7 +72,11 @@ public void stopMotors() {
7072
}
7173

7274
public double getCurrentPosition() {
73-
return currentPosition;
75+
return currentPosition - positionOffset;
76+
}
77+
78+
public void resetCurrentPosition() {
79+
positionOffset = rightEncoder.refresh().getValueAsDouble();
7480
}
7581

7682
@Override

0 commit comments

Comments
 (0)