Skip to content

Commit 28677bd

Browse files
committed
Move to Kotlin primary constructors and export geometry classes to JS
1 parent ad6cb55 commit 28677bd

File tree

7 files changed

+83
-74
lines changed

7 files changed

+83
-74
lines changed

build.gradle

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,11 @@ kotlin {
5151
implementation kotlin('test-annotations-common')
5252
}
5353
}
54+
all {
55+
languageSettings {
56+
useExperimentalAnnotation('kotlin.js.ExperimentalJsExport')
57+
}
58+
}
5459
}
5560
}
5661
test {

npm-publish.sh

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
1-
./gradlew compileKotlinJs
2-
./gradlew compileProductionExecutableKotlinJs
3-
./gradlew jsPublicPackageJson
1+
./gradlew compileKotlinJs || exit
2+
./gradlew compileProductionExecutableKotlinJs || exit
3+
./gradlew jsPublicPackageJson || exit
44

55
outputDir=build/compileSync/main/productionExecutable/kotlin
66
cp build/tmp/jsPublicPackageJson/package.json $outputDir/
7-
cd outputDir || exit
7+
cd $outputDir || exit
88
npm publish

src/commonMain/kotlin/com/team254/lib/geometry/Pose2d.kt

Lines changed: 23 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@ package com.team254.lib.geometry
33
import com.team254.lib.splinesutil.Util
44
import kotlin.js.ExperimentalJsExport
55
import kotlin.js.JsExport
6+
import kotlin.js.JsName
67
import kotlin.jvm.JvmStatic
78

89
/**
@@ -13,33 +14,27 @@ import kotlin.jvm.JvmStatic
1314
*/
1415
@ExperimentalJsExport
1516
@JsExport
16-
class Pose2d : IPose2d<Pose2d> {
17-
private val translation_: Translation2d
18-
private val rotation_: Rotation2d
19-
20-
constructor() {
21-
translation_ = Translation2d()
22-
rotation_ = Rotation2d()
23-
}
24-
25-
constructor(x: Double, y: Double, rotation: Rotation2d) {
26-
translation_ = Translation2d(x, y)
27-
rotation_ = rotation
28-
}
17+
class Pose2d(
18+
private val translation_ : Translation2d = Translation2d(),
19+
private val rotation_ : Rotation2d = Rotation2d()
20+
) : IPose2d<Pose2d> {
21+
22+
@JsName("fromXYRotation")
23+
constructor(x: Double, y: Double, rotation: Rotation2d) : this(
24+
Translation2d(x, y),
25+
rotation
26+
)
2927

28+
@JsName("fromTriple")
3029
constructor(x: Double, y: Double, rotation: Double): this(
3130
x, y, Rotation2d.fromDegrees(rotation)
3231
)
3332

34-
constructor(translation: Translation2d, rotation: Rotation2d) {
35-
translation_ = translation
36-
rotation_ = rotation
37-
}
38-
39-
constructor(other: Pose2d) {
40-
translation_ = Translation2d(other.translation_)
41-
rotation_ = Rotation2d(other.rotation_)
42-
}
33+
@JsName("copyOf")
34+
constructor(other: Pose2d) : this(
35+
Translation2d(other.translation_),
36+
Rotation2d(other.rotation_)
37+
)
4338

4439
override val translation: Translation2d
4540
get() = translation_
@@ -141,6 +136,12 @@ class Pose2d : IPose2d<Pose2d> {
141136
return Pose2d(Translation2d(translation.x(), -translation.y()), rotation.inverse())
142137
}
143138

139+
override fun hashCode(): Int {
140+
var result = translation_.hashCode()
141+
result = 31 * result + rotation_.hashCode()
142+
return result
143+
}
144+
144145
companion object {
145146
private val kIdentity = Pose2d()
146147

src/commonMain/kotlin/com/team254/lib/geometry/Rotation2d.kt

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ import com.team254.lib.splinesutil.toDegrees
77
import com.team254.lib.splinesutil.toRadians
88
import kotlin.js.ExperimentalJsExport
99
import kotlin.js.JsExport
10-
import kotlin.jvm.JvmOverloads
10+
import kotlin.js.JsName
1111
import kotlin.jvm.JvmStatic
1212

1313
/**
@@ -18,12 +18,15 @@ import kotlin.jvm.JvmStatic
1818
*/
1919
@ExperimentalJsExport
2020
@JsExport
21-
class Rotation2d : IRotation2d<Rotation2d> {
21+
class Rotation2d(
22+
x: Double = 1.0,
23+
y: Double = 0.0,
24+
normalize: Boolean = false
25+
) : IRotation2d<Rotation2d> {
2226
private val cos_angle_: Double
2327
private val sin_angle_: Double
2428

25-
@JvmOverloads
26-
constructor(x: Double = 1.0, y: Double = 0.0, normalize: Boolean = false) {
29+
init {
2730
if (normalize) {
2831
// From trig, we know that sin^2 + cos^2 == 1, but as we do math on this object we might accumulate rounding errors.
2932
// Normalizing forces us to re-scale the sin and cos to reset rounding errors.
@@ -41,11 +44,13 @@ class Rotation2d : IRotation2d<Rotation2d> {
4144
}
4245
}
4346

44-
constructor(other: Rotation2d) {
45-
cos_angle_ = other.cos_angle_
46-
sin_angle_ = other.sin_angle_
47-
}
47+
@JsName("copyOf")
48+
constructor(other: Rotation2d) : this(
49+
other.cos_angle_,
50+
other.sin_angle_
51+
)
4852

53+
@JsName("fromTranslation")
4954
constructor(direction: Translation2d, normalize: Boolean) : this(
5055
direction.x(),
5156
direction.y(),

src/commonMain/kotlin/com/team254/lib/geometry/Translation2d.kt

Lines changed: 30 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -4,56 +4,50 @@ import com.team254.lib.splinesutil.Util
44
import com.team254.lib.splinesutil.format
55
import kotlin.js.ExperimentalJsExport
66
import kotlin.js.JsExport
7+
import kotlin.js.JsName
78
import kotlin.jvm.JvmStatic
89

910
/**
1011
* A translation in a 2d coordinate frame. Translations are simply shifts in an (x, y) plane.
1112
*/
1213
@ExperimentalJsExport
1314
@JsExport
14-
class Translation2d : ITranslation2d<Translation2d> {
15-
private val x_: Double
16-
private val y_: Double
15+
class Translation2d(
16+
private val x: Double,
17+
private val y: Double
18+
) : ITranslation2d<Translation2d> {
1719

18-
constructor() {
19-
x_ = 0.0
20-
y_ = 0.0
21-
}
20+
@JsName("identity")
21+
constructor() : this(0.0, 0.0)
2222

23-
constructor(x: Double, y: Double) {
24-
x_ = x
25-
y_ = y
26-
}
23+
@JsName("copyOf")
24+
constructor(other: Translation2d) : this(other.x, other.y)
2725

28-
constructor(other: Translation2d) {
29-
x_ = other.x_
30-
y_ = other.y_
31-
}
32-
33-
constructor(start: Translation2d, end: Translation2d) {
34-
x_ = end.x_ - start.x_
35-
y_ = end.y_ - start.y_
36-
}
26+
@JsName("delta")
27+
constructor(start: Translation2d, end: Translation2d) : this(
28+
x = end.x - start.x,
29+
y = end.y - start.y
30+
)
3731

3832
/**
3933
* The "norm" of a transform is the Euclidean distance in x and y.
4034
*
4135
* @return sqrt(x ^ 2 + y ^ 2)
4236
*/
4337
fun norm(): Double {
44-
return kotlin.math.hypot(x_, y_)
38+
return kotlin.math.hypot(x, y)
4539
}
4640

4741
fun norm2(): Double {
48-
return x_ * x_ + y_ * y_
42+
return x * x + y * y
4943
}
5044

5145
fun x(): Double {
52-
return x_
46+
return x
5347
}
5448

5549
fun y(): Double {
56-
return y_
50+
return y
5751
}
5852

5953
/**
@@ -63,7 +57,7 @@ class Translation2d : ITranslation2d<Translation2d> {
6357
* @return The combined effect of translating by this object and the other.
6458
*/
6559
fun translateBy(other: Translation2d): Translation2d {
66-
return Translation2d(x_ + other.x_, y_ + other.y_)
60+
return Translation2d(x + other.x, y + other.y)
6761
}
6862

6963
/**
@@ -73,11 +67,11 @@ class Translation2d : ITranslation2d<Translation2d> {
7367
* @return This translation rotated by rotation.
7468
*/
7569
fun rotateBy(rotation: Rotation2d): Translation2d {
76-
return Translation2d(x_ * rotation.cos() - y_ * rotation.sin(), x_ * rotation.sin() + y_ * rotation.cos())
70+
return Translation2d(x * rotation.cos() - y * rotation.sin(), x * rotation.sin() + y * rotation.cos())
7771
}
7872

7973
fun direction(): Rotation2d {
80-
return Rotation2d(x_, y_, true)
74+
return Rotation2d(x, y, true)
8175
}
8276

8377
/**
@@ -86,7 +80,7 @@ class Translation2d : ITranslation2d<Translation2d> {
8680
* @return Translation by -x and -y.
8781
*/
8882
fun inverse(): Translation2d {
89-
return Translation2d(-x_, -y_)
83+
return Translation2d(-x, -y)
9084
}
9185

9286
override fun interpolate(other: Translation2d, x: Double): Translation2d {
@@ -99,23 +93,23 @@ class Translation2d : ITranslation2d<Translation2d> {
9993
}
10094

10195
fun extrapolate(other: Translation2d, x: Double): Translation2d {
102-
return Translation2d(x * (other.x_ - x_) + x_, x * (other.y_ - y_) + y_)
96+
return Translation2d(x * (other.x - x) + x, x * (other.y - y) + y)
10397
}
10498

10599
fun scale(s: Double): Translation2d {
106-
return Translation2d(x_ * s, y_ * s)
100+
return Translation2d(x * s, y * s)
107101
}
108102

109103
fun epsilonEquals(other: Translation2d, epsilon: Double): Boolean {
110104
return Util.epsilonEquals(x(), other.x(), epsilon) && Util.epsilonEquals(y(), other.y(), epsilon)
111105
}
112106

113107
override fun toString(): String {
114-
return "(" + x_.format(3) + "," + y_.format(3) + ")"
108+
return "(" + x.format(3) + "," + y.format(3) + ")"
115109
}
116110

117111
override fun toCSV(): String {
118-
return x_.format(3) + "," + y_.format(3)
112+
return x.format(3) + "," + y.format(3)
119113
}
120114

121115
override fun distance(other: Translation2d): Double {
@@ -127,8 +121,8 @@ class Translation2d : ITranslation2d<Translation2d> {
127121
}
128122

129123
override fun hashCode(): Int {
130-
var result = x_.hashCode()
131-
result = 31 * result + y_.hashCode()
124+
var result = x.hashCode()
125+
result = 31 * result + y.hashCode()
132126
return result
133127
}
134128

@@ -156,7 +150,7 @@ class Translation2d : ITranslation2d<Translation2d> {
156150

157151
@JvmStatic
158152
fun dot(a: Translation2d, b: Translation2d): Double {
159-
return a.x_ * b.x_ + a.y_ * b.y_
153+
return a.x * b.x + a.y * b.y
160154
}
161155

162156
@JvmStatic
@@ -176,7 +170,7 @@ class Translation2d : ITranslation2d<Translation2d> {
176170

177171
@JvmStatic
178172
fun cross(a: Translation2d, b: Translation2d): Double {
179-
return a.x_ * b.y_ - a.y_ * b.x_
173+
return a.x * b.y - a.y * b.x
180174
}
181175
}
182176
}

src/commonMain/kotlin/com/team254/lib/splinesutil/Util.kt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,8 @@
11
package com.team254.lib.splinesutil
22

3+
import kotlin.js.ExperimentalJsExport
4+
import kotlin.js.JsExport
5+
import kotlin.js.JsName
36
import kotlin.jvm.JvmOverloads
47
import kotlin.math.PI
58

@@ -55,10 +58,14 @@ object Util {
5558
}
5659
}
5760

61+
@ExperimentalJsExport
62+
@JsName("toDegrees")
5863
fun toDegrees(radians: Double): Double {
5964
return radians * (180.0 / PI)
6065
}
6166

67+
@ExperimentalJsExport
68+
@JsName("toRadians")
6269
fun toRadians(degrees: Double): Double {
6370
return degrees * (PI / 180.0)
6471
}

src/jsMain/kotlin/main.kt

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,10 +9,7 @@ external fun decodeURIComponent(encodedURI: String): String
99
@ExperimentalJsExport
1010
@JsExport
1111
@JsName("calcSplines")
12-
fun calcSplines(pointData: Array<DoubleArray>): String {
13-
val points = pointData.map { point ->
14-
Pose2d(point[0], point[1], point[2])
15-
}
12+
fun calcSplines(points: Array<Pose2d>): String {
1613
val mQuinticHermiteSplines: ArrayList<QuinticHermiteSpline> =
1714
ArrayList()
1815
val mSplines: ArrayList<Spline> = ArrayList()

0 commit comments

Comments
 (0)