mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpimath] Rename FindNearestPoint() to Nearest() (#7513)
This is easier to type and follows the naming of Pose2d::Nearest(). Since Ellipse2d and Rectangle2d were added for the 2025 season, we don't need to add deprecation notices.
This commit is contained in:
@@ -199,7 +199,7 @@ public class Ellipse2d implements ProtobufSerializable, StructSerializable {
|
||||
* @return The distance (0, if the point is contained by the ellipse)
|
||||
*/
|
||||
public double getDistance(Translation2d point) {
|
||||
return findNearestPoint(point).getDistance(point);
|
||||
return nearest(point).getDistance(point);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -218,7 +218,7 @@ public class Ellipse2d implements ProtobufSerializable, StructSerializable {
|
||||
* @param point The point that this will find the nearest point to.
|
||||
* @return A new point that is nearest to {@code point} and contained in the ellipse.
|
||||
*/
|
||||
public Translation2d findNearestPoint(Translation2d point) {
|
||||
public Translation2d nearest(Translation2d point) {
|
||||
// Check if already in ellipse
|
||||
if (contains(point)) {
|
||||
return point;
|
||||
@@ -226,7 +226,7 @@ public class Ellipse2d implements ProtobufSerializable, StructSerializable {
|
||||
|
||||
// Find nearest point
|
||||
var nearestPoint = new double[2];
|
||||
Ellipse2dJNI.findNearestPoint(
|
||||
Ellipse2dJNI.nearest(
|
||||
m_center.getX(),
|
||||
m_center.getY(),
|
||||
m_center.getRotation().getRadians(),
|
||||
|
||||
@@ -186,7 +186,7 @@ public class Rectangle2d implements ProtobufSerializable, StructSerializable {
|
||||
* @return The distance (0, if the point is contained by the rectangle)
|
||||
*/
|
||||
public double getDistance(Translation2d point) {
|
||||
return findNearestPoint(point).getDistance(point);
|
||||
return nearest(point).getDistance(point);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -205,7 +205,7 @@ public class Rectangle2d implements ProtobufSerializable, StructSerializable {
|
||||
* @param point The point that this will find the nearest point to.
|
||||
* @return A new point that is nearest to {@code point} and contained in the rectangle.
|
||||
*/
|
||||
public Translation2d findNearestPoint(Translation2d point) {
|
||||
public Translation2d nearest(Translation2d point) {
|
||||
// Check if already in rectangle
|
||||
if (contains(point)) {
|
||||
return point;
|
||||
|
||||
@@ -9,7 +9,7 @@ public final class Ellipse2dJNI extends WPIMathJNI {
|
||||
/**
|
||||
* Returns the nearest point that is contained within the ellipse.
|
||||
*
|
||||
* <p>Constructs an Ellipse2d object and runs its FindNearestPoint() method.
|
||||
* <p>Constructs an Ellipse2d object and runs its nearest() method.
|
||||
*
|
||||
* @param centerX The x coordinate of the center of the ellipse in meters.
|
||||
* @param centerY The y coordinate of the center of the ellipse in meters.
|
||||
@@ -20,7 +20,7 @@ public final class Ellipse2dJNI extends WPIMathJNI {
|
||||
* @param pointY The y coordinate of the point that this will find the nearest point to.
|
||||
* @param nearestPoint Array to store nearest point into.
|
||||
*/
|
||||
public static native void findNearestPoint(
|
||||
public static native void nearest(
|
||||
double centerX,
|
||||
double centerY,
|
||||
double centerHeading,
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
|
||||
using namespace frc;
|
||||
|
||||
Translation2d Ellipse2d::FindNearestPoint(const Translation2d& point) const {
|
||||
Translation2d Ellipse2d::Nearest(const Translation2d& point) const {
|
||||
// Check if already in ellipse
|
||||
if (Contains(point)) {
|
||||
return point;
|
||||
|
||||
@@ -16,11 +16,11 @@ extern "C" {
|
||||
|
||||
/*
|
||||
* Class: edu_wpi_first_math_jni_Ellipse2dJNI
|
||||
* Method: findNearestPoint
|
||||
* Method: nearest
|
||||
* Signature: (DDDDDDD[D)V
|
||||
*/
|
||||
JNIEXPORT void JNICALL
|
||||
Java_edu_wpi_first_math_jni_Ellipse2dJNI_findNearestPoint
|
||||
Java_edu_wpi_first_math_jni_Ellipse2dJNI_nearest
|
||||
(JNIEnv* env, jclass, jdouble centerX, jdouble centerY, jdouble centerHeading,
|
||||
jdouble xSemiAxis, jdouble ySemiAxis, jdouble pointX, jdouble pointY,
|
||||
jdoubleArray nearestPoint)
|
||||
@@ -30,7 +30,7 @@ Java_edu_wpi_first_math_jni_Ellipse2dJNI_findNearestPoint
|
||||
frc::Pose2d{units::meter_t{centerX}, units::meter_t{centerY},
|
||||
units::radian_t{centerHeading}},
|
||||
units::meter_t{xSemiAxis}, units::meter_t{ySemiAxis}}
|
||||
.FindNearestPoint({units::meter_t{pointX}, units::meter_t{pointY}});
|
||||
.Nearest({units::meter_t{pointX}, units::meter_t{pointY}});
|
||||
|
||||
wpi::array buf{point.X().value(), point.Y().value()};
|
||||
env->SetDoubleArrayRegion(nearestPoint, 0, 2, buf.data());
|
||||
|
||||
@@ -154,7 +154,7 @@ class WPILIB_DLLEXPORT Ellipse2d {
|
||||
* @return The distance (0, if the point is contained by the ellipse)
|
||||
*/
|
||||
units::meter_t Distance(const Translation2d& point) const {
|
||||
return FindNearestPoint(point).Distance(point);
|
||||
return Nearest(point).Distance(point);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -164,7 +164,7 @@ class WPILIB_DLLEXPORT Ellipse2d {
|
||||
* @return A new point that is nearest to {@code point} and contained in the
|
||||
* ellipse.
|
||||
*/
|
||||
Translation2d FindNearestPoint(const Translation2d& point) const;
|
||||
Translation2d Nearest(const Translation2d& point) const;
|
||||
|
||||
/**
|
||||
* Checks equality between this Ellipse2d and another object.
|
||||
|
||||
@@ -155,7 +155,7 @@ class WPILIB_DLLEXPORT Rectangle2d {
|
||||
* @return The distance (0, if the point is contained by the rectangle)
|
||||
*/
|
||||
constexpr units::meter_t Distance(const Translation2d& point) const {
|
||||
return FindNearestPoint(point).Distance(point);
|
||||
return Nearest(point).Distance(point);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -165,7 +165,7 @@ class WPILIB_DLLEXPORT Rectangle2d {
|
||||
* @return A new point that is nearest to {@code point} and contained in the
|
||||
* rectangle.
|
||||
*/
|
||||
constexpr Translation2d FindNearestPoint(const Translation2d& point) const {
|
||||
constexpr Translation2d Nearest(const Translation2d& point) const {
|
||||
// Check if already in rectangle
|
||||
if (Contains(point)) {
|
||||
return point;
|
||||
|
||||
@@ -30,7 +30,7 @@ class Ellipse2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testIntersectsPoint() {
|
||||
void testIntersects() {
|
||||
var center = new Pose2d(1.0, 2.0, new Rotation2d());
|
||||
var ellipse = new Ellipse2d(center, 2.0, 1.0);
|
||||
|
||||
@@ -43,7 +43,7 @@ class Ellipse2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testContainsPoint() {
|
||||
void testContains() {
|
||||
var center = new Pose2d(-1.0, -2.0, Rotation2d.fromDegrees(45.0));
|
||||
var ellipse = new Ellipse2d(center, 2.0, 1.0);
|
||||
|
||||
@@ -55,7 +55,7 @@ class Ellipse2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testDistanceToPoint() {
|
||||
void testDistance() {
|
||||
var center = new Pose2d(1.0, 2.0, Rotation2d.fromDegrees(270.0));
|
||||
var ellipse = new Ellipse2d(center, 1.0, 2.0);
|
||||
|
||||
@@ -73,30 +73,30 @@ class Ellipse2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testFindNearestPoint() {
|
||||
void testNearest() {
|
||||
var center = new Pose2d(1.0, 2.0, Rotation2d.fromDegrees(270.0));
|
||||
var ellipse = new Ellipse2d(center, 1.0, 2.0);
|
||||
|
||||
var point1 = new Translation2d(2.5, 2.0);
|
||||
var nearestPoint1 = ellipse.findNearestPoint(point1);
|
||||
var nearestPoint1 = ellipse.nearest(point1);
|
||||
assertAll(
|
||||
() -> assertEquals(2.5, nearestPoint1.getX(), kEpsilon),
|
||||
() -> assertEquals(2.0, nearestPoint1.getY(), kEpsilon));
|
||||
|
||||
var point2 = new Translation2d(1.0, 2.0);
|
||||
var nearestPoint2 = ellipse.findNearestPoint(point2);
|
||||
var nearestPoint2 = ellipse.nearest(point2);
|
||||
assertAll(
|
||||
() -> assertEquals(1.0, nearestPoint2.getX(), kEpsilon),
|
||||
() -> assertEquals(2.0, nearestPoint2.getY(), kEpsilon));
|
||||
|
||||
var point3 = new Translation2d(1.0, 1.0);
|
||||
var nearestPoint3 = ellipse.findNearestPoint(point3);
|
||||
var nearestPoint3 = ellipse.nearest(point3);
|
||||
assertAll(
|
||||
() -> assertEquals(1.0, nearestPoint3.getX(), kEpsilon),
|
||||
() -> assertEquals(1.0, nearestPoint3.getY(), kEpsilon));
|
||||
|
||||
var point4 = new Translation2d(-1.0, 2.5);
|
||||
var nearestPoint4 = ellipse.findNearestPoint(point4);
|
||||
var nearestPoint4 = ellipse.nearest(point4);
|
||||
assertAll(
|
||||
() -> assertEquals(-0.8512799937611617, nearestPoint4.getX(), kEpsilon),
|
||||
() -> assertEquals(2.378405333174535, nearestPoint4.getY(), kEpsilon));
|
||||
|
||||
@@ -30,7 +30,7 @@ class Rectangle2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testIntersectsPoint() {
|
||||
void testIntersects() {
|
||||
var center = new Pose2d(4.0, 3.0, Rotation2d.fromDegrees(90.0));
|
||||
var rect = new Rectangle2d(center, 2.0, 3.0);
|
||||
|
||||
@@ -42,7 +42,7 @@ class Rectangle2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testContainsPoint() {
|
||||
void testContains() {
|
||||
var center = new Pose2d(2.0, 3.0, Rotation2d.fromDegrees(45.0));
|
||||
var rect = new Rectangle2d(center, 3.0, 1.0);
|
||||
|
||||
@@ -53,7 +53,7 @@ class Rectangle2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testDistanceToPoint() {
|
||||
void testDistance() {
|
||||
var center = new Pose2d(1.0, 2.0, Rotation2d.fromDegrees(270.0));
|
||||
var rect = new Rectangle2d(center, 1.0, 2.0);
|
||||
|
||||
@@ -71,18 +71,18 @@ class Rectangle2dTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
void testFindNearestPoint() {
|
||||
void testNearest() {
|
||||
var center = new Pose2d(1.0, 1.0, Rotation2d.fromDegrees(90.0));
|
||||
var rect = new Rectangle2d(center, 3.0, 4.0);
|
||||
|
||||
var point1 = new Translation2d(1.0, 3.0);
|
||||
var nearestPoint1 = rect.findNearestPoint(point1);
|
||||
var nearestPoint1 = rect.nearest(point1);
|
||||
assertAll(
|
||||
() -> assertEquals(1.0, nearestPoint1.getX(), kEpsilon),
|
||||
() -> assertEquals(2.5, nearestPoint1.getY(), kEpsilon));
|
||||
|
||||
var point2 = new Translation2d(0.0, 0.0);
|
||||
var nearestPoint2 = rect.findNearestPoint(point2);
|
||||
var nearestPoint2 = rect.nearest(point2);
|
||||
assertAll(
|
||||
() -> assertEquals(0.0, nearestPoint2.getX(), kEpsilon),
|
||||
() -> assertEquals(0.0, nearestPoint2.getY(), kEpsilon));
|
||||
|
||||
@@ -16,7 +16,7 @@ TEST(Ellipse2dTest, FocalPoints) {
|
||||
EXPECT_EQ(frc::Translation2d(4_m, 2_m), b);
|
||||
}
|
||||
|
||||
TEST(Ellipse2dTest, IntersectsPoint) {
|
||||
TEST(Ellipse2dTest, Intersects) {
|
||||
constexpr frc::Pose2d center{1_m, 2_m, 0_deg};
|
||||
constexpr frc::Ellipse2d ellipse{center, 2_m, 1_m};
|
||||
|
||||
@@ -27,7 +27,7 @@ TEST(Ellipse2dTest, IntersectsPoint) {
|
||||
EXPECT_FALSE(ellipse.Intersects(pointB));
|
||||
}
|
||||
|
||||
TEST(Ellipse2dTest, ContainsPoint) {
|
||||
TEST(Ellipse2dTest, Contains) {
|
||||
constexpr frc::Pose2d center{-1_m, -2_m, 45_deg};
|
||||
constexpr frc::Ellipse2d ellipse{center, 2_m, 1_m};
|
||||
|
||||
@@ -38,7 +38,7 @@ TEST(Ellipse2dTest, ContainsPoint) {
|
||||
EXPECT_FALSE(ellipse.Contains(pointB));
|
||||
}
|
||||
|
||||
TEST(Ellipse2dTest, DistanceToPoint) {
|
||||
TEST(Ellipse2dTest, Distance) {
|
||||
constexpr double kEpsilon = 1E-9;
|
||||
|
||||
constexpr frc::Pose2d center{1_m, 2_m, 270_deg};
|
||||
@@ -57,29 +57,29 @@ TEST(Ellipse2dTest, DistanceToPoint) {
|
||||
EXPECT_NEAR(0.19210128384806818, ellipse.Distance(point4).value(), kEpsilon);
|
||||
}
|
||||
|
||||
TEST(Ellipse2dTest, FindNearestPoint) {
|
||||
TEST(Ellipse2dTest, Nearest) {
|
||||
constexpr double kEpsilon = 1E-9;
|
||||
|
||||
constexpr frc::Pose2d center{1_m, 2_m, 270_deg};
|
||||
constexpr frc::Ellipse2d ellipse{center, 1_m, 2_m};
|
||||
|
||||
constexpr frc::Translation2d point1{2.5_m, 2_m};
|
||||
auto nearestPoint1 = ellipse.FindNearestPoint(point1);
|
||||
auto nearestPoint1 = ellipse.Nearest(point1);
|
||||
EXPECT_NEAR(2.5, nearestPoint1.X().value(), kEpsilon);
|
||||
EXPECT_NEAR(2.0, nearestPoint1.Y().value(), kEpsilon);
|
||||
|
||||
constexpr frc::Translation2d point2{1_m, 2_m};
|
||||
auto nearestPoint2 = ellipse.FindNearestPoint(point2);
|
||||
auto nearestPoint2 = ellipse.Nearest(point2);
|
||||
EXPECT_NEAR(1.0, nearestPoint2.X().value(), kEpsilon);
|
||||
EXPECT_NEAR(2.0, nearestPoint2.Y().value(), kEpsilon);
|
||||
|
||||
constexpr frc::Translation2d point3{1_m, 1_m};
|
||||
auto nearestPoint3 = ellipse.FindNearestPoint(point3);
|
||||
auto nearestPoint3 = ellipse.Nearest(point3);
|
||||
EXPECT_NEAR(1.0, nearestPoint3.X().value(), kEpsilon);
|
||||
EXPECT_NEAR(1.0, nearestPoint3.Y().value(), kEpsilon);
|
||||
|
||||
constexpr frc::Translation2d point4{-1_m, 2.5_m};
|
||||
auto nearestPoint4 = ellipse.FindNearestPoint(point4);
|
||||
auto nearestPoint4 = ellipse.Nearest(point4);
|
||||
EXPECT_NEAR(-0.8512799937611617, nearestPoint4.X().value(), kEpsilon);
|
||||
EXPECT_NEAR(2.378405333174535, nearestPoint4.Y().value(), kEpsilon);
|
||||
}
|
||||
|
||||
@@ -18,7 +18,7 @@ TEST(Rectangle2dTest, NewWithCorners) {
|
||||
EXPECT_EQ(4.0, rect.Center().Y().value());
|
||||
}
|
||||
|
||||
TEST(Rectangle2dTest, IntersectsPoint) {
|
||||
TEST(Rectangle2dTest, Intersects) {
|
||||
constexpr frc::Pose2d center{4_m, 3_m, 90_deg};
|
||||
constexpr frc::Rectangle2d rect{center, 2_m, 3_m};
|
||||
|
||||
@@ -28,7 +28,7 @@ TEST(Rectangle2dTest, IntersectsPoint) {
|
||||
EXPECT_FALSE(rect.Intersects(frc::Translation2d{4_m, 3.5_m}));
|
||||
}
|
||||
|
||||
TEST(Rectangle2dTest, ContainsPoint) {
|
||||
TEST(Rectangle2dTest, Contains) {
|
||||
constexpr frc::Pose2d center{2_m, 3_m, 45_deg};
|
||||
constexpr frc::Rectangle2d rect{center, 3_m, 1_m};
|
||||
|
||||
@@ -37,7 +37,7 @@ TEST(Rectangle2dTest, ContainsPoint) {
|
||||
EXPECT_FALSE(rect.Contains(frc::Translation2d{3_m, 3_m}));
|
||||
}
|
||||
|
||||
TEST(Rectangle2dTest, DistanceToPoint) {
|
||||
TEST(Rectangle2dTest, Distance) {
|
||||
constexpr double kEpsilon = 1E-9;
|
||||
|
||||
constexpr frc::Pose2d center{1_m, 2_m, 270_deg};
|
||||
@@ -56,19 +56,19 @@ TEST(Rectangle2dTest, DistanceToPoint) {
|
||||
EXPECT_NEAR(1, rect.Distance(point4).value(), kEpsilon);
|
||||
}
|
||||
|
||||
TEST(Rectangle2dTest, FindNearestPoint) {
|
||||
TEST(Rectangle2dTest, Nearest) {
|
||||
constexpr double kEpsilon = 1E-9;
|
||||
|
||||
constexpr frc::Pose2d center{1_m, 1_m, 90_deg};
|
||||
constexpr frc::Rectangle2d rect{center, 3_m, 4_m};
|
||||
|
||||
constexpr frc::Translation2d point1{1_m, 3_m};
|
||||
auto nearestPoint1 = rect.FindNearestPoint(point1);
|
||||
auto nearestPoint1 = rect.Nearest(point1);
|
||||
EXPECT_NEAR(1.0, nearestPoint1.X().value(), kEpsilon);
|
||||
EXPECT_NEAR(2.5, nearestPoint1.Y().value(), kEpsilon);
|
||||
|
||||
constexpr frc::Translation2d point2{0_m, 0_m};
|
||||
auto nearestPoint2 = rect.FindNearestPoint(point2);
|
||||
auto nearestPoint2 = rect.Nearest(point2);
|
||||
EXPECT_NEAR(0.0, nearestPoint2.X().value(), kEpsilon);
|
||||
EXPECT_NEAR(0.0, nearestPoint2.Y().value(), kEpsilon);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user