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
107 changes: 98 additions & 9 deletions advantagescope/assets/Robot_frc2713-2026/config.json
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,96 @@
0,
0
],
"cameras": [],
"cameras": [
{
"name": "front",
"rotations": [
{
"axis": "y",
"degrees": -12.5
}
],
"position": [
0.2561335746,
0.1198999888,
0.538800167
],
"resolution": [
1920,
1080
],
"fov": 69
},
{
"name": "rear",
"rotations": [
{
"axis": "z",
"degrees": 180
},
{
"axis": "y",
"degrees": 12.5
}
],
"position": [
-0.3132835746,
-0.0436999888,
0.538800167
],
"resolution": [
1920,
1080
],
"fov": 69
},
{
"name": "left",
"rotations": [
{
"axis": "z",
"degrees": 90
},
{
"axis": "x",
"degrees": 12.5
}
],
"position": [
-0.1452999888,
0.3672585746,
0.538800167
],
"resolution": [
1920,
1080
],
"fov": 69
},
{
"name": "right",
"rotations": [
{
"axis": "z",
"degrees": -90
},
{
"axis": "x",
"degrees": -12.5
}
],
"position": [
-0.1722000112,
-0.3672585746,
0.538800167
],
"resolution": [
1920,
1080
],
"fov": 69
}
],
"components": [
{
"zeroedRotations": [
Expand Down Expand Up @@ -48,8 +137,8 @@
}
],
"zeroedPosition": [
0,
-0.04445,
-0.0127,
-0.0127,
0
]
},
Expand All @@ -65,9 +154,9 @@
}
],
"zeroedPosition": [
0,
-0.04445,
-0.4694966226
-0.0127,
-0.0127,
-0.472377262
]
},
{
Expand All @@ -82,9 +171,9 @@
}
],
"zeroedPosition": [
-0.103807641,
-0.04445,
-0.4694966226
-0.0623012978,
-0.0127,
-0.4984384748
]
}
]
Expand Down
Binary file modified advantagescope/assets/Robot_frc2713-2026/model.glb
Binary file not shown.
Binary file modified advantagescope/assets/Robot_frc2713-2026/model_0.glb
Binary file not shown.
Binary file modified advantagescope/assets/Robot_frc2713-2026/model_1.glb
Binary file not shown.
Binary file modified advantagescope/assets/Robot_frc2713-2026/model_2.glb
Binary file not shown.
Binary file modified advantagescope/assets/Robot_frc2713-2026/model_3.glb
Binary file not shown.
3 changes: 3 additions & 0 deletions src/main/java/frc2713/lib/subsystem/KinematicsManager.java
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,9 @@ public void periodic() {
// 1. Rebuild topology if new components were added
if (isDirty) {
rebuildTopology();
Pose3d[] zeroedComponentPoses = new Pose3d[publishableIndices.length];
Arrays.fill(zeroedComponentPoses, new Pose3d());
Logger.recordOutput(pb.makePath("zeroedComponentPoses"), zeroedComponentPoses);
}

// 2. Update Kinematics
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
package frc2713.lib.subsystem;

import static edu.wpi.first.units.Units.Inches;
import static edu.wpi.first.units.Units.Meters;

import com.ctre.phoenix6.configs.TalonFXConfiguration;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
Expand Down Expand Up @@ -32,5 +29,5 @@ public class TalonFXSubsystemConfig {
public double momentOfInertia = 0.5;

public Transform3d initialTransform =
new Transform3d(new Translation3d(0, 0, Inches.of(18.484119).in(Meters)), new Rotation3d());
new Transform3d(new Translation3d(0, 0, 0), new Rotation3d());
}
2 changes: 1 addition & 1 deletion src/main/java/frc2713/robot/oi/DriverControls.java
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ public void configureButtonBindings() {

// shoot when flywheels are ready
controller
.rightTrigger(-.98)
.rightTrigger(.98)
.whileTrue(
RobotContainer.GameCommandGroups.otfShot(
drive, flywheels, hood, turret, feeder, dyeRotor))
Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,10 @@
package frc2713.robot.subsystems.intake;

import static edu.wpi.first.units.Units.Degrees;
import static edu.wpi.first.units.Units.Meters;
import static edu.wpi.first.units.Units.Radians;

import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.Distance;
import edu.wpi.first.wpilibj2.command.Command;
import frc2713.lib.io.ArticulatedComponent;
Expand Down Expand Up @@ -68,12 +65,7 @@ public void periodic() {
@Override
public Transform3d getTransform3d() {
Distance distance = getCurrentPositionAsDistance();
Angle sliderAngle = Degrees.of(-4.479515);

Distance distanceX = distance.times(Math.cos(sliderAngle.in(Radians)));
Distance distanceZ = distance.times(Math.sin(sliderAngle.in(Radians)));

return new Transform3d(
new Translation3d(distanceX.in(Meters), 0, distanceZ.in(Meters)), new Rotation3d());
return new Transform3d(new Translation3d(distance.in(Meters), 0, 0), new Rotation3d());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,10 @@ public static final class Turret {

config.initialTransform =
new Transform3d(
new Translation3d(0, Inches.of(1.75).in(Meters), Inches.of(18.484119).in(Meters)),
new Translation3d(
Inches.of(0.5).in(Meters),
Inches.of(0.5).in(Meters),
Inches.of(18.484119).in(Meters)),
new Rotation3d(0, 0, 0));
}

Expand Down Expand Up @@ -171,7 +174,8 @@ public final class Hood {

config.initialTransform =
new Transform3d(
new Translation3d(Inches.of(4.086915).in(Meters), 0, 0), new Rotation3d());
new Translation3d(Inches.of(2.452807).in(Meters), 0, Inches.of(1.026032).in(Meters)),
new Rotation3d());
}

public static Angle retractedPosition = Degrees.of(0);
Expand All @@ -193,8 +197,8 @@ public final class Hood {
angleMap.put(1.5, 18.0);
angleMap.put(2.0, 24.0);
angleMap.put(3.0, 28.0);
angleMap.put(4.0, 32.0);
angleMap.put(4.5, 32.0);
angleMap.put(4.0, 30.0);
angleMap.put(4.5, 30.0);
angleMap.put(5.0, 30.0);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,9 @@ public static final class DyeRotor {
config.momentOfInertia = 0.001; // kg*m^2 for simulation (small roller)

config.initialTransform =
new Transform3d(new Translation3d(0, Inches.of(1.75).in(Meters), 0), new Rotation3d());
new Transform3d(
new Translation3d(Inches.of(0.5).in(Meters), Inches.of(0.5).in(Meters), 0),
new Rotation3d());
}

public static LoggedTunableMeasure<AngularVelocity> indexingSpeed =
Expand Down