Skip to content

Commit 6d1d769

Browse files
committed
Add isNotWithin() to Translation2dSubject and Translation3dSubject
1 parent 3fa6751 commit 6d1d769

4 files changed

Lines changed: 132 additions & 7 deletions

File tree

testing/src/main/java/com/team2813/lib2813/testing/truth/Translation2dSubject.java

Lines changed: 23 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,12 +54,33 @@ public TolerantComparison<Translation2d> isWithin(double tolerance) {
5454
return new TolerantComparison<Translation2d>() {
5555
@Override
5656
public void of(Translation2d expected) {
57-
x().isWithin(tolerance).of(expected.getX());
58-
y().isWithin(tolerance).of(expected.getY());
57+
if (expected == null) {
58+
throw new NullPointerException("Expected value cannot be null.");
59+
}
60+
checkDistance(expected).isWithin(tolerance).of(0);
5961
}
6062
};
6163
}
6264

65+
public TolerantComparison<Translation2d> isNotWithin(double tolerance) {
66+
return new TolerantComparison<Translation2d>() {
67+
@Override
68+
public void of(Translation2d expected) {
69+
if (expected == null) {
70+
throw new NullPointerException("Expected value cannot be null.");
71+
}
72+
checkDistance(expected).isNotWithin(tolerance).of(0);
73+
}
74+
};
75+
}
76+
77+
private DoubleSubject checkDistance(Translation2d expected) {
78+
if (expected == null) {
79+
throw new NullPointerException("Expected value cannot be null.");
80+
}
81+
return check("%s", actual).that(nonNullActual().getDistance(expected));
82+
}
83+
6384
public void isZero() {
6485
if (!Translation2d.kZero.equals(actual)) {
6586
failWithActual(simpleFact("expected to be zero"));

testing/src/main/java/com/team2813/lib2813/testing/truth/Translation3dSubject.java

Lines changed: 23 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,13 +54,33 @@ public TolerantComparison<Translation3d> isWithin(double tolerance) {
5454
return new TolerantComparison<Translation3d>() {
5555
@Override
5656
public void of(Translation3d expected) {
57-
x().isWithin(tolerance).of(expected.getX());
58-
y().isWithin(tolerance).of(expected.getY());
59-
z().isWithin(tolerance).of(expected.getZ());
57+
if (expected == null) {
58+
throw new NullPointerException("Expected value cannot be null.");
59+
}
60+
checkDistance(expected).isWithin(tolerance).of(0);
6061
}
6162
};
6263
}
6364

65+
public TolerantComparison<Translation3d> isNotWithin(double tolerance) {
66+
return new TolerantComparison<Translation3d>() {
67+
@Override
68+
public void of(Translation3d expected) {
69+
if (expected == null) {
70+
throw new NullPointerException("Expected value cannot be null.");
71+
}
72+
checkDistance(expected).isNotWithin(tolerance).of(0);
73+
}
74+
};
75+
}
76+
77+
private DoubleSubject checkDistance(Translation3d expected) {
78+
if (expected == null) {
79+
throw new NullPointerException("Expected value cannot be null.");
80+
}
81+
return check("%s", actual).that(nonNullActual().getDistance(expected));
82+
}
83+
6484
public void isZero() {
6585
if (!Translation3d.kZero.equals(actual)) {
6686
failWithActual(simpleFact("expected to be zero"));

testing/src/test/java/com/team2813/lib2813/testing/truth/Translation2dSubjectTest.java

Lines changed: 43 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,16 +15,40 @@
1515
*/
1616
package com.team2813.lib2813.testing.truth;
1717

18+
import static com.google.common.truth.Truth.assertThat;
1819
import static org.junit.jupiter.api.Assertions.*;
1920

2021
import edu.wpi.first.math.geometry.Translation2d;
22+
import org.junit.jupiter.api.Test;
2123
import org.junit.jupiter.params.ParameterizedTest;
2224
import org.junit.jupiter.params.provider.ArgumentsSource;
2325

2426
/** Tests for {@link Translation2dSubject}. */
2527
class Translation2dSubjectTest {
2628
private static final Translation2d TRANSLATION = new Translation2d(7.353, 0.706);
2729

30+
@Test
31+
public void isWithin_nullActual_throws() {
32+
Translation2d actual = null;
33+
34+
AssertionError e =
35+
assertThrows(
36+
AssertionError.class,
37+
() -> Translation2dSubject.assertThat(actual).isWithin(0.01).of(TRANSLATION));
38+
assertThat(e).hasMessageThat().contains("non-null");
39+
}
40+
41+
@Test
42+
public void isWithin_nullExpected_throwsNullPointerException() {
43+
Translation2d expected = null;
44+
45+
NullPointerException e =
46+
assertThrows(
47+
NullPointerException.class,
48+
() -> Translation2dSubject.assertThat(TRANSLATION).isWithin(0.01).of(expected));
49+
assertThat(e).hasMessageThat().contains("cannot be null");
50+
}
51+
2852
@ParameterizedTest
2953
@ArgumentsSource(Pose2dComponent.TranslationsArgumentsProvider.class)
3054
public void isWithin_valueWithinTolerance_doesNotThrow(Pose2dComponent component) {
@@ -36,10 +60,28 @@ public void isWithin_valueWithinTolerance_doesNotThrow(Pose2dComponent component
3660
@ParameterizedTest
3761
@ArgumentsSource(Pose2dComponent.TranslationsArgumentsProvider.class)
3862
public void isWithin_valueNotWithinTolerance_throws(Pose2dComponent component) {
39-
Translation2d closeTranslation = component.add(TRANSLATION, 0.011);
63+
Translation2d closeTranslation = component.add(TRANSLATION, 0.016);
4064

4165
assertThrows(
4266
AssertionError.class,
4367
() -> Translation2dSubject.assertThat(closeTranslation).isWithin(0.01).of(TRANSLATION));
4468
}
69+
70+
@ParameterizedTest
71+
@ArgumentsSource(Pose2dComponent.TranslationsArgumentsProvider.class)
72+
public void isNotWithin_valueNotWithinTolerance_doesNotThrow(Pose2dComponent component) {
73+
Translation2d closeTranslation = component.add(TRANSLATION, 0.016);
74+
75+
Translation2dSubject.assertThat(closeTranslation).isNotWithin(0.01).of(TRANSLATION);
76+
}
77+
78+
@ParameterizedTest
79+
@ArgumentsSource(Pose2dComponent.TranslationsArgumentsProvider.class)
80+
public void isNotWithin_valueWithinTolerance_throws(Pose2dComponent component) {
81+
Translation2d closeTranslation = component.add(TRANSLATION, 0.009);
82+
83+
assertThrows(
84+
AssertionError.class,
85+
() -> Translation2dSubject.assertThat(closeTranslation).isNotWithin(0.01).of(TRANSLATION));
86+
}
4587
}

testing/src/test/java/com/team2813/lib2813/testing/truth/Translation3dSubjectTest.java

Lines changed: 43 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,16 +15,40 @@
1515
*/
1616
package com.team2813.lib2813.testing.truth;
1717

18+
import static com.google.common.truth.Truth.assertThat;
1819
import static org.junit.jupiter.api.Assertions.assertThrows;
1920

2021
import edu.wpi.first.math.geometry.Translation3d;
22+
import org.junit.jupiter.api.Test;
2123
import org.junit.jupiter.params.ParameterizedTest;
2224
import org.junit.jupiter.params.provider.ArgumentsSource;
2325

2426
/** Tests for {@link Translation3dSubject}. */
2527
class Translation3dSubjectTest {
2628
private static final Translation3d TRANSLATION = new Translation3d(7.353, 0.706, 42.00);
2729

30+
@Test
31+
public void isWithin_nullActual_throws() {
32+
Translation3d actual = null;
33+
34+
AssertionError e =
35+
assertThrows(
36+
AssertionError.class,
37+
() -> Translation3dSubject.assertThat(actual).isWithin(0.01).of(TRANSLATION));
38+
assertThat(e).hasMessageThat().contains("non-null");
39+
}
40+
41+
@Test
42+
public void isWithin_nullExpected_throwsNullPointerException() {
43+
Translation3d expected = null;
44+
45+
NullPointerException e =
46+
assertThrows(
47+
NullPointerException.class,
48+
() -> Translation3dSubject.assertThat(TRANSLATION).isWithin(0.01).of(expected));
49+
assertThat(e).hasMessageThat().contains("cannot be null");
50+
}
51+
2852
@ParameterizedTest
2953
@ArgumentsSource(Pose3dComponent.TranslationsArgumentsProvider.class)
3054
public void isWithin_valueWithinTolerance_doesNotThrow(Pose3dComponent component) {
@@ -36,10 +60,28 @@ public void isWithin_valueWithinTolerance_doesNotThrow(Pose3dComponent component
3660
@ParameterizedTest
3761
@ArgumentsSource(Pose3dComponent.TranslationsArgumentsProvider.class)
3862
public void isWithin_valueNotWithinTolerance_throws(Pose3dComponent component) {
39-
Translation3d closeTranslation = component.add(TRANSLATION, 0.011);
63+
Translation3d closeTranslation = component.add(TRANSLATION, 0.04);
4064

4165
assertThrows(
4266
AssertionError.class,
4367
() -> Translation3dSubject.assertThat(closeTranslation).isWithin(0.01).of(TRANSLATION));
4468
}
69+
70+
@ParameterizedTest
71+
@ArgumentsSource(Pose3dComponent.TranslationsArgumentsProvider.class)
72+
public void isNotWithin_valueNotWithinTolerance_doesNotThrow(Pose3dComponent component) {
73+
Translation3d closeTranslation = component.add(TRANSLATION, 0.016);
74+
75+
Translation3dSubject.assertThat(closeTranslation).isNotWithin(0.01).of(TRANSLATION);
76+
}
77+
78+
@ParameterizedTest
79+
@ArgumentsSource(Pose3dComponent.TranslationsArgumentsProvider.class)
80+
public void isNotWithin_valueWithinTolerance_throws(Pose3dComponent component) {
81+
Translation3d closeTranslation = component.add(TRANSLATION, 0.009);
82+
83+
assertThrows(
84+
AssertionError.class,
85+
() -> Translation3dSubject.assertThat(closeTranslation).isNotWithin(0.01).of(TRANSLATION));
86+
}
4587
}

0 commit comments

Comments
 (0)