Skip to content
Open
8 changes: 8 additions & 0 deletions src/main/deploy/YAGSL/real/controllerproperties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
{
"angleJoystickRadiusDeadband": 0.5,
"heading": {
"p": 0.4,
"i": 0,
"d": 0.01
}
}
27 changes: 27 additions & 0 deletions src/main/deploy/YAGSL/real/modules/backleft.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
{
"location": {
"front": -9,
"left": 9
},
"absoluteEncoderOffset": 0,
"drive": {
"type": "sparkmax_neo",
"id": 58,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 28,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 0,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

0 is not a good CAN value - for now use the same ids as the testbed until we get the real ones.

"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderInverted": false
}
27 changes: 27 additions & 0 deletions src/main/deploy/YAGSL/real/modules/backright.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
{
"location": {
"front": -9,
"left": -9
},
"absoluteEncoderOffset": 0,
"drive": {
"type": "sparkmax_neo",
"id": 59,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 29,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 0,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same

"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderInverted": false
}
27 changes: 27 additions & 0 deletions src/main/deploy/YAGSL/real/modules/frontleft.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
{
"location": {
"front": 9,
"left": 9
},
"absoluteEncoderOffset": 0,
"drive": {
"type": "sparkmax_neo",
"id": 57,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 27,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 0,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same

"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderInverted": false
}
27 changes: 27 additions & 0 deletions src/main/deploy/YAGSL/real/modules/frontright.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
{
"location": {
"front": 9,
"left": -9
},
"absoluteEncoderOffset": 0,
"drive": {
"type": "sparkmax_neo",
"id": 60,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 30,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 0,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same

"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderInverted": false
}
24 changes: 24 additions & 0 deletions src/main/deploy/YAGSL/real/modules/physicalproperties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
{
"optimalVoltage": 12,
"robotMass": 137,
"wheelGripCoefficientOfFriction": 1.19,
"currentLimit": {
"drive": 40,
"angle": 20
},
"conversionFactors": {
"angle": {
"gearRatio": 12.8,
"factor": 0
},
"drive": {
"diameter": 4,
"gearRatio": 6.75,
"factor": 0
}
},
"rampRate": {
"drive": 0.25,
"angle": 0.25
}
}
16 changes: 16 additions & 0 deletions src/main/deploy/YAGSL/real/modules/pidfproperties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
{
"drive": {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Where did these numbers come from?

"p": 0.0020645,
"i": 0,
"d": 0,
"f": 0,
"iz": 0
},
"angle": {
"p": 0.0020645,
"i": 0,
"d": 0,
"f": 0,
"iz": 0
}
}
14 changes: 14 additions & 0 deletions src/main/deploy/YAGSL/real/swervedrive.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
{
"imu": {
"type": "navx_spi",
"id": 0,
"canbus": null
},
"invertedIMU": false,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ public RobotContainer() {
SwerveIMU swerveIMU = new ThreadedGyroSwerveIMU(threadedGyro);

drivebase = !Constants.TESTBED ? new SwerveSubsystem(
new File(Filesystem.getDeployDirectory(), "YAGSL"), swerveIMU) : null;
new File(Filesystem.getDeployDirectory(), "YAGSL/" + Constants.JSON_DIRECTORY), swerveIMU) : null;
apriltagSubsystem = !Constants.TESTBED ? new ApriltagSubsystem(ApriltagSubsystem.createRealIo(), drivebase) : null;
}
case REPLAY -> {
Expand All @@ -151,7 +151,7 @@ public RobotContainer() {
intakeDeployer = new IntakeDeployerSubsystem(IntakeDeployerSubsystem.createMockIo());
// No GyroSubsystem in REPLAY for now
// create the drive subsystem with null gyro (use default json)
drivebase = !Constants.TESTBED ? new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "YAGSL"), null) : null;
drivebase = !Constants.TESTBED ? new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "YAGSL/" + Constants.JSON_DIRECTORY), null) : null;
apriltagSubsystem = !Constants.TESTBED ? new ApriltagSubsystem(ApriltagSubsystem.createMockIo(), drivebase) : null;
}
case SIM -> {
Expand All @@ -170,7 +170,7 @@ public RobotContainer() {
intakeDeployer = new IntakeDeployerSubsystem(
IntakeDeployerSubsystem.createSimIo(robotVisualizer));// No GyroSubsystem in REPLAY for now
// create the drive subsystem with null gyro (use default json)
drivebase = !Constants.TESTBED ? new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "YAGSL"), null) : null;
drivebase = !Constants.TESTBED ? new SwerveSubsystem(new File(Filesystem.getDeployDirectory(), "YAGSL/" + Constants.JSON_DIRECTORY), null) : null;
apriltagSubsystem = !Constants.TESTBED ? new ApriltagSubsystem(ApriltagSubsystem.createSimIo(), drivebase) : null;
}

Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/constants/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,5 +14,10 @@
* constants are needed, to reduce verbosity.
*/

public class Constants extends Constants2026 {}

// To use the other constatns files, change which line is not commented out here.
// Then discard changes to this file before committing.
public class Constants extends ConstantsPushbot2026 {
// public class Constants extends ConstantsReal2026 {
// public class Constants extends ConstantsTestbed2026 {
}
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.robot.constants;

public class Constants2026 extends GameConstants {
public class ConstantsPushbot2026 extends GameConstants {

// Constants2026 is only for CANIDs and nothing else, everything else goes into GameConstants.
// ConstantsPushbot2026 is only for CANIDs and nothing else, everything else goes into GameConstants.

public static final int ROLLER_MOTOR_ID = 10; // we dont have a roller this year i thought?
public static final int TILT_MOTOR_ID = 20; // we dont have a tilt this year i thought?
Expand Down Expand Up @@ -33,6 +33,6 @@ public class Constants2026 extends GameConstants {
public static final int SERVER_SOCKET_ATTEMPT_DELAY = 100;
public static final int TCP_SERVER_PORT = 5806;


public static final String JSON_DIRECTORY = "pushbot";
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
public static final String JSON_DIRECTORY = "pushbot";
public static final String SWERVE_JSON_DIRECTORY = "pushbot";


}
20 changes: 20 additions & 0 deletions src/main/java/frc/robot/constants/ConstantsReal2026.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
package frc.robot.constants;

public class ConstantsReal2026 extends ConstantsPushbot2026 {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It doesn't feel right to have real extend pushbot. It would be better the other way around.


public static final String JSON_DIRECTORY = "real";
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
public static final String JSON_DIRECTORY = "real";
public static final String SWERVE_JSON_DIRECTORY = "real";


// shooter related
public static final int SHOOTER_MOTOR_ID = 53;
public static final int SHOOTER_FOLLOWER_MOTOR_ID = 54;
public static final int ANGLER_MOTOR_ID = 11;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

52?


// other CAN-ID's
public static final int TURRET_MOTOR_ID = 1;
public static final int FEEDER_MOTOR_ID = 2;
public static final int HOPPER_MOTOR_ID = 3;
public static final int INTAKE_MOTOR_ID = 4;
public static final int INTAKE_DEPLOYMENT_ID = 5;
public static final int CLIMBER_MOTOR_ID = 6;

}
18 changes: 9 additions & 9 deletions src/main/java/frc/robot/constants/ConstantsTestbed2026.java
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
package frc.robot.constants;

public class ConstantsTestbed2026 extends Constants2026 {
/**
* To use the TestBed constants, change Constants.java to read: {@code public class Constants extends
* ConstantsTestbed2026}
*
* <p>instead of: {@code public class Constants extends ConstantsPushbot2026}
*
* <p>Then revert changes to Constants.java and ConstantsTestBed.java before committing.
*/
public class ConstantsTestbed2026 extends ConstantsPushbot2026 {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

extend REAL?


// public static final int ROLLER_MOTOR_ID = 40;
// public static final int TILT_MOTOR_ID = 42;
//Intake motor id (43) isn't real
// public static final int HOPPER_MOTOR_ID = 43;
/**
* To use the TestBed constants, change Constants.java to read: public class Constants extends
* ConstantsTestbedClean2025
*
* <p>instead of: public class Constants extends Constants2025
*
* <p>Then revert changes to Constants.java and ConstantsTestBed.java before committing.
*/

/**
* This an example of overriding a specific motor ID for testing, no changes to this file should
Expand Down