Rotation2d

data class Rotation2d(val real: Double, val imag: Double)

Rotation \(\theta\) represented by the unit circle point \((\cos \theta, \sin \theta)\) or unit-modulus complex number \(\cos \theta + i \sin \theta\).

Advanced: Rotations in two dimensions comprise a Lie group referred to as SO(2). The terminology exp and log comes from the Lie theory, and this paper gives a targeted exposition of the key fundamentals.

Constructors

Link copied to clipboard
fun Rotation2d(real: Double, imag: Double)

Types

Link copied to clipboard
object Companion

Functions

Link copied to clipboard
fun inverse(): Rotation2d
Link copied to clipboard
fun log(): Double

Get the rotation as a normalized Double.

Link copied to clipboard
operator fun minus(r: Rotation2d): Double
Link copied to clipboard
operator fun plus(x: Double): Rotation2d
Link copied to clipboard
operator fun times(r: Rotation2d): Rotation2d
operator fun times(t: Twist2d): Twist2d
operator fun times(v: Vector2d): Vector2d
Link copied to clipboard
fun vec(): Vector2d

Properties

Link copied to clipboard
val imag: Double
Link copied to clipboard
val real: Double