Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
147 changes: 94 additions & 53 deletions .advantagescope/Robot_Relic2026/config.json
Original file line number Diff line number Diff line change
@@ -1,54 +1,95 @@
{
"name": "Relic",
"rotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"position": [0, 0, 0],
"disableSimplification": true,
"dynamicColoring": true,
"cameras": [
{
"name": "Front Camera",
"rotations": [
{
"axis": "y",
"degrees": -20
}
],
"position": [
0.3048,
0.12,
0.12
],
"resolution": [
1280,
960
],
"fov": 83
}
],
"components": [
{
"zeroedRotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"zeroedPosition": [0.098, 0, -0.457]
},
{
"zeroedRotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"zeroedPosition": [-0.252, 0, -0.207]
},
{
"zeroedRotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"zeroedPosition": [-0.252, 0, -0.207]
}
]
}
"name": "Relic",
"rotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"position": [0, 0, 0],
"disableSimplification": true,
"dynamicColoring": true,
"cameras": [
{
"name": "Shooter Camera",
"rotations": [
{
"axis": "y",
"degrees": -30
}
],
"position": [
0.0,
0.0,
0.526
]
},
{
"name": "Back Left Camera",
"rotations": [
{
"axis": "y",
"degrees": -30
},
{
"axis": "z",
"degrees": 150
}
],
"position": [
-0.160,
0.322,
0.216
],
"resolution": [
1280,
960
],
"fov": 83
},
{
"name": "Back Right Camera",
"rotations": [
{
"axis": "y",
"degrees": -30
},
{
"axis": "z",
"degrees": 210
}
],
"position": [
-0.162,
-0.322,
0.216
],
"resolution": [
1280,
960
],
"fov": 83
}
],
"components": [
{
"zeroedRotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"zeroedPosition": [0.098, 0, -0.457]
},
{
"zeroedRotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"zeroedPosition": [-0.252, 0, -0.207]
},
{
"zeroedRotations": [
{"axis": "x", "degrees": 90},
{"axis": "z", "degrees": 90}
],
"zeroedPosition": [-0.252, 0, -0.207]
}
]
}
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,9 @@ public RobotContainer() {

vision_ = new AprilTagVision(
drivebase_::addVisionMeasurement,
new CameraIOPhotonSim("front", VisionConstants.frontTransform, MapleSimUtil::getPosition, true)
new CameraIOPhotonSim("front", VisionConstants.frontTransform, MapleSimUtil::getPosition, true),
new CameraIOPhotonSim("backleft", VisionConstants.backLeftTransform, MapleSimUtil::getPosition, true),
new CameraIOPhotonSim("backright", VisionConstants.backRightTransform, MapleSimUtil::getPosition, true)
);

intake_= new IntakeSubsystem(new IntakeIOSim(roborioCANBus));
Expand Down Expand Up @@ -191,7 +193,7 @@ public RobotContainer() {
};

CameraIO[] cams = new CameraIO[numCams];
Arrays.fill(cams, new CameraIO() {});
Arrays.setAll(cams, i -> new CameraIO() {});

vision_ = new AprilTagVision(
drivebase_::addVisionMeasurement,
Expand Down
14 changes: 12 additions & 2 deletions src/main/java/frc/robot/subsystems/vision/VisionConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,18 @@ public class VisionConstants {

// Transforms
public static final Transform3d frontTransform = new Transform3d(
new Translation3d(Meters.of(0.1975), Meters.of(-0.2032), Meters.of(0.205)),
new Rotation3d(Degrees.zero(), Degrees.of(-20), Degrees.zero())
new Translation3d(Meters.of(0.0), Meters.of(0.0), Meters.of(0.526)),
new Rotation3d(Degrees.zero(), Degrees.of(-28), Degrees.zero())
);

public static final Transform3d backLeftTransform = new Transform3d(
new Translation3d(Meters.of(-0.160), Meters.of(0.322), Meters.of(0.216)),
new Rotation3d(Degrees.zero(), Degrees.of(-30), Degrees.of(150))
);

public static final Transform3d backRightTransform = new Transform3d(
new Translation3d(Meters.of(-0.162), Meters.of(-0.322), Meters.of(0.216)),
new Rotation3d(Degrees.zero(), Degrees.of(-30), Degrees.of(210))
);

// Odometry Filtering Configuration
Expand Down
Loading