us.ihmc.utilities.math.geometry
Class FramePoint2d

java.lang.Object
  extended by us.ihmc.utilities.math.geometry.FramePoint2d
All Implemented Interfaces:
java.io.Serializable, ReferenceFrameHolder

public class FramePoint2d
extends java.lang.Object
implements ReferenceFrameHolder, java.io.Serializable

Title: FramePoint2d

Description: A FramePoint2d is a normal point associated with a specified reference frame

Copyright: Copyright (c) 2006

Company: IHMC

Version:
2.0
Author:
Learning Locomotion Team
See Also:
Serialized Form

Constructor Summary
FramePoint2d(FramePoint2d framePoint)
          FramePoint2d A normal point associated with a specific reference frame
FramePoint2d(FramePoint2d framePoint, java.lang.String name)
           
FramePoint2d(FrameVector2d frameVector)
          FramePoint2d Converts frameVector to framePoint
FramePoint2d(FrameVector2d frameVector, java.lang.String name)
           
FramePoint2d(ReferenceFrame referenceFrame)
          FramePoint2d A normal point associated with a specific reference frame
FramePoint2d(ReferenceFrame referenceFrame, double[] position)
           
FramePoint2d(ReferenceFrame referenceFrame, double[] position, java.lang.String name)
           
FramePoint2d(ReferenceFrame referenceFrame, double x, double y)
          FramePoint2d A normal point associated with a specific reference frame.
FramePoint2d(ReferenceFrame referenceFrame, double x, double y, java.lang.String name)
           
FramePoint2d(ReferenceFrame referenceFrame, java.lang.String name)
           
FramePoint2d(ReferenceFrame referenceFrame, javax.vecmath.Tuple2d position)
          FramePoint2d A normal point associated with a specific reference frame
FramePoint2d(ReferenceFrame referenceFrame, javax.vecmath.Tuple2d position, java.lang.String name)
           
 
Method Summary
 void add(FramePoint2d framePoint)
           
 void add(FramePoint2d point1, FramePoint2d point2)
           
 void add(FramePoint2d point1, FrameVector2d vector2)
           
 void add(FrameVector2d frameVector)
           
 void add(FrameVector2d vector1, FramePoint2d point2)
           
 void applyTransform(javax.media.j3d.Transform3D transform)
           
 FramePoint2d applyTransformCopy(javax.media.j3d.Transform3D transform3D)
           
 FramePoint2d changeFrameCopy(ReferenceFrame desiredFrame)
          Changes frame of this FramePoint2d to the given ReferenceFrame and returns a copy.
static FramePoint2d[] changeFrameCopyBatch(FramePoint2d[] framePoints, ReferenceFrame desiredFrame)
           
 FramePoint2d changeFrameUsingTransformCopy(ReferenceFrame desiredFrame, javax.media.j3d.Transform3D transformToNewFrame)
          Changes frame of this FramePoint2d to the given ReferenceFrame, using the given Transform3D and returns a copy.
 void checkForNaN()
           
 void checkReferenceFrameMatch(ReferenceFrame frame)
           
 void checkReferenceFrameMatch(ReferenceFrameHolder referenceFrameHolder)
          Makes sure that the FramePoint2d argument has the same Frame as the current FramePoint2d.
 boolean containsNaN()
           
 double distance(FramePoint2d framePoint)
           
 double distanceSquared(FramePoint2d framePoint)
           
 boolean epsilonEquals(FramePoint2d framePoint, double threshold)
           
 boolean epsilonEquals(FrameVector2d frameVector, double threshold)
           
static FramePoint2d generateRandomFramePoint2d(java.util.Random random, ReferenceFrame zUpFrame, double xMin, double xMax, double yMin, double yMax)
           
 java.lang.String getName()
           
 javax.vecmath.Point2d getPoint()
          Returns the point in this FramePoint2d.
 javax.vecmath.Point2d getPointCopy()
          Returns a deep copy of the point in this FramePoint2d.
 ReferenceFrame getReferenceFrame()
           
 double getX()
           
 double getY()
           
static FramePoint2d load(java.io.BufferedReader bufferedReader, ReferenceFrame referenceFrame)
           
static FramePoint2d morph(FramePoint2d point1, FramePoint2d point2, double alpha)
           
 void save(java.io.PrintWriter printWriter)
           
 void scale(double scaleFactor)
           
 void scale(double scaleFactor, FramePoint2d point1)
           
 void scale(double scaleFactor, FrameVector2d vector1)
           
 void scaleAdd(double scaleFactor, FramePoint2d point1)
           
 void scaleAdd(double scaleFactor, FramePoint2d point1, FramePoint2d point2)
           
 void scaleAdd(double scaleFactor, FramePoint2d point1, FrameVector2d vector2)
           
 void scaleAdd(double scaleFactor, FrameVector2d vector1)
           
 void scaleAdd(double scaleFactor, FrameVector2d vector1, FramePoint2d point2)
           
 void scaleAdd(double scaleFactor, FrameVector2d vector1, FrameVector2d vector2)
           
 void set(double x, double y)
           
 void set(FramePoint2d framePoint)
           
 void set(FrameVector2d frameVector)
           
 void setName(java.lang.String name)
           
 void setX(double x)
           
 void setY(double y)
           
 void sub(FramePoint2d framePoint)
           
 void sub(FramePoint2d point1, FramePoint2d point2)
           
 void sub(FramePoint2d point1, FrameVector2d vector2)
           
 void sub(FrameVector2d frameVector)
           
 void sub(FrameVector2d vector1, FramePoint2d point2)
           
 double[] toArray()
           
static double[] toArray(FramePoint2d[] framePoints)
           
 java.lang.String toString()
          toString String representation of a FrameVector (x,y,z):reference frame name
 void weightedAverage(FramePoint2d point1, FramePoint2d point2, double weightedAverage)
          Sets this point to be the weighted average of the two input points.
 FramePoint2d yawAboutPoint(FramePoint2d pointToYawAbout, double yaw)
          yawAboutPoint
 
Methods inherited from class java.lang.Object
equals, getClass, hashCode, notify, notifyAll, wait, wait, wait
 

Constructor Detail

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame,
                    javax.vecmath.Tuple2d position)
FramePoint2d A normal point associated with a specific reference frame

Parameters:
referenceFrame - Frame
point - Point2d

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame,
                    javax.vecmath.Tuple2d position,
                    java.lang.String name)

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame,
                    double[] position)

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame,
                    double[] position,
                    java.lang.String name)

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame)
FramePoint2d A normal point associated with a specific reference frame

Parameters:
referenceFrame - Frame

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame,
                    java.lang.String name)

FramePoint2d

public FramePoint2d(FramePoint2d framePoint)
FramePoint2d A normal point associated with a specific reference frame

Parameters:
referenceFrame - Frame
point - Point3d

FramePoint2d

public FramePoint2d(FramePoint2d framePoint,
                    java.lang.String name)

FramePoint2d

public FramePoint2d(FrameVector2d frameVector)
FramePoint2d Converts frameVector to framePoint

Parameters:
referenceFrame - Frame
point - Point2d

FramePoint2d

public FramePoint2d(FrameVector2d frameVector,
                    java.lang.String name)

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame,
                    double x,
                    double y)
FramePoint2d A normal point associated with a specific reference frame. The x, y, and z are used to create the point

Parameters:
referenceFrame - Frame
x - double
y - double
z - double

FramePoint2d

public FramePoint2d(ReferenceFrame referenceFrame,
                    double x,
                    double y,
                    java.lang.String name)
Method Detail

setName

public void setName(java.lang.String name)

getName

public java.lang.String getName()

morph

public static FramePoint2d morph(FramePoint2d point1,
                                 FramePoint2d point2,
                                 double alpha)

getReferenceFrame

public ReferenceFrame getReferenceFrame()
Specified by:
getReferenceFrame in interface ReferenceFrameHolder

distance

public double distance(FramePoint2d framePoint)

distanceSquared

public double distanceSquared(FramePoint2d framePoint)

getX

public double getX()

getY

public double getY()

set

public void set(double x,
                double y)

setX

public void setX(double x)

setY

public void setY(double y)

scale

public void scale(double scaleFactor)

toArray

public double[] toArray()

scale

public void scale(double scaleFactor,
                  FrameVector2d vector1)

scale

public void scale(double scaleFactor,
                  FramePoint2d point1)

scaleAdd

public void scaleAdd(double scaleFactor,
                     FrameVector2d vector1,
                     FrameVector2d vector2)

scaleAdd

public void scaleAdd(double scaleFactor,
                     FrameVector2d vector1,
                     FramePoint2d point2)

scaleAdd

public void scaleAdd(double scaleFactor,
                     FramePoint2d point1,
                     FrameVector2d vector2)

scaleAdd

public void scaleAdd(double scaleFactor,
                     FramePoint2d point1,
                     FramePoint2d point2)

scaleAdd

public void scaleAdd(double scaleFactor,
                     FrameVector2d vector1)

scaleAdd

public void scaleAdd(double scaleFactor,
                     FramePoint2d point1)

getPoint

public javax.vecmath.Point2d getPoint()
Returns the point in this FramePoint2d.

Returns:
Point2d

getPointCopy

public javax.vecmath.Point2d getPointCopy()
Returns a deep copy of the point in this FramePoint2d.

Returns:
Point2d

changeFrameUsingTransformCopy

public FramePoint2d changeFrameUsingTransformCopy(ReferenceFrame desiredFrame,
                                                  javax.media.j3d.Transform3D transformToNewFrame)
Changes frame of this FramePoint2d to the given ReferenceFrame, using the given Transform3D and returns a copy.

Parameters:
desiredFrame - ReferenceFrame to change the FramePoint2d into.
transformToNewFrame - Transform3D from the current frame to the new desiredFrame
Returns:
Copied FramePoint2d in the new reference frame.

changeFrameCopy

public FramePoint2d changeFrameCopy(ReferenceFrame desiredFrame)
Changes frame of this FramePoint2d to the given ReferenceFrame and returns a copy.

Specified by:
changeFrameCopy in interface ReferenceFrameHolder
Parameters:
desiredFrame - ReferenceFrame to change the FramePoint2d into.
Returns:
Copied FramePoint2d in the new reference frame.

applyTransform

public void applyTransform(javax.media.j3d.Transform3D transform)

applyTransformCopy

public FramePoint2d applyTransformCopy(javax.media.j3d.Transform3D transform3D)

changeFrameCopyBatch

public static FramePoint2d[] changeFrameCopyBatch(FramePoint2d[] framePoints,
                                                  ReferenceFrame desiredFrame)

toArray

public static double[] toArray(FramePoint2d[] framePoints)

checkReferenceFrameMatch

public void checkReferenceFrameMatch(ReferenceFrameHolder referenceFrameHolder)
Makes sure that the FramePoint2d argument has the same Frame as the current FramePoint2d.

Specified by:
checkReferenceFrameMatch in interface ReferenceFrameHolder
Parameters:
framePoint - FramePoint2d

checkReferenceFrameMatch

public void checkReferenceFrameMatch(ReferenceFrame frame)
                              throws ReferenceFrameMismatchException
Specified by:
checkReferenceFrameMatch in interface ReferenceFrameHolder
Throws:
ReferenceFrameMismatchException

checkForNaN

public void checkForNaN()

containsNaN

public boolean containsNaN()

add

public void add(FramePoint2d framePoint)

add

public void add(FrameVector2d frameVector)

add

public void add(FramePoint2d point1,
                FramePoint2d point2)

add

public void add(FramePoint2d point1,
                FrameVector2d vector2)

add

public void add(FrameVector2d vector1,
                FramePoint2d point2)

sub

public void sub(FramePoint2d framePoint)

sub

public void sub(FrameVector2d frameVector)

sub

public void sub(FramePoint2d point1,
                FramePoint2d point2)

sub

public void sub(FramePoint2d point1,
                FrameVector2d vector2)

sub

public void sub(FrameVector2d vector1,
                FramePoint2d point2)

set

public void set(FramePoint2d framePoint)

set

public void set(FrameVector2d frameVector)

weightedAverage

public void weightedAverage(FramePoint2d point1,
                            FramePoint2d point2,
                            double weightedAverage)
Sets this point to be the weighted average of the two input points. p =

Parameters:
point1 - FramePoint2d
point2 - FramePoint2d
weightedAverage - double
Throws:
ReferenceFrameMismatchException

toString

public java.lang.String toString()
toString String representation of a FrameVector (x,y,z):reference frame name

Overrides:
toString in class java.lang.Object
Returns:
String

save

public void save(java.io.PrintWriter printWriter)

load

public static FramePoint2d load(java.io.BufferedReader bufferedReader,
                                ReferenceFrame referenceFrame)
                         throws java.io.IOException
Throws:
java.io.IOException

epsilonEquals

public boolean epsilonEquals(FramePoint2d framePoint,
                             double threshold)

epsilonEquals

public boolean epsilonEquals(FrameVector2d frameVector,
                             double threshold)

yawAboutPoint

public FramePoint2d yawAboutPoint(FramePoint2d pointToYawAbout,
                                  double yaw)
yawAboutPoint

Parameters:
pointToYawAbout - FramePoint2d
yaw - double
Returns:
CartesianPositionFootstep

generateRandomFramePoint2d

public static FramePoint2d generateRandomFramePoint2d(java.util.Random random,
                                                      ReferenceFrame zUpFrame,
                                                      double xMin,
                                                      double xMax,
                                                      double yMin,
                                                      double yMax)