|
||||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | |||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Objectus.ihmc.utilities.math.geometry.FramePoint
public class FramePoint
Constructor Summary | |
---|---|
FramePoint()
|
|
FramePoint(FramePoint framePoint)
|
|
FramePoint(FramePoint framePoint,
java.lang.String name)
|
|
FramePoint(FrameVector frameVector)
|
|
FramePoint(FrameVector frameVector,
java.lang.String name)
|
|
FramePoint(ReferenceFrame referenceFrame)
FramePoint A normal point associated with a specific reference frame |
|
FramePoint(ReferenceFrame referenceFrame,
double[] position)
|
|
FramePoint(ReferenceFrame referenceFrame,
double[] position,
java.lang.String name)
|
|
FramePoint(ReferenceFrame referenceFrame,
double x,
double y,
double z)
FramePoint A normal point associated with a specific reference frame. |
|
FramePoint(ReferenceFrame referenceFrame,
double x,
double y,
double z,
java.lang.String name)
|
|
FramePoint(ReferenceFrame referenceFrame,
java.lang.String name)
|
|
FramePoint(ReferenceFrame referenceFrame,
javax.vecmath.Tuple3d position)
|
|
FramePoint(ReferenceFrame referenceFrame,
javax.vecmath.Tuple3d position,
java.lang.String name)
|
Method Summary | |
---|---|
void |
add(FramePoint framePoint)
|
void |
add(FramePoint point1,
FramePoint point2)
|
void |
add(FramePoint point1,
FrameVector vector2)
|
void |
add(FrameVector frameVector)
|
void |
add(FrameVector vector1,
FramePoint point2)
|
void |
add(javax.vecmath.Tuple3d tuple3d)
|
void |
applyTransform(javax.media.j3d.Transform3D transform)
|
FramePoint |
applyTransformCopy(javax.media.j3d.Transform3D transform3D)
|
static FramePoint |
average(java.util.List<? extends FramePoint> framePoints)
|
void |
changeFrame(ReferenceFrame desiredFrame)
Changes frame of this FramePoint to the given ReferenceFrame. |
FramePoint |
changeFrameCopy(ReferenceFrame desiredFrame)
Changes frame of this FramePoint to the given ReferenceFrame and returns a copy. |
static FramePoint[] |
changeFrameCopyBatch(FramePoint[] framePoints,
ReferenceFrame desiredFrame)
|
void |
changeFrameUsingTransform(ReferenceFrame desiredFrame,
javax.media.j3d.Transform3D transformToNewFrame)
Changes frame of this FramePoint to the given ReferenceFrame, using the given Transform3D. |
FramePoint |
changeFrameUsingTransformCopy(ReferenceFrame desiredFrame,
javax.media.j3d.Transform3D transformToNewFrame)
Changes frame of this FramePoint to the given ReferenceFrame, using the given Transform3D and returns a copy. |
void |
checkForNaN()
|
void |
checkReferenceFrameMatch(ReferenceFrame frame)
|
void |
checkReferenceFrameMatch(ReferenceFrameHolder referenceFrameHolder)
|
boolean |
containsNaN()
|
double |
distance(FramePoint framePoint)
|
double |
distanceSquared(FramePoint framePoint)
|
boolean |
epsilonEquals(FramePoint framePoint,
double threshold)
|
boolean |
epsilonEquals(FrameVector frameVector,
double threshold)
|
double |
get(Direction direction)
|
static FramePoint |
getMidPoint(FramePoint point1,
FramePoint point2)
|
java.lang.String |
getName()
|
javax.vecmath.Point3d |
getPoint()
Returns the Point3d used in this FramePoint |
void |
getPoint(javax.vecmath.Tuple3d tuple3dToPack)
|
javax.vecmath.Point3d |
getPointCopy()
Returns a deep copy of the point in this FramePoint. |
ReferenceFrame |
getReferenceFrame()
|
void |
getVector(javax.vecmath.Vector3d vector)
|
javax.vecmath.Vector3d |
getVectorCopy()
Returns a vector copy of the Point3d used in this FramePoint |
double |
getX()
|
double |
getXYplaneDistance(FramePoint framePoint)
|
double |
getY()
|
double |
getZ()
|
void |
interpolate(FramePoint framePoint1,
FramePoint framePoint2,
double alpha)
|
static FramePoint |
load(java.io.BufferedReader bufferedReader,
ReferenceFrame referenceFrame)
|
static FramePoint |
morph(FramePoint point1,
FramePoint point2,
double alpha)
|
FramePoint |
pitchAboutPoint(FramePoint pointToPitchAbout,
double pitch)
|
void |
save(java.io.PrintWriter printWriter)
|
void |
scale(double scaleFactor)
|
void |
scale(double scaleFactor,
FramePoint point1)
|
void |
scale(double scaleFactor,
FrameVector vector1)
|
void |
scaleAdd(double scaleFactor,
FramePoint point1)
|
void |
scaleAdd(double scaleFactor,
FramePoint point1,
FramePoint point2)
|
void |
scaleAdd(double scaleFactor,
FramePoint point1,
FrameVector vector2)
|
void |
scaleAdd(double scaleFactor,
FrameVector vector1)
|
void |
scaleAdd(double scaleFactor,
FrameVector vector1,
FramePoint point2)
|
void |
scaleAdd(double scaleFactor,
FrameVector vector1,
FrameVector vector2)
|
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.Tuple3d tuple)
|
void |
set(javax.vecmath.Tuple3d point)
|
void |
setAndChangeFrame(FramePoint framePoint)
|
void |
setAndChangeFrame(FrameVector frameVector)
|
void |
setAndChangeFrame(ReferenceFrame referenceFrame,
javax.vecmath.Point3d point)
|
void |
setName(java.lang.String name)
|
void |
setToZero(ReferenceFrame referenceFrame)
|
void |
setX(double x)
|
void |
setXY(FramePoint2d framePoint2d)
|
void |
setY(double y)
|
void |
setZ(double z)
|
void |
sub(FramePoint framePoint)
|
void |
sub(FramePoint point1,
FramePoint point2)
|
void |
sub(FramePoint point1,
FrameVector vector2)
|
void |
sub(FrameVector frameVector)
|
void |
sub(FrameVector vector1,
FramePoint point2)
|
double[] |
toArray()
|
static double[] |
toArray(FramePoint[] framePoints)
|
FramePoint2d |
toFramePoint2d()
Creates a new FramePoint2d based on the x and y components of this FramePoint |
java.lang.String |
toString()
toString String representation of a FrameVector (x,y,z):reference frame name |
void |
weightedAverage(FramePoint point1,
FramePoint point2,
double weightedAverage)
Sets this point to be the weighted average of the two input points. |
FramePoint |
yawAboutPoint(FramePoint pointToYawAbout,
double yaw)
yawAboutPoint |
Methods inherited from class java.lang.Object |
---|
equals, getClass, hashCode, notify, notifyAll, wait, wait, wait |
Constructor Detail |
---|
public FramePoint(ReferenceFrame referenceFrame, javax.vecmath.Tuple3d position)
public FramePoint(ReferenceFrame referenceFrame, javax.vecmath.Tuple3d position, java.lang.String name)
public FramePoint(ReferenceFrame referenceFrame, double[] position)
public FramePoint(ReferenceFrame referenceFrame, double[] position, java.lang.String name)
public FramePoint(ReferenceFrame referenceFrame)
referenceFrame
- Framepublic FramePoint(ReferenceFrame referenceFrame, java.lang.String name)
public FramePoint(FramePoint framePoint)
public FramePoint(FramePoint framePoint, java.lang.String name)
public FramePoint(FrameVector frameVector)
public FramePoint(FrameVector frameVector, java.lang.String name)
public FramePoint(ReferenceFrame referenceFrame, double x, double y, double z)
referenceFrame
- Framex
- doubley
- doublez
- doublepublic FramePoint(ReferenceFrame referenceFrame, double x, double y, double z, java.lang.String name)
public FramePoint()
Method Detail |
---|
public void setName(java.lang.String name)
public java.lang.String getName()
public static FramePoint morph(FramePoint point1, FramePoint point2, double alpha)
public static FramePoint average(java.util.List<? extends FramePoint> framePoints)
public double getXYplaneDistance(FramePoint framePoint)
public ReferenceFrame getReferenceFrame()
getReferenceFrame
in interface ReferenceFrameHolder
public double distance(FramePoint framePoint)
public double distanceSquared(FramePoint framePoint)
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(ReferenceFrame referenceFrame, javax.vecmath.Tuple3d tuple)
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 FramePoint2d toFramePoint2d()
public void scale(double scaleFactor, FrameVector vector1)
public void scale(double scaleFactor, FramePoint point1)
public void scaleAdd(double scaleFactor, FrameVector vector1, FrameVector vector2)
public void scaleAdd(double scaleFactor, FrameVector vector1, FramePoint point2)
public void scaleAdd(double scaleFactor, FramePoint point1, FrameVector vector2)
public void scaleAdd(double scaleFactor, FramePoint point1, FramePoint point2)
public void scaleAdd(double scaleFactor, FrameVector vector1)
public void scaleAdd(double scaleFactor, FramePoint point1)
public javax.vecmath.Point3d getPoint()
public void getPoint(javax.vecmath.Tuple3d tuple3dToPack)
public javax.vecmath.Point3d getPointCopy()
public javax.vecmath.Vector3d getVectorCopy()
public void getVector(javax.vecmath.Vector3d vector)
public FramePoint changeFrameUsingTransformCopy(ReferenceFrame desiredFrame, javax.media.j3d.Transform3D transformToNewFrame)
desiredFrame
- ReferenceFrame to change the FramePoint into.transformToNewFrame
- Transform3D from the current frame to the new desiredFrame
public FramePoint changeFrameCopy(ReferenceFrame desiredFrame)
changeFrameCopy
in interface ReferenceFrameHolder
desiredFrame
- ReferenceFrame to change the FramePoint into.
public void changeFrame(ReferenceFrame desiredFrame)
desiredFrame
- ReferenceFrame to change the FramePoint into.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 void checkReferenceFrameMatch(ReferenceFrameHolder referenceFrameHolder)
checkReferenceFrameMatch
in interface ReferenceFrameHolder
public void checkReferenceFrameMatch(ReferenceFrame frame) throws ReferenceFrameMismatchException
checkReferenceFrameMatch
in interface ReferenceFrameHolder
ReferenceFrameMismatchException
public void checkForNaN()
public boolean containsNaN()
public void add(FramePoint framePoint)
public void add(FrameVector frameVector)
public void add(javax.vecmath.Tuple3d tuple3d)
public void add(FramePoint point1, FramePoint point2)
public void add(FramePoint point1, FrameVector vector2)
public void add(FrameVector vector1, FramePoint point2)
public void sub(FramePoint framePoint)
public void sub(FrameVector frameVector)
public void sub(FramePoint point1, FramePoint point2)
public void sub(FramePoint point1, FrameVector vector2)
public void sub(FrameVector vector1, FramePoint point2)
public void setToZero(ReferenceFrame referenceFrame)
public void set(FramePoint framePoint)
public void setXY(FramePoint2d framePoint2d)
public void setAndChangeFrame(ReferenceFrame referenceFrame, javax.vecmath.Point3d point)
public void setAndChangeFrame(FramePoint framePoint)
public void set(javax.vecmath.Tuple3d point)
public void set(FrameVector frameVector)
public void setAndChangeFrame(FrameVector frameVector)
public void applyTransform(javax.media.j3d.Transform3D transform)
public static FramePoint getMidPoint(FramePoint point1, FramePoint point2)
public static FramePoint[] changeFrameCopyBatch(FramePoint[] framePoints, ReferenceFrame desiredFrame)
public static double[] toArray(FramePoint[] framePoints)
public void weightedAverage(FramePoint point1, FramePoint point2, double weightedAverage)
point1
- FramePointpoint2
- FramePointweightedAverage
- double
ReferenceFrameMismatchException
public java.lang.String toString()
toString
in class java.lang.Object
public void save(java.io.PrintWriter printWriter)
public static FramePoint load(java.io.BufferedReader bufferedReader, ReferenceFrame referenceFrame) throws java.io.IOException
java.io.IOException
public boolean epsilonEquals(FramePoint framePoint, double threshold)
public boolean epsilonEquals(FrameVector frameVector, double threshold)
public FramePoint applyTransformCopy(javax.media.j3d.Transform3D transform3D)
public FramePoint yawAboutPoint(FramePoint pointToYawAbout, double yaw)
pointToYawAbout
- FramePointyaw
- double
public FramePoint pitchAboutPoint(FramePoint pointToPitchAbout, double pitch)
public void interpolate(FramePoint framePoint1, FramePoint framePoint2, double alpha)
|
||||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | |||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |