Compare commits
115 Commits
Author | SHA1 | Date | |
---|---|---|---|
|
e17e0129ca | ||
|
5bc17643ec | ||
|
81aefe3d56 | ||
|
57af33dfed | ||
|
a8489dadad | ||
|
27ba15f95f | ||
|
7222a1ec1e | ||
a0dc53800f | |||
99c50dc4fc | |||
cdb2947600 | |||
d709f194b4 | |||
|
dde21cddfd | ||
|
fa79ad86f0 | ||
1cd730c588 | |||
|
74b72fd992 | ||
be5abb84bd | |||
|
f7daa030bd | ||
|
d64509b3aa | ||
|
3f24040784 | ||
|
d8c572e47d | ||
0f2363826e | |||
fcc3a09070 | |||
e181361006 | |||
03bf04f40e | |||
|
876cf655f1 | ||
|
8e1d513b86 | ||
|
2a128b40fc | ||
|
448b92e8ab | ||
|
0735fdb41a | ||
|
4599457e14 | ||
899f8f3bf6 | |||
4076c5d368 | |||
|
a023213a18 | ||
|
75c59ddbe5 | ||
|
a7a4c4ef31 | ||
1facdb07e5 | |||
ab36e8dadf | |||
|
c6017d60b4 | ||
|
b7aec15b74 | ||
|
d3f7d01246 | ||
|
125ad2c417 | ||
4ddd030426 | |||
1fbc87cf67 | |||
|
035603c6eb | ||
|
b6b2f8f5f3 | ||
ab0439e309 | |||
7d2ef1017c | |||
|
015fec18d2 | ||
|
d524a87319 | ||
|
f06c9b0428 | ||
|
7b460fa3de | ||
|
908c5d0b96 | ||
|
46a71c5fba | ||
|
a45f27eb7f | ||
2b35ef9267 | |||
b070971185 | |||
|
2ca57f2556 | ||
|
144c9a1d71 | ||
|
368948b2aa | ||
|
f7e38ca9bc | ||
|
1367087b14 | ||
|
e7be2d6428 | ||
|
437bf16505 | ||
|
c22c507da0 | ||
a11b463cc2 | |||
910caa963e | |||
bf63394d77 | |||
|
954c82a7a0 | ||
|
0063ce1722 | ||
|
810ea210b1 | ||
|
b8894d4efd | ||
|
4197299808 | ||
|
bdbcf2e38f | ||
|
0e4efef6ee | ||
|
d0137d1531 | ||
8d93e7f24f | |||
4ece413126 | |||
|
f1406f0db0 | ||
|
9804a3cfbf | ||
|
9f51699e35 | ||
|
1c1e8fb714 | ||
|
104c9195bc | ||
|
205da73570 | ||
1989806378 | |||
fd72aaf8bd | |||
|
99525dc7d7 | ||
|
2533a3a462 | ||
|
ed5d3bc08b | ||
|
e9f55c9fd6 | ||
bde1715f76 | |||
|
48a4f2e0f4 | ||
|
fc75e1f997 | ||
|
d6508d513b | ||
1a899887da | |||
7e65352246 | |||
|
ee263139c1 | ||
|
938198d4e2 | ||
|
b460501b95 | ||
|
5e39e6fc4d | ||
|
6bec6011ca | ||
e1111511b7 | |||
c3d4b8c43c | |||
4944f4662b | |||
|
4f6552202c | ||
|
adb6d5554f | ||
eca7bb1891 | |||
6687dc73ea | |||
|
ea96a16864 | ||
|
dfa05d79a7 | ||
650e8341ec | |||
|
025d9e47f0 | ||
f0cdb9a241 | |||
ae9e9577c2 | |||
|
89d155ae5e | ||
|
787251658c |
12
.pathplanner/settings.json
Normal file
12
.pathplanner/settings.json
Normal file
@ -0,0 +1,12 @@
|
||||
{
|
||||
"robotWidth": 0.9,
|
||||
"robotLength": 0.9,
|
||||
"holonomicMode": true,
|
||||
"pathFolders": [],
|
||||
"autoFolders": [],
|
||||
"defaultMaxVel": 3.0,
|
||||
"defaultMaxAccel": 3.0,
|
||||
"defaultMaxAngVel": 540.0,
|
||||
"defaultMaxAngAccel": 720.0,
|
||||
"maxModuleSpeed": 4.5
|
||||
}
|
1
networktables.json
Normal file
1
networktables.json
Normal file
@ -0,0 +1 @@
|
||||
[]
|
92
simgui-ds.json
Normal file
92
simgui-ds.json
Normal file
@ -0,0 +1,92 @@
|
||||
{
|
||||
"keyboardJoysticks": [
|
||||
{
|
||||
"axisConfig": [
|
||||
{
|
||||
"decKey": 65,
|
||||
"incKey": 68
|
||||
},
|
||||
{
|
||||
"decKey": 87,
|
||||
"incKey": 83
|
||||
},
|
||||
{
|
||||
"decKey": 69,
|
||||
"decayRate": 0.0,
|
||||
"incKey": 82,
|
||||
"keyRate": 0.009999999776482582
|
||||
}
|
||||
],
|
||||
"axisCount": 3,
|
||||
"buttonCount": 4,
|
||||
"buttonKeys": [
|
||||
90,
|
||||
88,
|
||||
67,
|
||||
86
|
||||
],
|
||||
"povConfig": [
|
||||
{
|
||||
"key0": 328,
|
||||
"key135": 323,
|
||||
"key180": 322,
|
||||
"key225": 321,
|
||||
"key270": 324,
|
||||
"key315": 327,
|
||||
"key45": 329,
|
||||
"key90": 326
|
||||
}
|
||||
],
|
||||
"povCount": 1
|
||||
},
|
||||
{
|
||||
"axisConfig": [
|
||||
{
|
||||
"decKey": 74,
|
||||
"incKey": 76
|
||||
},
|
||||
{
|
||||
"decKey": 73,
|
||||
"incKey": 75
|
||||
}
|
||||
],
|
||||
"axisCount": 2,
|
||||
"buttonCount": 4,
|
||||
"buttonKeys": [
|
||||
77,
|
||||
44,
|
||||
46,
|
||||
47
|
||||
],
|
||||
"povCount": 0
|
||||
},
|
||||
{
|
||||
"axisConfig": [
|
||||
{
|
||||
"decKey": 263,
|
||||
"incKey": 262
|
||||
},
|
||||
{
|
||||
"decKey": 265,
|
||||
"incKey": 264
|
||||
}
|
||||
],
|
||||
"axisCount": 2,
|
||||
"buttonCount": 6,
|
||||
"buttonKeys": [
|
||||
260,
|
||||
268,
|
||||
266,
|
||||
261,
|
||||
269,
|
||||
267
|
||||
],
|
||||
"povCount": 0
|
||||
},
|
||||
{
|
||||
"axisCount": 0,
|
||||
"buttonCount": 0,
|
||||
"povCount": 0
|
||||
}
|
||||
]
|
||||
}
|
10
simgui.json
Normal file
10
simgui.json
Normal file
@ -0,0 +1,10 @@
|
||||
{
|
||||
"NTProvider": {
|
||||
"types": {
|
||||
"/FMSInfo": "FMSInfo"
|
||||
}
|
||||
},
|
||||
"NetworkTables Info": {
|
||||
"visible": true
|
||||
}
|
||||
}
|
99
src/main/deploy/pathplanner/autos/mode 1.auto
Normal file
99
src/main/deploy/pathplanner/autos/mode 1.auto
Normal file
@ -0,0 +1,99 @@
|
||||
{
|
||||
"version": 1.0,
|
||||
"startingPose": {
|
||||
"position": {
|
||||
"x": 5.76,
|
||||
"y": 3.93
|
||||
},
|
||||
"rotation": 0
|
||||
},
|
||||
"command": {
|
||||
"type": "sequential",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "1"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 2.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 1.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "lancer"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "2"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 2.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "lancer"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "wait",
|
||||
"data": {
|
||||
"waitTime": 1.0
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "named",
|
||||
"data": {
|
||||
"name": "lancer"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "3"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
"folder": null,
|
||||
"choreoAuto": false
|
||||
}
|
1
src/main/deploy/pathplanner/navgrid.json
Normal file
1
src/main/deploy/pathplanner/navgrid.json
Normal file
File diff suppressed because one or more lines are too long
137
src/main/deploy/pathplanner/paths/1.path
Normal file
137
src/main/deploy/pathplanner/paths/1.path
Normal file
@ -0,0 +1,137 @@
|
||||
{
|
||||
"version": 1.0,
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 5.76,
|
||||
"y": 3.93
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 5.801431310952625,
|
||||
"y": 3.93
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 7.3,
|
||||
"y": 3.2979107312440648
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 6.660542519857817,
|
||||
"y": 3.2979107312440648
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 7.948552157357058,
|
||||
"y": 3.2979107312440648
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 8.005090218423552,
|
||||
"y": 4.1022792022792025
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 7.89972103271822,
|
||||
"y": 3.7203159040973657
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 8.09701804368471,
|
||||
"y": 4.435517568850902
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 8.774985754985755,
|
||||
"y": 4.9411206077872745
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 8.087653449552494,
|
||||
"y": 5.261875683656129
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 9.292079772079772,
|
||||
"y": 4.699810066476734
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 10.41,
|
||||
"y": 3.07
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 9.74022792022792,
|
||||
"y": 2.8152896486229815
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 10.747612735931797,
|
||||
"y": 3.19839212203024
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 10.4,
|
||||
"y": 5.2
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 10.388509021842355,
|
||||
"y": 5.2
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [
|
||||
{
|
||||
"waypointRelativePos": 1,
|
||||
"rotationDegrees": 0.0,
|
||||
"rotateFast": false
|
||||
},
|
||||
{
|
||||
"waypointRelativePos": 2,
|
||||
"rotationDegrees": 76.0,
|
||||
"rotateFast": false
|
||||
},
|
||||
{
|
||||
"waypointRelativePos": 3,
|
||||
"rotationDegrees": 90.0,
|
||||
"rotateFast": false
|
||||
},
|
||||
{
|
||||
"waypointRelativePos": 4,
|
||||
"rotationDegrees": 90.0,
|
||||
"rotateFast": false
|
||||
}
|
||||
],
|
||||
"constraintZones": [],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3.0,
|
||||
"maxAcceleration": 3.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 90.55,
|
||||
"rotateFast": false
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"previewStartingState": {
|
||||
"rotation": 0,
|
||||
"velocity": 0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
52
src/main/deploy/pathplanner/paths/2.path
Normal file
52
src/main/deploy/pathplanner/paths/2.path
Normal file
@ -0,0 +1,52 @@
|
||||
{
|
||||
"version": 1.0,
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 10.4,
|
||||
"y": 5.2
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 9.705754985754986,
|
||||
"y": 4.745773979107312
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 9.3,
|
||||
"y": 4.0
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 9.936805143100598,
|
||||
"y": 4.758914817072607
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [],
|
||||
"constraintZones": [],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3.0,
|
||||
"maxAcceleration": 3.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 90.0,
|
||||
"rotateFast": false
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"previewStartingState": {
|
||||
"rotation": 90.60460638654384,
|
||||
"velocity": 0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
95
src/main/deploy/pathplanner/paths/3.path
Normal file
95
src/main/deploy/pathplanner/paths/3.path
Normal file
@ -0,0 +1,95 @@
|
||||
{
|
||||
"version": 1.0,
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 9.3,
|
||||
"y": 4.0
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 9.062260208926876,
|
||||
"y": 3.550712250712251
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 8.545166191832859,
|
||||
"y": 3.2749287749287745
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 9.07375118708452,
|
||||
"y": 3.2749287749287745
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 8.004601461786502,
|
||||
"y": 3.2749287749287745
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 7.441748878923768,
|
||||
"y": 4.964798206278027
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 7.957769732906826,
|
||||
"y": 4.951218710120577
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 7.005091708933264,
|
||||
"y": 4.976289184435672
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 5.76,
|
||||
"y": 3.93
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 6.374633781763827,
|
||||
"y": 4.277503736920778
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [
|
||||
{
|
||||
"waypointRelativePos": 1,
|
||||
"rotationDegrees": 30.0,
|
||||
"rotateFast": false
|
||||
},
|
||||
{
|
||||
"waypointRelativePos": 2,
|
||||
"rotationDegrees": 0.0,
|
||||
"rotateFast": false
|
||||
}
|
||||
],
|
||||
"constraintZones": [],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3.0,
|
||||
"maxAcceleration": 3.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 0.8151092400891717,
|
||||
"rotateFast": false
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"previewStartingState": {
|
||||
"rotation": 89.62831416675282,
|
||||
"velocity": 0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
8
src/main/deploy/swerve/controllerproperties.json
Normal file
8
src/main/deploy/swerve/controllerproperties.json
Normal file
@ -0,0 +1,8 @@
|
||||
{
|
||||
"angleJoystickRadiusDeadband": 0.5,
|
||||
"heading": {
|
||||
"p": 0.4,
|
||||
"i": 0,
|
||||
"d": 0.01
|
||||
}
|
||||
}
|
30
src/main/deploy/swerve/modules/backleft.json
Normal file
30
src/main/deploy/swerve/modules/backleft.json
Normal file
@ -0,0 +1,30 @@
|
||||
{
|
||||
"location": {
|
||||
"front": -12.375,
|
||||
"left": 12.375
|
||||
},
|
||||
"absoluteEncoderOffset":209.443,
|
||||
"drive": {
|
||||
"type": "talonFX",
|
||||
"id": 8,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "talonFX",
|
||||
"id": 9,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"angle": true,
|
||||
"drive": false
|
||||
},
|
||||
"conversionFactor": {
|
||||
"angle": 0,
|
||||
"drive": 0
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 6,
|
||||
"canbus": null
|
||||
}
|
||||
}
|
30
src/main/deploy/swerve/modules/backright.json
Normal file
30
src/main/deploy/swerve/modules/backright.json
Normal file
@ -0,0 +1,30 @@
|
||||
{
|
||||
"location": {
|
||||
"front": -12.375,
|
||||
"left": -12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 5.537,
|
||||
"drive": {
|
||||
"type": "talonFX",
|
||||
"id": 11,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "talonFX",
|
||||
"id": 12,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"angle": true,
|
||||
"drive": false
|
||||
},
|
||||
"conversionFactor": {
|
||||
"angle": 0,
|
||||
"drive": 0
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 7,
|
||||
"canbus": null
|
||||
}
|
||||
}
|
30
src/main/deploy/swerve/modules/frontleft.json
Normal file
30
src/main/deploy/swerve/modules/frontleft.json
Normal file
@ -0,0 +1,30 @@
|
||||
{
|
||||
"location": {
|
||||
"front": 12.375,
|
||||
"left": 12.375
|
||||
},
|
||||
"absoluteEncoderOffset":258.223 ,
|
||||
"drive": {
|
||||
"type": "talonFX",
|
||||
"id": 2,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "talonFX",
|
||||
"id": 3,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"angle": true,
|
||||
"drive": false
|
||||
},
|
||||
"conversionFactor": {
|
||||
"angle": 0,
|
||||
"drive": 0
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 4,
|
||||
"canbus": null
|
||||
}
|
||||
}
|
30
src/main/deploy/swerve/modules/frontright.json
Normal file
30
src/main/deploy/swerve/modules/frontright.json
Normal file
@ -0,0 +1,30 @@
|
||||
{
|
||||
"location": {
|
||||
"front": 12.375,
|
||||
"left": -12.375
|
||||
},
|
||||
"absoluteEncoderOffset": 110.215,
|
||||
"drive": {
|
||||
"type": "talonFX",
|
||||
"id": 18,
|
||||
"canbus": null
|
||||
},
|
||||
"angle": {
|
||||
"type": "talonFX",
|
||||
"id": 17,
|
||||
"canbus": null
|
||||
},
|
||||
"inverted": {
|
||||
"angle": true,
|
||||
"drive": false
|
||||
},
|
||||
"conversionFactor": {
|
||||
"angle": 0,
|
||||
"drive": 0
|
||||
},
|
||||
"encoder": {
|
||||
"type": "cancoder",
|
||||
"id": 5,
|
||||
"canbus": null
|
||||
}
|
||||
}
|
16
src/main/deploy/swerve/modules/physicalproperties.json
Normal file
16
src/main/deploy/swerve/modules/physicalproperties.json
Normal file
@ -0,0 +1,16 @@
|
||||
{
|
||||
"optimalVoltage": 12,
|
||||
"wheelGripCoefficientOfFriction": 1.19,
|
||||
"currentLimit": {
|
||||
"drive": 40,
|
||||
"angle": 20
|
||||
},
|
||||
"conversionFactor": {
|
||||
"angle": 16.8,
|
||||
"drive": 0.04
|
||||
},
|
||||
"rampRate": {
|
||||
"drive": 0.25,
|
||||
"angle": 0.25
|
||||
}
|
||||
}
|
16
src/main/deploy/swerve/modules/pidfproperties.json
Normal file
16
src/main/deploy/swerve/modules/pidfproperties.json
Normal file
@ -0,0 +1,16 @@
|
||||
{
|
||||
"drive": {
|
||||
"p": 0.0020645,
|
||||
"i": 0,
|
||||
"d": 0,
|
||||
"f": 0,
|
||||
"iz": 0
|
||||
},
|
||||
"angle": {
|
||||
"p": 0.01,
|
||||
"i": 0,
|
||||
"d": 0,
|
||||
"f": 0,
|
||||
"iz": 0
|
||||
}
|
||||
}
|
14
src/main/deploy/swerve/swervedrive.json
Normal file
14
src/main/deploy/swerve/swervedrive.json
Normal file
@ -0,0 +1,14 @@
|
||||
{
|
||||
"imu": {
|
||||
"type": "pigeon",
|
||||
"id": 0,
|
||||
"canbus": null
|
||||
},
|
||||
"invertedIMU": false,
|
||||
"modules": [
|
||||
"frontleft.json",
|
||||
"frontright.json",
|
||||
"backleft.json",
|
||||
"backright.json"
|
||||
]
|
||||
}
|
45
src/main/java/frc/robot/Commands/Desaccumuler.java
Normal file
45
src/main/java/frc/robot/Commands/Desaccumuler.java
Normal file
@ -0,0 +1,45 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.Subsystems.Accumulateur;
|
||||
|
||||
public class Desaccumuler extends Command {
|
||||
private Accumulateur accumulateur;
|
||||
/** Creates a new Desaccumuler. */
|
||||
public Desaccumuler(Accumulateur accumulateur){
|
||||
this.accumulateur = accumulateur;
|
||||
addRequirements(accumulateur);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
|
||||
}
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
/*if(accumulateur.photocell() || accumulateur.photocell2()){
|
||||
accumulateur.desaccumule(0);
|
||||
accumulateur.masterslave2();
|
||||
|
||||
}
|
||||
else{
|
||||
*/ accumulateur.desaccumule(0.4);
|
||||
accumulateur.masterslave2();
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
accumulateur.desaccumule(0);
|
||||
}
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return /*accumulateur.photocell()==true || accumulateur.photocell2()==true*/ false;
|
||||
}
|
||||
}
|
53
src/main/java/frc/robot/Commands/FollowAprilTag.java
Normal file
53
src/main/java/frc/robot/Commands/FollowAprilTag.java
Normal file
@ -0,0 +1,53 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.Subsystems.Lanceur;
|
||||
import frc.robot.Subsystems.Limelight3G;
|
||||
|
||||
public class FollowAprilTag extends Command {
|
||||
|
||||
private Limelight3G enlignement;
|
||||
private Lanceur lanceur;
|
||||
/** Creates a new Limelight3g. */
|
||||
public FollowAprilTag(Limelight3G enlignement, Lanceur lanceur) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
this.lanceur = lanceur;
|
||||
this.enlignement = enlignement;
|
||||
addRequirements(lanceur, enlignement);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
|
||||
|
||||
if (enlignement.getv()==1)
|
||||
{
|
||||
lanceur.tourelRotation(0,0, enlignement.getx()/30);
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
lanceur.tourelRotation(0, 0, 0);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.tourelRotation(0, 0, 0);
|
||||
}
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
50
src/main/java/frc/robot/Commands/LEDactive.java
Normal file
50
src/main/java/frc/robot/Commands/LEDactive.java
Normal file
@ -0,0 +1,50 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.Subsystems.Accumulateur;
|
||||
import frc.robot.Subsystems.LED;
|
||||
|
||||
public class LEDactive extends Command {
|
||||
private Accumulateur accumulateur;
|
||||
private LED led;
|
||||
/** Creates a new LEDactive. */
|
||||
public LEDactive(Accumulateur accumulateur, LED led) {
|
||||
this.accumulateur = accumulateur;
|
||||
this.led = led;
|
||||
addRequirements(accumulateur,led);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
led.led(25, 25, 100);
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(accumulateur.photocell())
|
||||
led.led(0, 255, 0);
|
||||
else{
|
||||
led.led(255, 0, 0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
led.led(0, 0, 0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
@ -3,37 +3,42 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.Subsystems.Accumulateur;
|
||||
import frc.robot.Subsystems.Lanceur;
|
||||
|
||||
public class Lancer extends Command {
|
||||
private Lanceur lanceur;
|
||||
private Accumulateur accumulateur;
|
||||
/** Creates a new Lancer. */
|
||||
public Lancer(Lanceur lanceur) {
|
||||
public Lancer(Lanceur lanceur,Accumulateur accumulateur) {
|
||||
this.lanceur = lanceur;
|
||||
addRequirements(lanceur);
|
||||
this.accumulateur = accumulateur;
|
||||
addRequirements(lanceur, accumulateur);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
lanceur.setPID(0, 0, 0);
|
||||
lanceur.PIDlanceur(0, 0, 0);
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
lanceur.lance(0.5);
|
||||
lanceur.lance();
|
||||
accumulateur.Petitlanceur(0.9);
|
||||
accumulateur.desaccumule(0.2);
|
||||
lanceur.masterslave();
|
||||
accumulateur.rouesbleue(0.5);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.lance(0);
|
||||
accumulateur.desaccumule(0);
|
||||
accumulateur.Petitlanceur(0);
|
||||
accumulateur.rouesbleue(0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
|
48
src/main/java/frc/robot/Commands/LancerModeAuto.java
Normal file
48
src/main/java/frc/robot/Commands/LancerModeAuto.java
Normal file
@ -0,0 +1,48 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
import frc.robot.Subsystems.Accumulateur;
|
||||
import frc.robot.Subsystems.Lanceur;
|
||||
|
||||
public class LancerModeAuto extends Command {
|
||||
private Lanceur lanceur;
|
||||
private Accumulateur accumulateur;
|
||||
/** Creates a new Lancer. */
|
||||
public LancerModeAuto(Lanceur lanceur,Accumulateur accumulateur) {
|
||||
this.lanceur = lanceur;
|
||||
this.accumulateur = accumulateur;
|
||||
addRequirements(lanceur, accumulateur);
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
lanceur.PIDlanceur(0, 0, 0);
|
||||
}
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
lanceur.lance();
|
||||
accumulateur.Petitlanceur(0.9);
|
||||
accumulateur.desaccumule(0.2);
|
||||
lanceur.masterslave();
|
||||
accumulateur.rouesbleue(0.7);
|
||||
}
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
lanceur.lance(0);
|
||||
accumulateur.desaccumule(0);
|
||||
accumulateur.Petitlanceur(0);
|
||||
accumulateur.rouesbleue(0);
|
||||
}
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
42
src/main/java/frc/robot/Commands/Tourel.java
Normal file
42
src/main/java/frc/robot/Commands/Tourel.java
Normal file
@ -0,0 +1,42 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.Subsystems.Lanceur;
|
||||
|
||||
public class Tourel extends Command {
|
||||
private Lanceur lanceur;
|
||||
/** Creates a new Tourel. */
|
||||
public Tourel(Lanceur lanceur) {
|
||||
this.lanceur = lanceur;
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
if(lanceur.limitswitch1()){
|
||||
lanceur.touchagedelimitswitch1(0);
|
||||
}
|
||||
else if(lanceur.limitswitch2()){
|
||||
lanceur.touchagedelimitswitch2(0);
|
||||
}
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
47
src/main/java/frc/robot/Commands/Tracker_Couleur_Forme.java
Normal file
47
src/main/java/frc/robot/Commands/Tracker_Couleur_Forme.java
Normal file
@ -0,0 +1,47 @@
|
||||
// // Copyright (c) FIRST and other WPILib contributors.
|
||||
// // Open Source Software; you can modify and/or share it under the terms of
|
||||
// // the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// package frc.robot.Commands;
|
||||
|
||||
// import edu.wpi.first.wpilibj2.command.Command;
|
||||
// import frc.robot.Subsystems.Limelight3G;
|
||||
|
||||
|
||||
// public class Tracker_Couleur_Forme extends Command {
|
||||
// /** Creates a new Tracker_Couleur_Forme. */
|
||||
// private Limelight3G pipeline;
|
||||
// public Tracker_Couleur_Forme(Limelight3G tracker_couleur, Limelight3G tracker_forme) {
|
||||
// // Use addRequirements() here to declare subsystem dependencies.
|
||||
// this.pipeline = pipeline;
|
||||
// this.tracker_couleur = tracker_couleur;
|
||||
// this.tracker_forme = tracker_forme;
|
||||
// }
|
||||
|
||||
// // Called when the command is initially scheduled.
|
||||
// @Override
|
||||
// public void initialize() {}
|
||||
|
||||
// // Called every time the scheduler runs while the command is scheduled.
|
||||
// @Override
|
||||
// public void execute() {
|
||||
// if (pipeline == 1) {
|
||||
// Limelight3G.tracker_couleur;
|
||||
// }
|
||||
// else if (pipeline == 2){
|
||||
// Limelight3G.tracker_forme;
|
||||
// }
|
||||
|
||||
|
||||
// }
|
||||
|
||||
// // Called once the command ends or is interrupted.
|
||||
// @Override
|
||||
// public void end(boolean interrupted) {}
|
||||
|
||||
// // Returns true when the command should end.
|
||||
// @Override
|
||||
// public boolean isFinished() {
|
||||
// return false;
|
||||
// }
|
||||
// }
|
@ -4,17 +4,96 @@
|
||||
|
||||
package frc.robot;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
|
||||
|
||||
import com.ctre.phoenix6.Utils;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveRequest;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.DriveRequestType;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import frc.robot.Commands.Desaccumuler;
|
||||
import frc.robot.Commands.LEDactive;
|
||||
import frc.robot.Commands.Lancer;
|
||||
import frc.robot.Commands.LancerModeAuto;
|
||||
import frc.robot.Subsystems.Accumulateur;
|
||||
import frc.robot.Subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.Subsystems.LED;
|
||||
//import frc.robot.Subsystems.Drive;
|
||||
import frc.robot.Subsystems.Lanceur;
|
||||
import frc.robot.Subsystems.Limelight3G;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
//import com.pathplanner.lib.auto.AutoBuilder;
|
||||
//import com.pathplanner.lib.auto.NamedCommands;
|
||||
public class RobotContainer {
|
||||
CommandXboxController manette = new CommandXboxController(0);
|
||||
private double MaxSpeed = TunerConstants.kSpeedAt12VoltsMps; // kSpeedAt12VoltsMps desired top speed
|
||||
private double MaxAngularRate = 1.5 * Math.PI; // 3/4 of a rotation per second max angular velocity
|
||||
|
||||
/* Setting up bindings for necessary control of the swerve drive platform */ // My joystick
|
||||
private final CommandSwerveDrivetrain drivetrain = TunerConstants.DriveTrain; // My drivetrain
|
||||
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.15).withRotationalDeadband(MaxAngularRate * 0.15) // Add a 10% deadband
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // I want field-centric
|
||||
// driving in open loop
|
||||
private final SwerveRequest.PointWheelsAt point = new SwerveRequest.PointWheelsAt();
|
||||
|
||||
private final Telemetry logger = new Telemetry(MaxSpeed);
|
||||
|
||||
|
||||
// private final SendableChooser<Command> autoChooser;
|
||||
Lanceur lanceur= new Lanceur();
|
||||
Accumulateur accumulateur = new Accumulateur();
|
||||
Limelight3G limelight3G = new Limelight3G();
|
||||
LED led = new LED();
|
||||
//Drive drive = new Drive();
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
|
||||
public RobotContainer() {
|
||||
// NamedCommands.registerCommand("lancer", lanceur.lance());
|
||||
//autoChooser = AutoBuilder.buildAutoChooser();
|
||||
dashboard.addCamera("limelight3G", "limelight3G","limelight.local:5800")
|
||||
.withSize(3,4)
|
||||
.withPosition(5,0);
|
||||
dashboard.addCamera("limelight3", "limelight3","limelight.local:5800")
|
||||
.withSize(3,4)
|
||||
.withPosition(2,0);
|
||||
|
||||
|
||||
manette.x().whileTrue(new Lancer(lanceur,accumulateur));
|
||||
//manette.leftBumper().toggleOnTrue(new FollowAprilTag(limelight3G, lanceur));
|
||||
manette.a().whileTrue(new Desaccumuler(accumulateur));
|
||||
manette.y().whileTrue(new LEDactive(accumulateur, led));
|
||||
configureBindings();
|
||||
}
|
||||
private void configureBindings() {
|
||||
drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically
|
||||
drivetrain.applyRequest(() -> drive.withVelocityX(-manette.getLeftY() * MaxSpeed) // Drive forward with
|
||||
// negative Y (forward)
|
||||
.withVelocityY(-manette.getLeftX() * MaxSpeed) // Drive left with negative X (left)
|
||||
.withRotationalRate(-manette.getRightX() * MaxAngularRate) // Drive counterclockwise with negative X (left)
|
||||
));
|
||||
|
||||
private void configureBindings() {}
|
||||
manette.b().whileTrue(drivetrain
|
||||
.applyRequest(() -> point.withModuleDirection(new Rotation2d(-manette.getLeftY(), -manette.getLeftX()))));
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
return Commands.print("No autonomous command configured");
|
||||
// reset the field-centric heading on left bumper press
|
||||
manette.leftBumper().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldRelative()));
|
||||
|
||||
if (Utils.isSimulation()) {
|
||||
drivetrain.seedFieldRelative(new Pose2d(new Translation2d(), Rotation2d.fromDegrees(90)));
|
||||
}
|
||||
drivetrain.registerTelemetry(logger::telemeterize);
|
||||
}
|
||||
}
|
||||
public Command getAutonomousCommand() {
|
||||
return new SequentialCommandGroup(new LancerModeAuto(lanceur, accumulateur));
|
||||
// return autoChooser.getSelected();
|
||||
}
|
||||
}
|
66
src/main/java/frc/robot/Subsystems/Accumulateur.java
Normal file
66
src/main/java/frc/robot/Subsystems/Accumulateur.java
Normal file
@ -0,0 +1,66 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Subsystems;
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
public class Accumulateur extends SubsystemBase {
|
||||
|
||||
/** Creates a new Accumulateur. */
|
||||
public Accumulateur() {dashboard.addBoolean("photocell", this::photocell).withSize(1, 1).withPosition(0, 1);
|
||||
dashboard.addBoolean("photocell2", this::photocell).withSize(1, 1).withPosition(1, 1);
|
||||
}
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
|
||||
private GenericEntry vitesse =
|
||||
dashboard.add("vitesseacc", 0.1)
|
||||
.withSize(1, 1)
|
||||
.withPosition(0, 0)
|
||||
.getEntry();
|
||||
|
||||
final WPI_TalonSRX strap = new WPI_TalonSRX(16);
|
||||
final WPI_TalonSRX rouesbleues = new WPI_TalonSRX(21);
|
||||
final WPI_TalonSRX roueRouge1 = new WPI_TalonSRX(14);
|
||||
final WPI_TalonSRX roueRouge2 = new WPI_TalonSRX(22);
|
||||
final DigitalInput photocell = new DigitalInput(2);
|
||||
final DigitalInput photocell2 = new DigitalInput(5);
|
||||
public void encodeur(){
|
||||
}
|
||||
public boolean photocell(){
|
||||
return !photocell.get();
|
||||
}
|
||||
public boolean photocell2(){
|
||||
return !photocell2.get();
|
||||
}
|
||||
public void desaccumule(double vitesse){
|
||||
strap.set(vitesse);
|
||||
|
||||
}
|
||||
public void masterslave(){
|
||||
roueRouge2.follow(roueRouge1);
|
||||
roueRouge1.setInverted(true);
|
||||
}
|
||||
public void masterslave2(){
|
||||
rouesbleues.follow(strap);
|
||||
rouesbleues.setInverted(true);
|
||||
}
|
||||
public void Petitlanceur(double vitesse){
|
||||
roueRouge1.set(vitesse);
|
||||
}
|
||||
|
||||
public void desaccumule(){
|
||||
desaccumule(vitesse.getDouble(0.9));
|
||||
}
|
||||
public void rouesbleue(double vitesse){
|
||||
rouesbleues.set(vitesse);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
@ -0,0 +1,82 @@
|
||||
package frc.robot.Subsystems;
|
||||
|
||||
import java.util.function.Supplier;
|
||||
|
||||
import com.ctre.phoenix6.Utils;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrain;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj.Notifier;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
/**
|
||||
* Class that extends the Phoenix SwerveDrivetrain class and implements
|
||||
* subsystem so it can be used in command-based projects easily.
|
||||
*/
|
||||
public class CommandSwerveDrivetrain extends SwerveDrivetrain implements Subsystem {
|
||||
private static final double kSimLoopPeriod = 0.005; // 5 ms
|
||||
private Notifier m_simNotifier = null;
|
||||
private double m_lastSimTime;
|
||||
|
||||
/* Blue alliance sees forward as 0 degrees (toward red alliance wall) */
|
||||
private final Rotation2d BlueAlliancePerspectiveRotation = Rotation2d.fromDegrees(0);
|
||||
/* Red alliance sees forward as 180 degrees (toward blue alliance wall) */
|
||||
private final Rotation2d RedAlliancePerspectiveRotation = Rotation2d.fromDegrees(180);
|
||||
/* Keep track if we've ever applied the operator perspective before or not */
|
||||
private boolean hasAppliedOperatorPerspective = false;
|
||||
public CommandSwerveDrivetrain(SwerveDrivetrainConstants driveTrainConstants, double OdometryUpdateFrequency, SwerveModuleConstants... modules) {
|
||||
super(driveTrainConstants, OdometryUpdateFrequency, modules);
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
}
|
||||
}
|
||||
|
||||
public CommandSwerveDrivetrain(SwerveDrivetrainConstants driveTrainConstants, SwerveModuleConstants... modules) {
|
||||
super(driveTrainConstants, modules);
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
}
|
||||
}
|
||||
|
||||
public Command applyRequest(Supplier<SwerveRequest> requestSupplier) {
|
||||
return run(() -> this.setControl(requestSupplier.get()));
|
||||
}
|
||||
|
||||
private void startSimThread() {
|
||||
m_lastSimTime = Utils.getCurrentTimeSeconds();
|
||||
|
||||
/* Run simulation at a faster rate so PID gains behave more reasonably */
|
||||
m_simNotifier = new Notifier(() -> {
|
||||
final double currentTime = Utils.getCurrentTimeSeconds();
|
||||
double deltaTime = currentTime - m_lastSimTime;
|
||||
m_lastSimTime = currentTime;
|
||||
|
||||
/* use the measured time delta, get battery voltage from WPILib */
|
||||
updateSimState(deltaTime, RobotController.getBatteryVoltage());
|
||||
});
|
||||
m_simNotifier.startPeriodic(kSimLoopPeriod);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
/* Periodically try to apply the operator perspective */
|
||||
/* If we haven't applied the operator perspective before, then we should apply it regardless of DS state */
|
||||
/* This allows us to correct the perspective in case the robot code restarts mid-match */
|
||||
/* Otherwise, only check and apply the operator perspective if the DS is disabled */
|
||||
/* This ensures driving behavior doesn't change until an explicit disable event occurs during testing*/
|
||||
if (!hasAppliedOperatorPerspective || DriverStation.isDisabled()) {
|
||||
DriverStation.getAlliance().ifPresent((allianceColor) -> {
|
||||
this.setOperatorPerspectiveForward(
|
||||
allianceColor == Alliance.Red ? RedAlliancePerspectiveRotation
|
||||
: BlueAlliancePerspectiveRotation);
|
||||
hasAppliedOperatorPerspective = true;
|
||||
});
|
||||
}
|
||||
}
|
||||
}
|
48
src/main/java/frc/robot/Subsystems/Drive.java
Normal file
48
src/main/java/frc/robot/Subsystems/Drive.java
Normal file
@ -0,0 +1,48 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
/*package frc.robot.Subsystems;
|
||||
import java.io.File;
|
||||
import java.io.IOException;
|
||||
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.wpilibj.Filesystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import swervelib.SwerveDrive;
|
||||
import swervelib.parser.SwerveParser;
|
||||
|
||||
public class Drive extends SubsystemBase {
|
||||
|
||||
SwerveDrive swerveDrive;
|
||||
|
||||
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
|
||||
|
||||
Pigeon2 Gyro = new Pigeon2(0);
|
||||
|
||||
public void drive(double x, double y, double zRotation){
|
||||
swerveDrive.drive(new Translation2d(x*5, y*5), zRotation*4, true, false);
|
||||
}
|
||||
|
||||
public Drive() {
|
||||
try {
|
||||
this.swerveDrive = new SwerveParser(swerveJsonDirectory).createSwerveDrive(5);
|
||||
swerveDrive.setHeadingCorrection(true);
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
public void restgyroscope(){
|
||||
Gyro.reset();
|
||||
}
|
||||
public SwerveModulePosition[] distance(){
|
||||
return swerveDrive.getModulePositions();
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}*/
|
22
src/main/java/frc/robot/Subsystems/LED.java
Normal file
22
src/main/java/frc/robot/Subsystems/LED.java
Normal file
@ -0,0 +1,22 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Subsystems;
|
||||
|
||||
import com.ctre.phoenix.led.CANdle;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class LED extends SubsystemBase {
|
||||
/** Creates a new LED. */
|
||||
public LED() {}
|
||||
CANdle led = new CANdle(1);
|
||||
public void led(int R, int G, int B){
|
||||
led.setLEDs(R, G, B);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
@ -6,29 +6,84 @@ package frc.robot.Subsystems;
|
||||
|
||||
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
|
||||
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.networktables.GenericEntry;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
|
||||
public class Lanceur extends SubsystemBase {
|
||||
/** Creates a new Lanceur. */
|
||||
public Lanceur() {}
|
||||
public Lanceur() {
|
||||
dashboard.addBoolean("limitswitch1", this::limitswitch1)
|
||||
.withSize(0,0).withPosition(1,2);
|
||||
dashboard.addBoolean("limitswitch2", this::limitswitch2)
|
||||
.withSize(0,0).withPosition(0,3);
|
||||
dashboard.addDouble("rottourel", this::distancetourel)
|
||||
.withSize(0,0).withPosition(1, 0);
|
||||
}
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
|
||||
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(0);
|
||||
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(1);
|
||||
final CANSparkMax tourel = new CANSparkMax(2, MotorType.kBrushed);
|
||||
final WPI_TalonSRX lanceur1 = new WPI_TalonSRX(17);
|
||||
final WPI_TalonSRX lanceur2 = new WPI_TalonSRX(15);
|
||||
final CANSparkMax tourelle = new CANSparkMax(23, MotorType.kBrushless);
|
||||
final DigitalInput limitswitch1 = new DigitalInput(4);
|
||||
final DigitalInput limitswitch2 = new DigitalInput(3);
|
||||
private GenericEntry vitesse =
|
||||
dashboard.add("vitesselanceur", 0.5)
|
||||
.withSize(0,0)
|
||||
.withPosition(0, 2)
|
||||
.getEntry();
|
||||
|
||||
public void encodeur(double distance){
|
||||
lanceur1.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
|
||||
lanceur2.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
|
||||
lanceur1.setStatusFramePeriod(StatusFrameEnhanced.Status_2_Feedback0, 1);
|
||||
}
|
||||
public void touchagedelimitswitch1(double distance){
|
||||
tourelle.getEncoder().setPosition(distance);
|
||||
}
|
||||
public void touchagedelimitswitch2(double distance){
|
||||
tourelle.getEncoder().setPosition(distance);
|
||||
}
|
||||
public void masterslave(){
|
||||
lanceur2.follow(lanceur1);
|
||||
lanceur1.setInverted(true);
|
||||
}
|
||||
public void lance(double vitesse){
|
||||
lanceur1.set(vitesse);
|
||||
lanceur2.set(-vitesse);
|
||||
}
|
||||
public void tourelRotation(double vitesse){
|
||||
tourel.set(vitesse);
|
||||
public void lance(){
|
||||
lance(vitesse.getDouble(0.9));
|
||||
}
|
||||
public void setPID(double p, double i, int d) {
|
||||
public void tourelRotation(double x, double y, double rotation){
|
||||
tourelle.set(rotation);
|
||||
}
|
||||
|
||||
public double vitessetourel(){
|
||||
return (tourelle.getEncoder().getVelocity());
|
||||
}
|
||||
public double distancetourel(){
|
||||
return (tourelle.getEncoder().getPosition());
|
||||
}
|
||||
public void PIDlanceur(double p, double i, double d) {
|
||||
lanceur1.config_kP(0, p);
|
||||
lanceur1.config_kI(0, i);
|
||||
lanceur1.config_kD(0, d);
|
||||
}
|
||||
public boolean limitswitch1(){
|
||||
return !limitswitch1.get();
|
||||
}
|
||||
public boolean limitswitch2(){
|
||||
return !limitswitch2.get();
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called oncehttps://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-latest.json per scheduler run
|
||||
|
53
src/main/java/frc/robot/Subsystems/Limelight3G.java
Normal file
53
src/main/java/frc/robot/Subsystems/Limelight3G.java
Normal file
@ -0,0 +1,53 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package frc.robot.Subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.net.PortForwarder;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
|
||||
public class Limelight3G extends SubsystemBase {
|
||||
ShuffleboardTab dashboard = Shuffleboard.getTab("dashboard");
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
NetworkTableEntry ty = table.getEntry("ty");
|
||||
NetworkTableEntry pipeline = table.getEntry("pipeline");
|
||||
NetworkTableEntry tv = table.getEntry("tv");
|
||||
NetworkTableEntry camMode = table.getEntry("camMode");
|
||||
NetworkTableEntry tid = table.getEntry("tid");
|
||||
|
||||
/** Creates a new Limelight. */
|
||||
public Limelight3G() {
|
||||
dashboard.addDouble("tv", this::getv).withSize(0, 0).withPosition(1,3);
|
||||
for (int port = 5800; port <= 5807; port++) {
|
||||
PortForwarder.add(port, "limelight.local", port);
|
||||
}}
|
||||
public double getx(){
|
||||
return tx.getDouble(0);
|
||||
}
|
||||
public double gety(){
|
||||
return ty.getDouble(0);
|
||||
}
|
||||
public double getv(){
|
||||
return tv.getDouble(0);
|
||||
}
|
||||
public void setpipeline(){
|
||||
pipeline.setNumber(0);
|
||||
}
|
||||
public void setcamMode(){
|
||||
camMode.setNumber(0);
|
||||
}
|
||||
public double getTid(){
|
||||
return tid.getDouble(0);
|
||||
}
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
}
|
||||
}
|
110
src/main/java/frc/robot/Telemetry.java
Normal file
110
src/main/java/frc/robot/Telemetry.java
Normal file
@ -0,0 +1,110 @@
|
||||
package frc.robot;
|
||||
|
||||
import com.ctre.phoenix6.Utils;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrain.SwerveDriveState;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.networktables.DoubleArrayPublisher;
|
||||
import edu.wpi.first.networktables.DoublePublisher;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.networktables.StringPublisher;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj.util.Color;
|
||||
import edu.wpi.first.wpilibj.util.Color8Bit;
|
||||
|
||||
public class Telemetry {
|
||||
private final double MaxSpeed;
|
||||
|
||||
/**
|
||||
* Construct a telemetry object, with the specified max speed of the robot
|
||||
*
|
||||
* @param maxSpeed Maximum speed in meters per second
|
||||
*/
|
||||
public Telemetry(double maxSpeed) {
|
||||
MaxSpeed = maxSpeed;
|
||||
}
|
||||
|
||||
/* What to publish over networktables for telemetry */
|
||||
private final NetworkTableInstance inst = NetworkTableInstance.getDefault();
|
||||
|
||||
/* Robot pose for field positioning */
|
||||
private final NetworkTable table = inst.getTable("Pose");
|
||||
private final DoubleArrayPublisher fieldPub = table.getDoubleArrayTopic("robotPose").publish();
|
||||
private final StringPublisher fieldTypePub = table.getStringTopic(".type").publish();
|
||||
|
||||
/* Robot speeds for general checking */
|
||||
private final NetworkTable driveStats = inst.getTable("Drive");
|
||||
private final DoublePublisher velocityX = driveStats.getDoubleTopic("Velocity X").publish();
|
||||
private final DoublePublisher velocityY = driveStats.getDoubleTopic("Velocity Y").publish();
|
||||
private final DoublePublisher speed = driveStats.getDoubleTopic("Speed").publish();
|
||||
private final DoublePublisher odomPeriod = driveStats.getDoubleTopic("Odometry Period").publish();
|
||||
|
||||
/* Keep a reference of the last pose to calculate the speeds */
|
||||
private Pose2d m_lastPose = new Pose2d();
|
||||
private double lastTime = Utils.getCurrentTimeSeconds();
|
||||
|
||||
/* Mechanisms to represent the swerve module states */
|
||||
private final Mechanism2d[] m_moduleMechanisms = new Mechanism2d[] {
|
||||
new Mechanism2d(1, 1),
|
||||
new Mechanism2d(1, 1),
|
||||
new Mechanism2d(1, 1),
|
||||
new Mechanism2d(1, 1),
|
||||
};
|
||||
/* A direction and length changing ligament for speed representation */
|
||||
private final MechanismLigament2d[] m_moduleSpeeds = new MechanismLigament2d[] {
|
||||
m_moduleMechanisms[0].getRoot("RootSpeed", 0.5, 0.5).append(new MechanismLigament2d("Speed", 0.5, 0)),
|
||||
m_moduleMechanisms[1].getRoot("RootSpeed", 0.5, 0.5).append(new MechanismLigament2d("Speed", 0.5, 0)),
|
||||
m_moduleMechanisms[2].getRoot("RootSpeed", 0.5, 0.5).append(new MechanismLigament2d("Speed", 0.5, 0)),
|
||||
m_moduleMechanisms[3].getRoot("RootSpeed", 0.5, 0.5).append(new MechanismLigament2d("Speed", 0.5, 0)),
|
||||
};
|
||||
/* A direction changing and length constant ligament for module direction */
|
||||
private final MechanismLigament2d[] m_moduleDirections = new MechanismLigament2d[] {
|
||||
m_moduleMechanisms[0].getRoot("RootDirection", 0.5, 0.5)
|
||||
.append(new MechanismLigament2d("Direction", 0.1, 0, 0, new Color8Bit(Color.kWhite))),
|
||||
m_moduleMechanisms[1].getRoot("RootDirection", 0.5, 0.5)
|
||||
.append(new MechanismLigament2d("Direction", 0.1, 0, 0, new Color8Bit(Color.kWhite))),
|
||||
m_moduleMechanisms[2].getRoot("RootDirection", 0.5, 0.5)
|
||||
.append(new MechanismLigament2d("Direction", 0.1, 0, 0, new Color8Bit(Color.kWhite))),
|
||||
m_moduleMechanisms[3].getRoot("RootDirection", 0.5, 0.5)
|
||||
.append(new MechanismLigament2d("Direction", 0.1, 0, 0, new Color8Bit(Color.kWhite))),
|
||||
};
|
||||
|
||||
/* Accept the swerve drive state and telemeterize it to smartdashboard */
|
||||
public void telemeterize(SwerveDriveState state) {
|
||||
/* Telemeterize the pose */
|
||||
Pose2d pose = state.Pose;
|
||||
fieldTypePub.set("Field2d");
|
||||
fieldPub.set(new double[] {
|
||||
pose.getX(),
|
||||
pose.getY(),
|
||||
pose.getRotation().getDegrees()
|
||||
});
|
||||
|
||||
/* Telemeterize the robot's general speeds */
|
||||
double currentTime = Utils.getCurrentTimeSeconds();
|
||||
double diffTime = currentTime - lastTime;
|
||||
lastTime = currentTime;
|
||||
Translation2d distanceDiff = pose.minus(m_lastPose).getTranslation();
|
||||
m_lastPose = pose;
|
||||
|
||||
Translation2d velocities = distanceDiff.div(diffTime);
|
||||
|
||||
speed.set(velocities.getNorm());
|
||||
velocityX.set(velocities.getX());
|
||||
velocityY.set(velocities.getY());
|
||||
odomPeriod.set(state.OdometryPeriod);
|
||||
|
||||
/* Telemeterize the module's states */
|
||||
for (int i = 0; i < 4; ++i) {
|
||||
m_moduleSpeeds[i].setAngle(state.ModuleStates[i].angle);
|
||||
m_moduleDirections[i].setAngle(state.ModuleStates[i].angle);
|
||||
m_moduleSpeeds[i].setLength(state.ModuleStates[i].speedMetersPerSecond / (2 * MaxSpeed));
|
||||
|
||||
SmartDashboard.putData("Module " + i, m_moduleMechanisms[i]);
|
||||
}
|
||||
}
|
||||
}
|
167
src/main/java/frc/robot/generated/TunerConstants.java
Normal file
167
src/main/java/frc/robot/generated/TunerConstants.java
Normal file
@ -0,0 +1,167 @@
|
||||
package frc.robot.generated;
|
||||
|
||||
import com.ctre.phoenix6.configs.CANcoderConfiguration;
|
||||
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
|
||||
import com.ctre.phoenix6.configs.Pigeon2Configuration;
|
||||
import com.ctre.phoenix6.configs.Slot0Configs;
|
||||
import com.ctre.phoenix6.configs.TalonFXConfiguration;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstantsFactory;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.ClosedLoopOutputType;
|
||||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants.SteerFeedbackType;
|
||||
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import frc.robot.Subsystems.CommandSwerveDrivetrain;
|
||||
|
||||
// Generated by the Tuner X Swerve Project Generator
|
||||
// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html
|
||||
public class TunerConstants {
|
||||
// Both sets of gains need to be tuned to your individual robot.
|
||||
|
||||
// The steer motor uses any SwerveModule.SteerRequestType control request with the
|
||||
// output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
|
||||
private static final Slot0Configs steerGains = new Slot0Configs()
|
||||
.withKP(100).withKI(0).withKD(0.2)
|
||||
.withKS(0).withKV(1.5).withKA(0);
|
||||
// When using closed-loop control, the drive motor uses the control
|
||||
// output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
|
||||
private static final Slot0Configs driveGains = new Slot0Configs()
|
||||
.withKP(3).withKI(0).withKD(0)
|
||||
.withKS(0).withKV(0).withKA(0);
|
||||
|
||||
// The closed-loop output type to use for the steer motors;
|
||||
// This affects the PID/FF gains for the steer motors
|
||||
private static final ClosedLoopOutputType steerClosedLoopOutput = ClosedLoopOutputType.Voltage;
|
||||
// The closed-loop output type to use for the drive motors;
|
||||
// This affects the PID/FF gains for the drive motors
|
||||
private static final ClosedLoopOutputType driveClosedLoopOutput = ClosedLoopOutputType.Voltage;
|
||||
|
||||
// The stator current at which the wheels start to slip;
|
||||
// This needs to be tuned to your individual robot
|
||||
private static final double kSlipCurrentA = 150.0;
|
||||
|
||||
// Initial configs for the drive and steer motors and the CANcoder; these cannot be null.
|
||||
// Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
|
||||
private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration();
|
||||
private static final TalonFXConfiguration steerInitialConfigs = new TalonFXConfiguration()
|
||||
.withCurrentLimits(
|
||||
new CurrentLimitsConfigs()
|
||||
// Swerve azimuth does not require much torque output, so we can set a relatively low
|
||||
// stator current limit to help avoid brownouts without impacting performance.
|
||||
.withStatorCurrentLimit(60)
|
||||
.withStatorCurrentLimitEnable(true)
|
||||
);
|
||||
private static final CANcoderConfiguration cancoderInitialConfigs = new CANcoderConfiguration();
|
||||
// Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
|
||||
private static final Pigeon2Configuration pigeonConfigs = null;
|
||||
|
||||
// Theoretical free speed (m/s) at 12v applied output;
|
||||
// This needs to be tuned to your individual robot
|
||||
public static final double kSpeedAt12VoltsMps = 5.21;
|
||||
|
||||
// Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
|
||||
// This may need to be tuned to your individual robot
|
||||
private static final double kCoupleRatio = 3.5714285714285716;
|
||||
|
||||
private static final double kDriveGearRatio = 6.122448979591837;
|
||||
private static final double kSteerGearRatio = 21.428571428571427;
|
||||
private static final double kWheelRadiusInches = 2;
|
||||
|
||||
private static final boolean kInvertLeftSide = false;
|
||||
private static final boolean kInvertRightSide = true;
|
||||
|
||||
private static final String kCANbusName = "swerve";
|
||||
private static final int kPigeonId = 13;
|
||||
|
||||
|
||||
// These are only used for simulation
|
||||
private static final double kSteerInertia = 0.00001;
|
||||
private static final double kDriveInertia = 0.001;
|
||||
// Simulated voltage necessary to overcome friction
|
||||
private static final double kSteerFrictionVoltage = 0.25;
|
||||
private static final double kDriveFrictionVoltage = 0.25;
|
||||
|
||||
private static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
|
||||
.withCANbusName(kCANbusName)
|
||||
.withPigeon2Id(kPigeonId)
|
||||
.withPigeon2Configs(pigeonConfigs);
|
||||
|
||||
private static final SwerveModuleConstantsFactory ConstantCreator = new SwerveModuleConstantsFactory()
|
||||
.withDriveMotorGearRatio(kDriveGearRatio)
|
||||
.withSteerMotorGearRatio(kSteerGearRatio)
|
||||
.withWheelRadius(kWheelRadiusInches)
|
||||
.withSlipCurrent(kSlipCurrentA)
|
||||
.withSteerMotorGains(steerGains)
|
||||
.withDriveMotorGains(driveGains)
|
||||
.withSteerMotorClosedLoopOutput(steerClosedLoopOutput)
|
||||
.withDriveMotorClosedLoopOutput(driveClosedLoopOutput)
|
||||
.withSpeedAt12VoltsMps(kSpeedAt12VoltsMps)
|
||||
.withSteerInertia(kSteerInertia)
|
||||
.withDriveInertia(kDriveInertia)
|
||||
.withSteerFrictionVoltage(kSteerFrictionVoltage)
|
||||
.withDriveFrictionVoltage(kDriveFrictionVoltage)
|
||||
.withFeedbackSource(SteerFeedbackType.FusedCANcoder)
|
||||
.withCouplingGearRatio(kCoupleRatio)
|
||||
.withDriveMotorInitialConfigs(driveInitialConfigs)
|
||||
.withSteerMotorInitialConfigs(steerInitialConfigs)
|
||||
.withCANcoderInitialConfigs(cancoderInitialConfigs);
|
||||
|
||||
|
||||
// Front Left
|
||||
private static final int kFrontLeftDriveMotorId = 2;
|
||||
private static final int kFrontLeftSteerMotorId = 6;
|
||||
private static final int kFrontLeftEncoderId = 9;
|
||||
private static final double kFrontLeftEncoderOffset = -0.046142578125;
|
||||
private static final boolean kFrontLeftSteerInvert = true;
|
||||
|
||||
private static final double kFrontLeftXPosInches = 11.625;
|
||||
private static final double kFrontLeftYPosInches = 11.625;
|
||||
|
||||
// Front Right
|
||||
private static final int kFrontRightDriveMotorId = 4;
|
||||
private static final int kFrontRightSteerMotorId = 5;
|
||||
private static final int kFrontRightEncoderId = 12;
|
||||
private static final double kFrontRightEncoderOffset = -0.116455078125;
|
||||
private static final boolean kFrontRightSteerInvert = true;
|
||||
|
||||
private static final double kFrontRightXPosInches = 11.625;
|
||||
private static final double kFrontRightYPosInches = -11.625;
|
||||
|
||||
// Back Left
|
||||
private static final int kBackLeftDriveMotorId = 3;
|
||||
private static final int kBackLeftSteerMotorId = 7;
|
||||
private static final int kBackLeftEncoderId = 10;
|
||||
private static final double kBackLeftEncoderOffset = -0.046630859375;
|
||||
private static final boolean kBackLeftSteerInvert = true;
|
||||
|
||||
private static final double kBackLeftXPosInches = -11.625;
|
||||
private static final double kBackLeftYPosInches = 11.625;
|
||||
|
||||
// Back Right
|
||||
private static final int kBackRightDriveMotorId = 18;
|
||||
private static final int kBackRightSteerMotorId = 8;
|
||||
private static final int kBackRightEncoderId = 11;
|
||||
private static final double kBackRightEncoderOffset = -0.016357421875;
|
||||
private static final boolean kBackRightSteerInvert = true;
|
||||
|
||||
private static final double kBackRightXPosInches = -11.625;
|
||||
private static final double kBackRightYPosInches = -11.625;
|
||||
|
||||
|
||||
private static final SwerveModuleConstants FrontLeft = ConstantCreator.createModuleConstants(
|
||||
kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset, Units.inchesToMeters(kFrontLeftXPosInches), Units.inchesToMeters(kFrontLeftYPosInches), kInvertLeftSide)
|
||||
.withSteerMotorInverted(kFrontLeftSteerInvert);
|
||||
private static final SwerveModuleConstants FrontRight = ConstantCreator.createModuleConstants(
|
||||
kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset, Units.inchesToMeters(kFrontRightXPosInches), Units.inchesToMeters(kFrontRightYPosInches), kInvertRightSide)
|
||||
.withSteerMotorInverted(kFrontRightSteerInvert);
|
||||
private static final SwerveModuleConstants BackLeft = ConstantCreator.createModuleConstants(
|
||||
kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset, Units.inchesToMeters(kBackLeftXPosInches), Units.inchesToMeters(kBackLeftYPosInches), kInvertLeftSide)
|
||||
.withSteerMotorInverted(kBackLeftSteerInvert);
|
||||
private static final SwerveModuleConstants BackRight = ConstantCreator.createModuleConstants(
|
||||
kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset, Units.inchesToMeters(kBackRightXPosInches), Units.inchesToMeters(kBackRightYPosInches), kInvertRightSide)
|
||||
.withSteerMotorInverted(kBackRightSteerInvert);
|
||||
|
||||
public static final CommandSwerveDrivetrain DriveTrain = new CommandSwerveDrivetrain(DrivetrainConstants, FrontLeft,
|
||||
FrontRight, BackLeft, BackRight);
|
||||
}
|
38
vendordeps/PathplannerLib.json
Normal file
38
vendordeps/PathplannerLib.json
Normal file
@ -0,0 +1,38 @@
|
||||
{
|
||||
"fileName": "PathplannerLib.json",
|
||||
"name": "PathplannerLib",
|
||||
"version": "2024.2.8",
|
||||
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
|
||||
"frcYear": "2024",
|
||||
"mavenUrls": [
|
||||
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
|
||||
],
|
||||
"jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
|
||||
"javaDependencies": [
|
||||
{
|
||||
"groupId": "com.pathplanner.lib",
|
||||
"artifactId": "PathplannerLib-java",
|
||||
"version": "2024.2.8"
|
||||
}
|
||||
],
|
||||
"jniDependencies": [],
|
||||
"cppDependencies": [
|
||||
{
|
||||
"groupId": "com.pathplanner.lib",
|
||||
"artifactId": "PathplannerLib-cpp",
|
||||
"version": "2024.2.8",
|
||||
"libName": "PathplannerLib",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"binaryPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxx86-64",
|
||||
"osxuniversal",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"linuxarm64"
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
Loading…
x
Reference in New Issue
Block a user