Pose2d

data class Pose2d(val position: Vector2d, val heading: Rotation2d)

2D rigid transform comprised of heading followed by position.

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
constructor(position: Vector2d, heading: Double)
constructor(positionX: Double, positionY: Double, heading: Double)
constructor(position: Vector2d, heading: Rotation2d)

Types

Link copied to clipboard
object Companion

Properties

Link copied to clipboard
Link copied to clipboard

Functions

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