Skip to content

Commit f126258

Browse files
authored
Flippable (#31)
* Remade mirrorable as flippable * Formatted * Fixed javadocs
1 parent 1532628 commit f126258

File tree

8 files changed

+230
-179
lines changed

8 files changed

+230
-179
lines changed

src/main/java/org/trigon/utilities/mirrorable/Mirrorable.java renamed to src/main/java/org/trigon/utilities/flippable/Flippable.java

Lines changed: 24 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
1-
package org.trigon.utilities.mirrorable;
1+
package org.trigon.utilities.flippable;
22

3-
import edu.wpi.first.math.geometry.Rotation2d;
43
import edu.wpi.first.wpilibj.DriverStation;
54
import edu.wpi.first.wpilibj.Timer;
65
import edu.wpi.first.wpilibj2.command.Command;
@@ -10,22 +9,22 @@
109
import java.util.Optional;
1110

1211
/**
13-
* A class that allows for objects to be mirrored across the center of the field when the robot is on the red alliance.
14-
* This is useful for placing field elements and other objects that are mirrored across the field, or for mirroring the target heading to face a field element.
12+
* A class that allows for objects to be flipped across the center of the field when the robot is on the red alliance.
13+
* This is useful for placing field elements and other objects that are flipped across the field, or for flipping the target heading to face a field element.
14+
* This either represents a field that is mirrored vertically over the center of the field, or a field that is rotationally symmetric: the red alliance side is the blue alliance side rotated by 180 degrees.
15+
* The code will automatically determine which type of field the robot is on and flip the object accordingly.
1516
*
16-
* @param <T> the type of object to mirror
17+
* @param <T> the type of object to flip
1718
*/
18-
public abstract class Mirrorable<T> {
19-
protected static final Rotation2d HALF_ROTATION = new Rotation2d(Math.PI);
20-
protected static final double FIELD_LENGTH_METERS = 16.54175;
19+
public abstract class Flippable<T> {
2120
private static final Timer UPDATE_ALLIANCE_TIMER = new Timer();
2221
private static boolean IS_RED_ALLIANCE = notCachedIsRedAlliance();
23-
protected final T nonMirroredObject, mirroredObject;
22+
protected final T nonFlippedObject, flippedObject;
2423

25-
protected final boolean shouldMirrorWhenRedAlliance;
24+
protected final boolean shouldFlipWhenRedAlliance;
2625

2726
/**
28-
* Initializes the mirrorable class. This should be called once in RobotContainer.
27+
* Initializes the Flippable class. This should be called once in RobotContainer.
2928
*/
3029
public static void init() {
3130
UPDATE_ALLIANCE_TIMER.start();
@@ -57,32 +56,32 @@ private static boolean notCachedIsRedAlliance() {
5756
}
5857

5958
/**
60-
* Creates a new mirrorable object.
59+
* Creates a new Flippable object.
6160
*
62-
* @param nonMirroredObject the object when the robot is on the blue alliance, or the non-mirrored object
63-
* @param shouldMirrorWhenRedAlliance should the object should be mirrored when the robot is on the red alliance
61+
* @param nonFlippedObject the object when the robot is on the blue alliance; the non-flipped object
62+
* @param shouldFlipWhenRedAlliance should the object should be flipped when the robot is on the red alliance
6463
*/
65-
protected Mirrorable(T nonMirroredObject, boolean shouldMirrorWhenRedAlliance) {
66-
this.nonMirroredObject = nonMirroredObject;
67-
this.mirroredObject = mirror(nonMirroredObject);
68-
this.shouldMirrorWhenRedAlliance = shouldMirrorWhenRedAlliance;
64+
protected Flippable(T nonFlippedObject, boolean shouldFlipWhenRedAlliance) {
65+
this.nonFlippedObject = nonFlippedObject;
66+
this.flippedObject = flip(nonFlippedObject);
67+
this.shouldFlipWhenRedAlliance = shouldFlipWhenRedAlliance;
6968
}
7069

7170
/**
72-
* If the robot is on the red alliance and the object should be mirrored, the mirrored object is returned.
73-
* Otherwise, the non-mirrored object is returned.
71+
* If the robot is on the red alliance and the object should be flipped, the flipped object is returned.
72+
* Otherwise, the non-flipped object is returned.
7473
*
7574
* @return the current object
7675
*/
7776
public T get() {
78-
return isRedAlliance() && shouldMirrorWhenRedAlliance ? mirroredObject : nonMirroredObject;
77+
return isRedAlliance() && shouldFlipWhenRedAlliance ? flippedObject : nonFlippedObject;
7978
}
8079

8180
/**
82-
* Mirrors the object across the center of the field.
81+
* Flips the object across the center of the field.
8382
*
84-
* @param object the object to mirror
85-
* @return the mirrored object
83+
* @param object the object to flip
84+
* @return the flipped object
8685
*/
87-
protected abstract T mirror(T object);
86+
protected abstract T flip(T object);
8887
}
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
package org.trigon.utilities.flippable;
2+
3+
import com.pathplanner.lib.util.FlippingUtil;
4+
import edu.wpi.first.math.geometry.Pose2d;
5+
import edu.wpi.first.math.geometry.Rotation2d;
6+
import edu.wpi.first.math.geometry.Translation2d;
7+
8+
/**
9+
* A class that represents a {@link Pose2d} that can be flipped when the robot is on the red alliance.
10+
*/
11+
public class FlippablePose2d extends Flippable<Pose2d> {
12+
/**
13+
* Creates a new FlippablePose2d with the given x, y, and rotation.
14+
*
15+
* @param x the x value of the pose
16+
* @param y the y value of the pose
17+
* @param rotation the rotation of the pose
18+
* @param shouldFlipWhenRedAlliance should the pose be flipped when the robot is on the red alliance
19+
*/
20+
public FlippablePose2d(double x, double y, Rotation2d rotation, boolean shouldFlipWhenRedAlliance) {
21+
this(new Pose2d(x, y, rotation), shouldFlipWhenRedAlliance);
22+
}
23+
24+
/**
25+
* Creates a new FlippablePose2d with the given translation and rotation.
26+
*
27+
* @param translation2d the translation of the pose
28+
* @param rotationRadians the rotation of the pose in radians
29+
* @param shouldFlipWhenRedAlliance should the pose be flipped when the robot is on the red alliance
30+
*/
31+
public FlippablePose2d(Translation2d translation2d, double rotationRadians, boolean shouldFlipWhenRedAlliance) {
32+
this(new Pose2d(translation2d, new Rotation2d(rotationRadians)), shouldFlipWhenRedAlliance);
33+
}
34+
35+
/**
36+
* Creates a new FlippablePose2d with the given x, y, and rotation.
37+
*
38+
* @param nonFlippedPose the pose when the robot is on the blue alliance
39+
* @param shouldFlipWhenRedAlliance should the pose be flipped when the robot is on the red alliance
40+
*/
41+
public FlippablePose2d(Pose2d nonFlippedPose, boolean shouldFlipWhenRedAlliance) {
42+
super(nonFlippedPose, shouldFlipWhenRedAlliance);
43+
}
44+
45+
/**
46+
* Gets the rotation value of the pose. The pose will be flipped if the robot is on the red alliance and {@link #shouldFlipWhenRedAlliance} is true.
47+
*
48+
* @return the rotation value of the pose
49+
*/
50+
public FlippableRotation2d getRotation() {
51+
return new FlippableRotation2d(nonFlippedObject.getRotation(), shouldFlipWhenRedAlliance);
52+
}
53+
54+
@Override
55+
protected Pose2d flip(Pose2d pose) {
56+
return FlippingUtil.flipFieldPose(pose);
57+
}
58+
}
Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
1+
package org.trigon.utilities.flippable;
2+
3+
import com.pathplanner.lib.util.FlippingUtil;
4+
import edu.wpi.first.math.geometry.Rotation2d;
5+
6+
/**
7+
* A class that represents a {@link Rotation2d} that can be flipped when the robot is on the red alliance.
8+
*/
9+
public class FlippableRotation2d extends Flippable<Rotation2d> {
10+
/**
11+
* Constructs and returns a FlippableRotation2d with the given degree value.
12+
*
13+
* @param degrees the value of the angle in degrees
14+
* @param shouldFlipWhenRedAlliance should the rotation be flipped when the robot is on the red alliance
15+
* @return the rotation object with the desired angle value
16+
*/
17+
public static FlippableRotation2d fromDegrees(double degrees, boolean shouldFlipWhenRedAlliance) {
18+
return new FlippableRotation2d(Rotation2d.fromDegrees(degrees), shouldFlipWhenRedAlliance);
19+
}
20+
21+
/**
22+
* Constructs and returns a FlippableRotation2d with the given radian value.
23+
*
24+
* @param radians the value of the angle in radians
25+
* @param shouldFlipWhenRedAlliance should the rotation be flipped when the robot is on the red alliance
26+
* @return the rotation object with the desired angle value
27+
*/
28+
public static FlippableRotation2d fromRadians(double radians, boolean shouldFlipWhenRedAlliance) {
29+
return new FlippableRotation2d(Rotation2d.fromRadians(radians), shouldFlipWhenRedAlliance);
30+
}
31+
32+
/**
33+
* Constructs a FlippableRotation2d with the given number of rotations.
34+
*
35+
* @param rotations the value of the angle in rotations
36+
* @param shouldFlipWhenRedAlliance should the rotation be flipped when the robot is on the red alliance
37+
* @return the rotation object with the desired angle value
38+
*/
39+
public static FlippableRotation2d fromRotations(double rotations, boolean shouldFlipWhenRedAlliance) {
40+
return new FlippableRotation2d(Rotation2d.fromRotations(rotations), shouldFlipWhenRedAlliance);
41+
}
42+
43+
/**
44+
* Creates a new FlippableRotation2d with the given rotation value.
45+
*
46+
* @param radians the value of the angle in radians
47+
* @param shouldFlipWhenRedAlliance should the rotation be flipped when the robot is on the red alliance
48+
*/
49+
public FlippableRotation2d(double radians, boolean shouldFlipWhenRedAlliance) {
50+
this(new Rotation2d(radians), shouldFlipWhenRedAlliance);
51+
}
52+
53+
/**
54+
* Creates a new FlippableRotation2d with the given Rotation2d.
55+
*
56+
* @param nonFlippedRotation the non flipped rotation when the robot is on the blue alliance
57+
* @param shouldFlipWhenRedAlliance should the rotation be flipped when the robot is on the red alliance
58+
*/
59+
public FlippableRotation2d(Rotation2d nonFlippedRotation, boolean shouldFlipWhenRedAlliance) {
60+
super(nonFlippedRotation, shouldFlipWhenRedAlliance);
61+
}
62+
63+
@Override
64+
protected Rotation2d flip(Rotation2d rotation) {
65+
return FlippingUtil.flipFieldRotation(rotation);
66+
}
67+
}
Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
package org.trigon.utilities.flippable;
2+
3+
import com.pathplanner.lib.util.FlippingUtil;
4+
import edu.wpi.first.math.geometry.Translation2d;
5+
6+
/**
7+
* A class that represents a {@link Translation2d} that can be flipped when the robot is on the red alliance.
8+
*/
9+
public class FlippableTranslation2d extends Flippable<Translation2d> {
10+
/**
11+
* Creates a new FlippableTranslation2d with the given x and y values.
12+
*
13+
* @param x the x value of the translation
14+
* @param y the y value of the translation
15+
* @param shouldFlipWhenRedAlliance should the position be flipped when the robot is on the red alliance
16+
*/
17+
public FlippableTranslation2d(double x, double y, boolean shouldFlipWhenRedAlliance) {
18+
this(new Translation2d(x, y), shouldFlipWhenRedAlliance);
19+
}
20+
21+
/**
22+
* Creates a new FlippableTranslation2d with the given translation.
23+
*
24+
* @param nonFlippedTranslation the translation to flip
25+
* @param shouldFlipWhenRedAlliance should the position be flipped when the robot is on the red alliance
26+
*/
27+
public FlippableTranslation2d(Translation2d nonFlippedTranslation, boolean shouldFlipWhenRedAlliance) {
28+
super(nonFlippedTranslation, shouldFlipWhenRedAlliance);
29+
}
30+
31+
@Override
32+
protected Translation2d flip(Translation2d translation) {
33+
return FlippingUtil.flipFieldPosition(translation);
34+
}
35+
}
Lines changed: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
package org.trigon.utilities.flippable;
2+
3+
import com.pathplanner.lib.util.FlippingUtil;
4+
import edu.wpi.first.math.geometry.Translation2d;
5+
import edu.wpi.first.math.geometry.Translation3d;
6+
7+
/**
8+
* A class that represents a {@link Translation3d} that can be flipped when the robot is on the red alliance.
9+
* The Z value will have no change.
10+
*/
11+
public class FlippableTranslation3d extends Flippable<Translation3d> {
12+
/**
13+
* Creates a new FlippableTranslation3d with the given x, y, and z values.
14+
*
15+
* @param x the x value of the translation
16+
* @param y the y value of the translation
17+
* @param z the z value of the translation
18+
* @param shouldFlipWhenRedAlliance should the position be flipped when the robot is on the red alliance
19+
*/
20+
public FlippableTranslation3d(double x, double y, double z, boolean shouldFlipWhenRedAlliance) {
21+
this(new Translation3d(x, y, z), shouldFlipWhenRedAlliance);
22+
}
23+
24+
/**
25+
* Creates a new FlippableTranslation3d with the given translation.
26+
*
27+
* @param nonFlippedTranslation the translation to flip
28+
* @param shouldFlipWhenRedAlliance should the position be flipped when the robot is on the red alliance
29+
*/
30+
public FlippableTranslation3d(Translation3d nonFlippedTranslation, boolean shouldFlipWhenRedAlliance) {
31+
super(nonFlippedTranslation, shouldFlipWhenRedAlliance);
32+
}
33+
34+
/**
35+
* Flips the given translation. The translation will be flipped if the robot is on the red alliance and {@link #shouldFlipWhenRedAlliance} is true.
36+
* The Z value will have no change.
37+
*
38+
* @param translation the object to flip
39+
* @return the flipped translation
40+
*/
41+
@Override
42+
protected Translation3d flip(Translation3d translation) {
43+
final Translation2d flippedTranslation2d = FlippingUtil.flipFieldPosition(translation.toTranslation2d());
44+
return new Translation3d(flippedTranslation2d.getX(), flippedTranslation2d.getY(), translation.getZ());
45+
}
46+
}

src/main/java/org/trigon/utilities/mirrorable/MirrorablePose2d.java

Lines changed: 0 additions & 55 deletions
This file was deleted.

0 commit comments

Comments
 (0)