Pose2d

data class Pose2d(val trans: Vector2d, val rot: Rotation2d)

2D rigid transform comprised of rot followed by trans.

The pose destPoseSource denotes the transform from frame Source into frame Dest. It can be applied with times() to change the coordinates of xSource into xDest where x is a vector, twist, or even another pose: xDest = destPoseSource * xSource. The awkward names take some getting used to, but they avoid many routine errors.

Transforms into the world frame are common enough to warrant a shorthand. The pose worldPoseSource can be shortened to poseSource for any frame Source.

Advanced: Transforms in two dimensions comprise a Lie group referred to as SE(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 Pose2d(trans: Vector2d, rot: Double)
Link copied to clipboard
fun Pose2d(    transX: Double,     transY: Double,     rot: Double)
Link copied to clipboard
fun Pose2d(trans: Vector2d, rot: Rotation2d)

Types

Link copied to clipboard
object Companion

Functions

Link copied to clipboard
fun inverse(): Pose2d
Link copied to clipboard
fun log(): Twist2dIncr
Link copied to clipboard
operator fun minus(t: Pose2d): Twist2dIncr
Link copied to clipboard
fun minusExp(t: Pose2d): Pose2d
Link copied to clipboard
operator fun plus(t: Twist2dIncr): Pose2d
Link copied to clipboard
operator fun times(t: Pose2d): Pose2d
operator fun times(t: Twist2d): Twist2d
operator fun times(v: Vector2d): Vector2d

Properties

Link copied to clipboard
val rot: Rotation2d
Link copied to clipboard
val trans: Vector2d