core
core
com.
acmerobotics.
roadrunner
Accel
Constraint
Angular
Vel
Constraint
Arclength
Arclength
Reparam
Curve2
backward
Profile()
Cancelable
Profile
clamp()
Composite
Accel
Constraint
Composite
Pose
Path
Composite
Position
Path
Composite
Vel
Constraint
Constant
Heading
Path
Constant
Path
Builder
constant
Profile()
Constant
Trajectory
Builder
Displacement
Profile
Displacement
Trajectory
Dual
Num
forward
Profile()
Heading
Path
Heading
Pose
Path
Holonomic
Controller
integral
Scan()
Integral
Scan
Result
Internal
lerp()
Line
Linear
Heading
Path
Mecanum
Kinematics
merge()
Min
Max
Min
Vel
Constraint
Motor
Feedforward
Path
Builder
Pose2d
Pose2d
Dual
Pose
Path
Pose
Path
Builder
Position
Path
Position
Path
Builder
Position
Path
View
profile()
Profile
Accel
Constraint
project()
Quintic
Spline1
Quintic
Spline2
Ramsete
Controller
range()
range
Middle()
Restricted
Path
Builder
Restricted
Pose
Path
Builder
Restricted
Trajectory
Builder
Rotation2d
Rotation2d
Dual
Safe
Path
Builder
Safe
Pose
Path
Builder
Safe
Trajectory
Builder
snz()
Spline
Heading
Path
Tangent
Path
Tangent
Path
Builder
Tangent
Trajectory
Builder
Tank
Kinematics
Time
Time
Profile
Time
Trajectory
Trajectory
Trajectory
Builder
Translational
Vel
Constraint
Twist2d
Twist2d
Dual
Twist2d
Incr
Twist2d
Incr
Dual
Vector2d
Vector2d
Dual
Vel
Constraint
core
/
com.acmerobotics.roadrunner
/
Rotation2dDual
Rotation2d
Dual
data
class
Rotation2dDual
<
Param
>
(
val
real
:
DualNum
<
Param
>
,
val
imag
:
DualNum
<
Param
>
)
Content copied to clipboard
Dual version of
Rotation2d
.
Types
Constructors
Functions
Properties
Constructors
Rotation2d
Dual
Link copied to clipboard
fun
<
Param
>
Rotation2dDual
(
real
:
DualNum
<
Param
>
,
imag
:
DualNum
<
Param
>
)
Content copied to clipboard
Types
Companion
Link copied to clipboard
object
Companion
Content copied to clipboard
Functions
inverse
Link copied to clipboard
fun
inverse
(
)
:
Rotation2dDual
<
Param
>
Content copied to clipboard
plus
Link copied to clipboard
operator
fun
plus
(
d
:
DualNum
<
Param
>
)
:
Rotation2dDual
<
Param
>
Content copied to clipboard
operator
fun
plus
(
x
:
Double
)
:
Rotation2dDual
<
Param
>
Content copied to clipboard
reparam
Link copied to clipboard
fun
<
NewParam
>
reparam
(
oldParam
:
DualNum
<
NewParam
>
)
:
Rotation2dDual
<
NewParam
>
Content copied to clipboard
size
Link copied to clipboard
fun
size
(
)
:
Int
Content copied to clipboard
times
Link copied to clipboard
operator
fun
times
(
t
:
Pose2d
)
:
Pose2dDual
<
Param
>
Content copied to clipboard
operator
fun
times
(
r
:
Rotation2d
)
:
Rotation2dDual
<
Param
>
Content copied to clipboard
operator
fun
times
(
r
:
Rotation2dDual
<
Param
>
)
:
Rotation2dDual
<
Param
>
Content copied to clipboard
operator
fun
times
(
t
:
Twist2dDual
<
Param
>
)
:
Twist2dDual
<
Param
>
Content copied to clipboard
operator
fun
times
(
v
:
Vector2d
)
:
Vector2dDual
<
Param
>
Content copied to clipboard
operator
fun
times
(
v
:
Vector2dDual
<
Param
>
)
:
Vector2dDual
<
Param
>
Content copied to clipboard
value
Link copied to clipboard
fun
value
(
)
:
Rotation2d
Content copied to clipboard
velocity
Link copied to clipboard
fun
velocity
(
)
:
DualNum
<
Param
>
Content copied to clipboard
with
Rot
Link copied to clipboard
fun
withRot
(
r
:
Rotation2d
)
:
Rotation2dDual
<
Param
>
Content copied to clipboard
Properties
imag
Link copied to clipboard
@
JvmField
val
imag
:
DualNum
<
Param
>
Content copied to clipboard
real
Link copied to clipboard
@
JvmField
val
real
:
DualNum
<
Param
>
Content copied to clipboard