Skip to content

Commit 901e3b9

Browse files
committed
Renames angleFrom to getTargetAngleForRobot to make it easier to find
1 parent 4078c12 commit 901e3b9

File tree

1 file changed

+13
-1
lines changed

1 file changed

+13
-1
lines changed

src/main/java/com/chaos131/poses/FieldPose.java

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -106,10 +106,22 @@ public static Distance getDistanceFromLocations(Pose2d pose1, Pose2d pose2) {
106106
}
107107

108108
/**
109+
* Calculates the angle from the robotPose to the FieldPose. Useful for aiming the robot.
110+
*
111+
* @param robotpose to calculate from
112+
* @return Rotation2d - the field coordinate angle relative to field angle 0.
113+
*/
114+
public Rotation2d getTargetAngleForRobot(Pose2d robotpose) {
115+
return getTargetAngleForRobot(robotpose.getTranslation());
116+
}
117+
118+
/**
119+
* Calculates the angle from the robotPose to the FieldPose. Useful for aiming the robot.
120+
*
109121
* @param robotpose to calculate from
110122
* @return Rotation2d - the field coordinate angle relative to field angle 0.
111123
*/
112-
public Rotation2d angleFrom(Translation2d robotpose) {
124+
public Rotation2d getTargetAngleForRobot(Translation2d robotpose) {
113125
return getCurrentAlliancePose().getTranslation().minus(robotpose).getAngle();
114126
}
115127

0 commit comments

Comments
 (0)