|
||||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | |||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Objectus.ihmc.utilities.math.geometry.FrameVector
public class FrameVector
One of the main goals of this class is to check, at runtime, that operations on vectors occur within the same Frame. This method checks for one Vector argument.
Field Summary | |
---|---|
static boolean |
LOUD_WARNING
|
Constructor Summary | |
---|---|
FrameVector()
|
|
FrameVector(FramePoint framePoint)
FrameVector Turns a FramePoint into a FrameVector. |
|
FrameVector(FramePoint framePoint,
java.lang.String name)
|
|
FrameVector(FrameVector frameVector)
FrameVector A normal vector associated with a specific reference frame |
|
FrameVector(FrameVector frameVector,
java.lang.String name)
|
|
FrameVector(ReferenceFrame referenceFrame)
FrameVector A normal vector associated with a specific reference frame |
|
FrameVector(ReferenceFrame referenceFrame,
double[] vector)
|
|
FrameVector(ReferenceFrame referenceFrame,
double[] vector,
java.lang.String name)
|
|
FrameVector(ReferenceFrame referenceFrame,
double x,
double y,
double z)
FrameVector A normal vector associated with a specific reference frame. |
|
FrameVector(ReferenceFrame referenceFrame,
double x,
double y,
double z,
java.lang.String name)
|
|
FrameVector(ReferenceFrame referenceFrame,
java.lang.String name)
|
|
FrameVector(ReferenceFrame referenceFrame,
javax.vecmath.Tuple3d tuple)
FrameVector A normal vector associated with a specific reference frame |
|
FrameVector(ReferenceFrame referenceFrame,
javax.vecmath.Tuple3d tuple,
java.lang.String name)
|
Method Summary | |
---|---|
void |
add(FramePoint framePoint)
|
void |
add(FrameVector frameVector)
|
void |
add(FrameVector vector1,
FrameVector vector2)
|
double |
angle(FrameVector frameVector)
|
void |
applyTransform(javax.media.j3d.Transform3D transform)
|
FrameVector |
applyTransformCopy(javax.media.j3d.Transform3D transform)
|
void |
changeFrame(ReferenceFrame desiredFrame)
Changes frame of this FrameVector to the given ReferenceFrame. |
FrameVector |
changeFrameCopy(ReferenceFrame desiredFrame)
Changes frame of this FrameVector to the given ReferenceFrame and returns a copy. |
void |
changeFrameUsingTransform(ReferenceFrame desiredFrame,
javax.media.j3d.Transform3D transformToNewFrame)
Changes frame of this FramePoint to the given ReferenceFrame, using the given Transform3D. |
void |
checkForNaN()
|
void |
checkReferenceFrameMatch(ReferenceFrame frame)
|
void |
checkReferenceFrameMatch(ReferenceFrameHolder referenceFrameHolder)
Makes sure that the FrameVector argument has the same Frame as the current FrameVector. |
boolean |
containsNaN()
|
void |
cross(FramePoint f1,
FramePoint f2)
|
void |
cross(FramePoint f1,
FrameVector f2)
|
void |
cross(FrameVector f1,
FramePoint f2)
|
void |
cross(FrameVector f1,
FrameVector f2)
|
double |
dot(FrameVector frameVector)
|
boolean |
epsilonEquals(FramePoint framePoint,
double threshold)
|
boolean |
epsilonEquals(FrameVector frameVector,
double threshold)
|
double |
get(Direction direction)
|
com.mathworks.jama.Matrix |
getMatrix()
|
java.lang.String |
getName()
|
ReferenceFrame |
getReferenceFrame()
Returns this FrameVectors ReferenceFrame. |
javax.vecmath.Vector3d |
getVector()
Retrieves the vector inside this FrameVector |
void |
getVector(javax.vecmath.Tuple3d tuple3dToPack)
|
javax.vecmath.Vector3d |
getVectorCopy()
Returns a deep copy of the vector inside this FrameVector. |
double |
getX()
|
double |
getY()
|
double |
getZ()
|
double |
length()
|
double |
lengthSquared()
|
void |
negate()
|
void |
normalize()
|
void |
packMatrix(org.ejml.data.DenseMatrix64F matrix,
int startRow)
|
void |
printOutFrameVector(java.lang.String varaibleName)
|
void |
scale(double scaleFactor)
|
void |
scale(double scaleFactor,
FramePoint point1)
Sets the value of this tuple to the scalar multiplication of vertor1 (this = s * t1). |
void |
scale(double scaleFactor,
FrameVector vector1)
Sets the value of this tuple to the scalar multiplication of vertor1 (this = s * t1). |
void |
scaleAdd(double scaleFactor,
FramePoint point1)
Sets the value of this tuple to the scalar multiplication of itself and then adds tuple t1 (this = s*this + t1). |
void |
scaleAdd(double scaleFactor,
FramePoint point1,
FramePoint point2)
Sets the value of this tuple to the scalar multiplication of tuple t1 and then adds tuple t2 (this = s*v1 + t2). |
void |
scaleAdd(double scaleFactor,
FramePoint point1,
FrameVector vector2)
Sets the value of this tuple to the scalar multiplication of tuple t1 and then adds tuple t2 (this = s*v1 + t2). |
void |
scaleAdd(double scaleFactor,
FrameVector vector1)
Sets the value of this tuple to the scalar multiplication of itself and then adds tuple t1 (this = s*this + t1). |
void |
scaleAdd(double scaleFactor,
FrameVector vector1,
FramePoint point2)
Sets the value of this tuple to the scalar multiplication of tuple t1 and then adds tuple t2 (this = s*v1 + t2). |
void |
scaleAdd(double scaleFactor,
FrameVector vector1,
FrameVector vector2)
Sets the value of this tuple to the scalar multiplication of tuple t1 and then adds tuple t2 (this = s*v1 + t2) |
void |
set(Direction direction,
double value)
|
void |
set(double x,
double y,
double z)
|
void |
set(FramePoint framePoint)
|
void |
set(FrameVector frameVector)
|
void |
set(ReferenceFrame referenceFrame,
double x,
double y,
double z)
|
void |
set(ReferenceFrame referenceFrame,
javax.vecmath.Vector3d vector)
|
void |
set(javax.vecmath.Vector3d vector)
|
void |
setAndChangeFrame(FramePoint framePoint)
|
void |
setAndChangeFrame(FrameVector frameVector)
|
void |
setAndChangeFrame(ReferenceFrame referenceFrame,
javax.vecmath.Vector3d vector)
|
void |
setName(java.lang.String name)
|
void |
setToZero(ReferenceFrame referenceFrame)
|
void |
setX(double x)
|
void |
setY(double y)
|
void |
setZ(double z)
|
void |
sub(FramePoint framePoint)
|
void |
sub(FramePoint point1,
FramePoint point2)
|
void |
sub(FrameVector frameVector)
|
void |
sub(FrameVector vector1,
FrameVector vector2)
|
double[] |
toArray()
|
static double[] |
toArray(FrameVector[] frameVectors)
|
FrameVector2d |
toFrameVector2d()
Creates a new FrameVector2d based on the x and y components of this FrameVector |
java.lang.String |
toString()
toString String representation of a FrameVector (x,y,z):reference frame name |
void |
weightedAverage(FrameVector vector1,
FrameVector vector2,
double weightedAverage)
Sets this vector to be the weighted average of the two input vectors. |
Methods inherited from class java.lang.Object |
---|
equals, getClass, hashCode, notify, notifyAll, wait, wait, wait |
Field Detail |
---|
public static boolean LOUD_WARNING
Constructor Detail |
---|
public FrameVector(ReferenceFrame referenceFrame, javax.vecmath.Tuple3d tuple)
referenceFrame
- Framevector
- Vector3dpublic FrameVector(ReferenceFrame referenceFrame, javax.vecmath.Tuple3d tuple, java.lang.String name)
public FrameVector(ReferenceFrame referenceFrame, double[] vector)
public FrameVector(ReferenceFrame referenceFrame, double[] vector, java.lang.String name)
public FrameVector(ReferenceFrame referenceFrame)
referenceFrame
- Framepublic FrameVector(ReferenceFrame referenceFrame, java.lang.String name)
public FrameVector(FrameVector frameVector)
referenceFrame
- Framevector
- Vector3dpublic FrameVector(FrameVector frameVector, java.lang.String name)
public FrameVector(FramePoint framePoint)
referenceFrame
- Framevector
- Vector3dpublic FrameVector(FramePoint framePoint, java.lang.String name)
public FrameVector(ReferenceFrame referenceFrame, double x, double y, double z)
referenceFrame
- Framex
- doubley
- doublez
- doublepublic FrameVector(ReferenceFrame referenceFrame, double x, double y, double z, java.lang.String name)
public FrameVector()
Method Detail |
---|
public void setName(java.lang.String name)
public java.lang.String getName()
public void changeFrameUsingTransform(ReferenceFrame desiredFrame, javax.media.j3d.Transform3D transformToNewFrame)
desiredFrame
- ReferenceFrame to change the FramePoint into.transformToNewFrame
- Transform3D from the current frame to the new desiredFramepublic ReferenceFrame getReferenceFrame()
getReferenceFrame
in interface ReferenceFrameHolder
public javax.vecmath.Vector3d getVector()
public void getVector(javax.vecmath.Tuple3d tuple3dToPack)
public javax.vecmath.Vector3d getVectorCopy()
public FrameVector changeFrameCopy(ReferenceFrame desiredFrame)
changeFrameCopy
in interface ReferenceFrameHolder
desiredFrame
- ReferenceFrame to change the FrameVector into.
public void changeFrame(ReferenceFrame desiredFrame)
desiredFrame
- ReferenceFrame to change the FrameVector into.public void negate()
public double getX()
public double getY()
public double getZ()
public double get(Direction direction)
public void set(ReferenceFrame referenceFrame, double x, double y, double z)
public void set(double x, double y, double z)
public void setX(double x)
public void setY(double y)
public void setZ(double z)
public void set(Direction direction, double value)
public void scale(double scaleFactor)
public double[] toArray()
public FrameVector2d toFrameVector2d()
public void scale(double scaleFactor, FrameVector vector1)
scaleFactor
- doublevector1
- FrameVectorpublic void scale(double scaleFactor, FramePoint point1)
scaleFactor
- doublepoint1
- FramePointpublic void scaleAdd(double scaleFactor, FrameVector vector1, FrameVector vector2)
scaleFactor
- doublevector1
- FrameVectorvector2
- FrameVectorpublic void scaleAdd(double scaleFactor, FrameVector vector1, FramePoint point2)
scaleFactor
- doublevector1
- FrameVectorpoint2
- FramePointpublic void scaleAdd(double scaleFactor, FramePoint point1, FrameVector vector2)
scaleFactor
- doublepoint1
- FramePointvector2
- FrameVectorpublic void scaleAdd(double scaleFactor, FramePoint point1, FramePoint point2)
scaleFactor
- doublepoint1
- FramePointpoint2
- FramePointpublic void scaleAdd(double scaleFactor, FrameVector vector1)
scaleFactor
- doublevector1
- FrameVectorpublic void scaleAdd(double scaleFactor, FramePoint point1)
scaleFactor
- doublepoint1
- FramePointpublic void checkReferenceFrameMatch(ReferenceFrameHolder referenceFrameHolder)
checkReferenceFrameMatch
in interface ReferenceFrameHolder
frameVector
- FrameVector
ReferenceFrameMismatchException
public void checkReferenceFrameMatch(ReferenceFrame frame) throws ReferenceFrameMismatchException
checkReferenceFrameMatch
in interface ReferenceFrameHolder
ReferenceFrameMismatchException
public void checkForNaN()
public boolean containsNaN()
public void add(FrameVector frameVector)
public void add(FramePoint framePoint)
public void add(FrameVector vector1, FrameVector vector2)
public void setToZero(ReferenceFrame referenceFrame)
public void sub(FrameVector frameVector)
public void sub(FramePoint framePoint)
public void sub(FramePoint point1, FramePoint point2)
public void sub(FrameVector vector1, FrameVector vector2)
public double dot(FrameVector frameVector)
public double angle(FrameVector frameVector)
public void cross(FrameVector f1, FrameVector f2)
public void cross(FrameVector f1, FramePoint f2)
public void cross(FramePoint f1, FrameVector f2)
public void cross(FramePoint f1, FramePoint f2)
public void setAndChangeFrame(FrameVector frameVector)
public void set(FrameVector frameVector)
public void set(javax.vecmath.Vector3d vector)
public void set(ReferenceFrame referenceFrame, javax.vecmath.Vector3d vector)
public void setAndChangeFrame(FramePoint framePoint)
public void set(FramePoint framePoint)
public void normalize()
public double length()
public double lengthSquared()
public void applyTransform(javax.media.j3d.Transform3D transform)
public FrameVector applyTransformCopy(javax.media.j3d.Transform3D transform)
public static double[] toArray(FrameVector[] frameVectors)
public void weightedAverage(FrameVector vector1, FrameVector vector2, double weightedAverage)
vector1
- FramePointvector2
- FramePointweightedAverage
- double
ReferenceFrameMismatchException
public java.lang.String toString()
toString
in class java.lang.Object
public void printOutFrameVector(java.lang.String varaibleName)
public boolean epsilonEquals(FramePoint framePoint, double threshold)
public boolean epsilonEquals(FrameVector frameVector, double threshold)
public com.mathworks.jama.Matrix getMatrix()
public void packMatrix(org.ejml.data.DenseMatrix64F matrix, int startRow)
public void setAndChangeFrame(ReferenceFrame referenceFrame, javax.vecmath.Vector3d vector)
|
||||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | |||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |