public class Twist extends SpatialVector
Modifier and Type | Field and Description |
---|---|
Vector3d |
v
Translational velocity
|
Vector3d |
w
Rotational (angular) velocity
|
static Twist |
ZERO |
Constructor and Description |
---|
Twist()
Creates a Twist and initializes its contents to zero.
|
Twist(double vx,
double vy,
double vz,
double wx,
double wy,
double wz)
Creates a Twist and initializes its components to the specified values.
|
Twist(Twist tw)
Creates a Twist and initializes its contents to the values of an existing
Twist.
|
Twist(Vector3d v,
Vector3d w)
Creates a Twist and initializes its components to the specified values.
|
Modifier and Type | Method and Description |
---|---|
void |
absolute(Twist tw1)
Sets the elements of this twist to their absolute values.
|
void |
add(Twist tw1)
Adds this twist to tw1 and places the result in this twist.
|
void |
add(Twist tw1,
Twist tw2)
Adds twist tw1 to tw2 and places the result in this twist.
|
Twist |
clone() |
void |
combine(double s1,
Twist tw1,
double s2,
Twist tw2)
Computes s1 tw1 + s2 tw2 and places the result in this twist.
|
void |
extrapolateTransform(RigidTransform3d X,
double h)
Extrapolates a rigid spatial transformation by an increment corresponding
to this Twist scaled by h.
|
void |
extrapolateTransformWorld(RigidTransform3d X,
double h)
Extrapolates a rigid spatial transformation by an increment corresponding
to this Twist scaled by h.
|
void |
interpolate(double s,
Twist tw1)
Computes the interpolation (1-s) this + s tw1 and places the result in
this twist.
|
void |
interpolate(Twist tw1,
double s,
Twist tw2)
Computes the interpolation (1-s) tw1 + s tw2 and places the result in this
twist.
|
void |
inverseTransform(RigidTransform3d X,
Twist tw1)
Applies an inverse rigid spatial transformation to the twist tw1, and
places the result in this twist.
|
void |
inverseTransform(RotationMatrix3d R,
Twist tw1)
Applies an inverse rotational transformation to the twist tw1, and stores
the result in this twist.
|
void |
negate(Twist tw1)
Sets this twist to the negative of tw1.
|
void |
normalize(Twist tw1)
Computes a unit twist in the direction of tw1 and places the result in
this twist.
|
void |
scale(double s,
Twist tw1)
Scales the elements of twist tw1 by s and places the results in this
twist.
|
void |
scaledAdd(double s,
Twist tw1)
Computes s tw1 and adds the result to this twist.
|
void |
scaledAdd(double s,
Twist tw1,
Twist tw2)
Computes s tw1 + tw2 and places the result in this twist.
|
void |
set(double vx,
double vy,
double vz,
double wx,
double wy,
double wz)
Sets the values of this twist to the specified component values.
|
void |
set(RigidTransform3d X)
Sets this twist to a representation of a rigid spatial transformation.
|
void |
set(Twist tw)
Sets the values of this twist to those of twist tw.
|
void |
set(Vector3d v,
Vector3d w)
Sets the values of this twist to the specified component values.
|
void |
setTransform(RigidTransform3d X)
Sets a rigid spatial transformation to correspond to this Twist.
|
void |
sub(Twist tw1)
Subtracts tw1 from this twist and places the result in this twist.
|
void |
sub(Twist tw1,
Twist tw2)
Subtracts twist tw1 from tw2 and places the result in this twist.
|
void |
transform(RigidTransform3d X,
Twist tw1)
Applies a rigid spatial transformation to the twist tw1, and places the
result in this twist.
|
void |
transform(RotationMatrix3d R,
Twist tw1)
Applies a rotational transformation to the twist tw1 and stores the result
in this twist.
|
absolute, cross, dot, epsilonEquals, equals, get, get, get, get, infinityNorm, inverseTransform, inverseTransform, isContravariant, maxElement, minElement, mul, negate, norm, normalize, normSquared, oneNorm, scale, set, set, set, set, setRandom, setRandom, setRandom, setZero, size, toString, transform, transform
containsNaN, copy, copyAndAdd, copyAndNegate, copyAndScale, copyAndSub, copyAndSubLeft, dot, epsilonEquals, equals, get, getDefaultFormat, hasInf, hasNaN, isColumnVectorStringsVertical, isFixedSize, isRowVector, isWritable, scan, scan, set, set, setColumnVectorStringsVertical, setDefaultFormat, setRowVector, setSize, toString, toString, write, write, write, writeToFile
public static final Twist ZERO
public Vector3d v
public Vector3d w
public Twist()
public Twist(Twist tw)
tw
- twist whose values are to be copiedpublic Twist(double vx, double vy, double vz, double wx, double wy, double wz)
vx
- translational velocity x componentvy
- translational velocity y componentvz
- translational velocity z componentwx
- rotational velocity x componentwy
- rotational velocity y componentwz
- rotational velocity z componentpublic void setTransform(RigidTransform3d X)
X
- rigid transformextrapolateTransform(maspack.matrix.RigidTransform3d, double)
public void extrapolateTransform(RigidTransform3d X, double h)
RigidTransform3d Xinc = new RigidTransform3d(); Twist inc = new Twist(); inc.scale (h, this); Xinc.setTransform (inc); X.mul (Xinc);
X
- rigid transform to extrapolateh
- scaling factor used to compute increment from this twistsetTransform(maspack.matrix.RigidTransform3d)
public void extrapolateTransformWorld(RigidTransform3d X, double h)
X
- rigid transform to extrapolateh
- scaling factor used to compute increment from this twistsetTransform(maspack.matrix.RigidTransform3d)
public void set(double vx, double vy, double vz, double wx, double wy, double wz)
vx
- translational velocity x componentvy
- translational velocity y componentvz
- translational velocity z componentwx
- rotational velocity x componentwy
- rotational velocity y componentwz
- rotational velocity z componentpublic void set(Vector3d v, Vector3d w)
v
- translational velocityw
- rotational velocitypublic void set(Twist tw)
tw
- twist whose values are to be copiedpublic void set(RigidTransform3d X)
X
- rigid transformpublic void add(Twist tw1, Twist tw2)
tw1
- left-hand twisttw2
- right-hand twistpublic void add(Twist tw1)
tw1
- right-hand twistpublic void sub(Twist tw1, Twist tw2)
tw1
- left-hand twisttw2
- right-hand twistpublic void sub(Twist tw1)
tw1
- right-hand twistpublic void negate(Twist tw1)
tw1
- twist to negatepublic void scale(double s, Twist tw1)
s
- scaling factortw1
- twist to be scaledpublic void interpolate(Twist tw1, double s, Twist tw2)
tw1
- left-hand twists
- interpolation factortw2
- right-hand twistpublic void interpolate(double s, Twist tw1)
s
- interpolation factortw1
- right-hand twistpublic void scaledAdd(double s, Twist tw1, Twist tw2)
s
- scaling factortw1
- twist to be scaledtw2
- twist to be addedpublic void scaledAdd(double s, Twist tw1)
s
- scaling factortw1
- twist to be scaled and addedpublic void combine(double s1, Twist tw1, double s2, Twist tw2)
s1
- left-hand scaling factortw1
- left-hand twists2
- right-hand scaling factortw2
- right-hand twistpublic void normalize(Twist tw1)
tw1
- twist to normalizepublic void absolute(Twist tw1)
public void transform(RotationMatrix3d R, Twist tw1)
R
- rotational transformation matrixtw1
- twist to transformpublic void inverseTransform(RotationMatrix3d R, Twist tw1)
R
- rotational transformation matrixtw1
- twist to transformpublic void transform(RigidTransform3d X, Twist tw1)
X
- rigid spatial transformationtw1
- twist to be transformedpublic void inverseTransform(RigidTransform3d X, Twist tw1)
X
- rigid spatial transformationtw1
- twist to be transformedpublic Twist clone()
clone
in interface Clonable
clone
in class SpatialVector