us.ihmc.utilities.math.geometry
Class LineSegment2d
java.lang.Object
us.ihmc.utilities.math.geometry.LineSegment2d
- All Implemented Interfaces:
- Geometry2d
public class LineSegment2d
- extends java.lang.Object
- implements Geometry2d
Title:
Description: a line segment must have two distinct endpoints by definition
Copyright: Copyright (c) 2007
Company:
- Version:
- 1.0
- Author:
- Twan Koolen
Methods inherited from class java.lang.Object |
getClass, hashCode, notify, notifyAll, wait, wait, wait |
LineSegment2d
public LineSegment2d(double x0,
double y0,
double x1,
double y1)
LineSegment2d
public LineSegment2d(javax.vecmath.Point2d[] endpoints)
LineSegment2d
public LineSegment2d(javax.vecmath.Point2d endpoint1,
javax.vecmath.Point2d endpoint2)
LineSegment2d
public LineSegment2d(LineSegment2d lineSegment2d)
getEndpointsCopy
public javax.vecmath.Point2d[] getEndpointsCopy()
getEndpoints
public void getEndpoints(javax.vecmath.Point2d endpoint0,
javax.vecmath.Point2d endpoint1)
getEndpoints
public javax.vecmath.Point2d[] getEndpoints()
getFirstEndPointCopy
public javax.vecmath.Point2d getFirstEndPointCopy()
getSecondEndPointCopy
public javax.vecmath.Point2d getSecondEndPointCopy()
set
public void set(javax.vecmath.Point2d endpoint0,
javax.vecmath.Point2d endpoint1)
set
public void set(double x0,
double y0,
double x1,
double y1)
set
public void set(javax.vecmath.Point2d[] endpoints)
set
public void set(LineSegment2d lineSegment)
flipDirection
public void flipDirection()
midpoint
public javax.vecmath.Point2d midpoint()
length
public double length()
dotProduct
public double dotProduct(LineSegment2d lineSegment2d)
isBetweenEndpoints
public boolean isBetweenEndpoints(javax.vecmath.Point2d point2d,
double epsilon)
isPointOnLeftSideOfLineSegment
public boolean isPointOnLeftSideOfLineSegment(javax.vecmath.Point2d point)
isPointOnRightSideOfLineSegment
public boolean isPointOnRightSideOfLineSegment(javax.vecmath.Point2d point)
shiftToLeftCopy
public LineSegment2d shiftToLeftCopy(double distanceToShift)
shiftToRightCopy
public LineSegment2d shiftToRightCopy(double distanceToShift)
percentageAlongLineSegment
public double percentageAlongLineSegment(javax.vecmath.Point2d point2d)
isPointOnLineSegment
public boolean isPointOnLineSegment(javax.vecmath.Point2d point2d)
intersectionWith
public javax.vecmath.Point2d intersectionWith(LineSegment2d secondLineSegment2d)
- Specified by:
intersectionWith
in interface Geometry2d
intersectionWith
public javax.vecmath.Point2d intersectionWith(Line2d line2d)
- Specified by:
intersectionWith
in interface Geometry2d
intersectionWith
public javax.vecmath.Point2d[] intersectionWith(ConvexPolygon2d convexPolygon)
- Specified by:
intersectionWith
in interface Geometry2d
distance
public double distance(Line2d line)
- Specified by:
distance
in interface Geometry2d
distance
public double distance(LineSegment2d lineSegment)
- Specified by:
distance
in interface Geometry2d
distance
public double distance(ConvexPolygon2d convexPolygon)
- Specified by:
distance
in interface Geometry2d
toString
public java.lang.String toString()
- Overrides:
toString
in class java.lang.Object
applyTransform
public void applyTransform(javax.media.j3d.Transform3D transform)
- Specified by:
applyTransform
in interface Geometry2d
applyTransform
public void applyTransform(javax.media.j3d.Transform3D transform,
boolean requireTransformInPlane)
- Specified by:
applyTransform
in interface Geometry2d
applyTransformCopy
public LineSegment2d applyTransformCopy(javax.media.j3d.Transform3D transform)
- Specified by:
applyTransformCopy
in interface Geometry2d
applyTransformCopy
public LineSegment2d applyTransformCopy(javax.media.j3d.Transform3D transform,
boolean requireTransformInPlane)
- Specified by:
applyTransformCopy
in interface Geometry2d
pointBetweenEndPointsGivenParameter
public javax.vecmath.Point2d pointBetweenEndPointsGivenParameter(double parameter)
distance
public double distance(javax.vecmath.Point2d point)
- Specified by:
distance
in interface Geometry2d
orthogonalProjectionCopy
public javax.vecmath.Point2d orthogonalProjectionCopy(javax.vecmath.Point2d point)
- Specified by:
orthogonalProjectionCopy
in interface Geometry2d
orthogonalProjection
public void orthogonalProjection(javax.vecmath.Point2d point2d)
- Specified by:
orthogonalProjection
in interface Geometry2d
getClosestPointOnLineSegment
public javax.vecmath.Point2d getClosestPointOnLineSegment(javax.vecmath.Point2d testPoint)
equals
public boolean equals(java.lang.Object object)
- Overrides:
equals
in class java.lang.Object