Skip to content

Commit c7e25c9

Browse files
authored
Merge pull request #1 from MilwaukeeCyberCheese/feat/swerve
chore: very badly written commit with the vast majority of the conten…
2 parents 6874545 + 858a948 commit c7e25c9

23 files changed

Lines changed: 2190 additions & 140 deletions

simgui-ds.json

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -88,5 +88,10 @@
8888
"buttonCount": 0,
8989
"povCount": 0
9090
}
91+
],
92+
"robotJoysticks": [
93+
{
94+
"guid": "Keyboard0"
95+
}
9196
]
9297
}
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
{
2+
"angleJoystickRadiusDeadband": 0.5,
3+
"heading": {
4+
"p": 0.4,
5+
"i": 0,
6+
"d": 0.01
7+
}
8+
}
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
{
2+
"drive": {
3+
"type": "sparkmax_neo",
4+
"id": 5,
5+
"canbus": null
6+
},
7+
"angle": {
8+
"type": "sparkmax_neo550",
9+
"id": 6,
10+
"canbus": null
11+
},
12+
"encoder": {
13+
"type": "attached",
14+
"id": 0,
15+
"canbus": null
16+
},
17+
"inverted": {
18+
"drive": false,
19+
"angle": false
20+
},
21+
"absoluteEncoderInverted": true,
22+
"absoluteEncoderOffset": 0,
23+
"location": {
24+
"front": -14,
25+
"left": 14
26+
}
27+
}
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
{
2+
"drive": {
3+
"type": "sparkmax_neo",
4+
"id": 7,
5+
"canbus": null
6+
},
7+
"angle": {
8+
"type": "sparkmax_neo550",
9+
"id": 8,
10+
"canbus": null
11+
},
12+
"encoder": {
13+
"type": "attached",
14+
"id": 0,
15+
"canbus": null
16+
},
17+
"inverted": {
18+
"drive": true,
19+
"angle": false
20+
},
21+
"absoluteEncoderInverted": true,
22+
"absoluteEncoderOffset": 100,
23+
"location": {
24+
"front": -14,
25+
"left": -14
26+
}
27+
}
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
{
2+
"drive": {
3+
"type": "sparkmax_neo",
4+
"id": 1,
5+
"canbus": null
6+
},
7+
"angle": {
8+
"type": "sparkmax_neo550",
9+
"id": 2,
10+
"canbus": null
11+
},
12+
"encoder": {
13+
"type": "attached",
14+
"id": 0,
15+
"canbus": null
16+
},
17+
"inverted": {
18+
"drive": true,
19+
"angle": false
20+
},
21+
"absoluteEncoderInverted": true,
22+
"absoluteEncoderOffset": -90,
23+
"location": {
24+
"front": 14,
25+
"left": 14
26+
}
27+
}
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
{
2+
"drive": {
3+
"type": "sparkmax_neo",
4+
"id": 11,
5+
"canbus": null
6+
},
7+
"angle": {
8+
"type": "sparkmax_neo550",
9+
"id": 12,
10+
"canbus": null
11+
},
12+
"encoder": {
13+
"type": "attached",
14+
"id": 0,
15+
"canbus": null
16+
},
17+
"inverted": {
18+
"drive": false,
19+
"angle": false
20+
},
21+
"absoluteEncoderInverted": true,
22+
"absoluteEncoderOffset": 180,
23+
"location": {
24+
"front": 14,
25+
"left": -14
26+
}
27+
}
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
{
2+
"conversionFactors": {
3+
"angle": {
4+
"gearRatio": 46.42,
5+
"factor": 0
6+
},
7+
"drive": {
8+
"gearRatio": 5.50,
9+
"diameter": 3,
10+
"factor": 0
11+
}
12+
},
13+
"currentLimit": {
14+
"drive": 60,
15+
"angle": 20
16+
},
17+
"rampRate": {
18+
"drive": 0.25,
19+
"angle": 0.20
20+
},
21+
"optimalVoltage": 12,
22+
"wheelGripCoefficientOfFriction": 1.19
23+
}
Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
{
2+
"drive": {
3+
"p": 0.00005,
4+
"i": 0.000001,
5+
"d": 0,
6+
"f": 0,
7+
"iz": 0
8+
},
9+
"angle": {
10+
"p": 0.0098,
11+
"i": 0,
12+
"d": 0,
13+
"f": 0,
14+
"iz": 0
15+
}
16+
}
Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
{
2+
"imu": {
3+
"type": "navx_usb",
4+
"id": 0,
5+
"canbus": null
6+
},
7+
"invertedIMU": false,
8+
"modules": [
9+
"frontleft.json",
10+
"frontright.json",
11+
"backleft.json",
12+
"backright.json"
13+
]
14+
}

src/main/java/frc/robot/Constants.java

Lines changed: 33 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,13 @@
44

55
package frc.robot;
66

7+
import java.io.File;
8+
9+
import edu.wpi.first.math.geometry.Translation3d;
10+
import edu.wpi.first.math.util.Units;
11+
import edu.wpi.first.wpilibj.Filesystem;
12+
import swervelib.math.Matter;
13+
714
/**
815
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
916
* constants. This class should not be used for any other purpose. All constants should be declared
@@ -13,7 +20,32 @@
1320
* constants are needed, to reduce verbosity.
1421
*/
1522
public final class Constants {
16-
public static class OperatorConstants {
23+
public static final double ROBOT_MASS = (148 - 20.3) * 0.453592; // 32lbs * kg per pound
24+
public static final Matter CHASSIS = new Matter(new Translation3d(0, 0, Units.inchesToMeters(8)), ROBOT_MASS);
25+
public static final double LOOP_TIME = 0.13; //s, 20ms + 110ms sprk max velocity lag
26+
public static final double MAX_SPEED = Units.feetToMeters(14.5);
27+
28+
public static final class DrivebaseConstants
29+
{
30+
31+
// Hold time on motor brakes when disabled
32+
public static final double WHEEL_LOCK_TIME = 10; // seconds
33+
}
34+
35+
36+
public static class SwerveConstants {
37+
public static final double kMaximumSpeed = Units.feetToMeters(4.5);
38+
public static final File kSwerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
39+
}
40+
41+
public static class OperatorConstants
42+
{
1743
public static final int kDriverControllerPort = 0;
44+
45+
// Joystick Deadband
46+
public static final double DEADBAND = 0.1;
47+
public static final double LEFT_Y_DEADBAND = 0.1;
48+
public static final double RIGHT_X_DEADBAND = 0.1;
49+
public static final double TURN_CONSTANT = 6;
1850
}
1951
}

0 commit comments

Comments
 (0)