[wpimath] Java: add static instantiations of common rotations (#6563)

C++ doesn't need this because it supports value types, which are much
cheaper to construct. constexpr is also available to make construction
zero-cost.
This commit is contained in:
Tyler Veness
2024-05-03 12:39:35 -07:00
committed by GitHub
parent 9c7120e6bf
commit e172aa66f7
75 changed files with 499 additions and 429 deletions

View File

@@ -83,7 +83,7 @@ public class Drivetrain {
m_gyro.getRotation2d(),
m_leftEncoder.getDistance(),
m_rightEncoder.getDistance(),
new Pose2d(),
Pose2d.kZero,
VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)),
VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));

View File

@@ -90,11 +90,11 @@ public class RobotContainer {
Trajectory exampleTrajectory =
TrajectoryGenerator.generateTrajectory(
// Start at the origin facing the +X direction
new Pose2d(0, 0, new Rotation2d(0)),
Pose2d.kZero,
// Pass through these two interior waypoints, making an 's' curve path
List.of(new Translation2d(1, 1), new Translation2d(2, -1)),
// End 3 meters straight ahead of where we started, facing forward
new Pose2d(3, 0, new Rotation2d(0)),
new Pose2d(3, 0, Rotation2d.kZero),
config);
MecanumControllerCommand mecanumControllerCommand =

View File

@@ -58,7 +58,7 @@ public class Drivetrain {
m_kinematics,
m_gyro.getRotation2d(),
getCurrentDistances(),
new Pose2d(),
Pose2d.kZero,
VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)),
VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));

View File

@@ -34,9 +34,9 @@ public class Robot extends TimedRobot {
public void robotInit() {
m_trajectory =
TrajectoryGenerator.generateTrajectory(
new Pose2d(2, 2, new Rotation2d()),
new Pose2d(2, 2, Rotation2d.kZero),
List.of(),
new Pose2d(6, 4, new Rotation2d()),
new Pose2d(6, 4, Rotation2d.kZero),
new TrajectoryConfig(2, 2));
}

View File

@@ -88,11 +88,11 @@ public class RobotContainer {
Trajectory exampleTrajectory =
TrajectoryGenerator.generateTrajectory(
// Start at the origin facing the +X direction
new Pose2d(0, 0, new Rotation2d(0)),
Pose2d.kZero,
// Pass through these two interior waypoints, making an 's' curve path
List.of(new Translation2d(1, 1), new Translation2d(2, -1)),
// End 3 meters straight ahead of where we started, facing forward
new Pose2d(3, 0, new Rotation2d(0)),
new Pose2d(3, 0, Rotation2d.kZero),
config);
var thetaController =

View File

@@ -48,7 +48,7 @@ public class Drivetrain {
m_backLeft.getPosition(),
m_backRight.getPosition()
},
new Pose2d(),
Pose2d.kZero,
VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)),
VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));