public FrameLine2d negateDirectionCopy() { FrameLine2d ret = new FrameLine2d(this.referenceFrame, line.negateDirectionCopy()); return ret; }
@Override public FrameLine2d applyTransformAndProjectToXYPlaneCopy(RigidBodyTransform transform) { FrameLine2d copy = new FrameLine2d(this); copy.applyTransformAndProjectToXYPlane(transform); return copy; }
@Override public FrameLine2d changeFrameAndProjectToXYPlaneCopy(ReferenceFrame desiredFrame) { FrameLine2d copy = new FrameLine2d(this); copy.changeFrameAndProjectToXYPlane(desiredFrame); return copy; }
public FrameLine2d getFrameLine2d() { putYoValuesIntoFrameLine(); return new FrameLine2d(frameLine); }
@Override public FrameLine2d applyTransformCopy(RigidBodyTransform transform) { FrameLine2d copy = new FrameLine2d(this); copy.applyTransform(transform); return copy; }
public FrameLine2d applyTransformAndProjectToXYPlaneCopy(RigidBodyTransform transform, ReferenceFrame newFrame) { return new FrameLine2d(newFrame, this.line.applyTransformAndProjectToXYPlaneCopy(transform)); }
/** * applyTransformCopy * Use of this method is discouraged. Only use it to speed up computation * FrameLine2ds en masse, and only when the desired reference frame is not a * parent or child of the current reference frame. * * @param transform Transform3D * @param newFrame ReferenceFrame * @param requirePlanarTransform boolean * @return FrameConvexPolygon2d */ public FrameLine2d applyTransformCopy(RigidBodyTransform transform, ReferenceFrame newFrame) { return new FrameLine2d(newFrame, this.line.applyTransformCopy(transform)); }
public static FrameLine2d generateRandomFrameLine2d(Random random, ReferenceFrame zUpFrame, double xMin, double xMax, double yMin, double yMax) { FramePoint2d randomPoint = FramePoint2d.generateRandomFramePoint2d(random, zUpFrame, xMin, xMax, yMin, yMax); FrameVector2d randomVector = FrameVector2d.generateRandomFrameVector2d(random, zUpFrame); return new FrameLine2d(randomPoint, randomVector); } }
public FrameLine2d interiorBisector(FrameLine2d secondLine) { this.checkReferenceFrameMatch(secondLine); ReferenceFrame referenceFrame = this.referenceFrame; Line2d bisectorLine2d = this.line.interiorBisector(secondLine.line); if (bisectorLine2d == null) { return null; } else { return new FrameLine2d(referenceFrame, bisectorLine2d); } }
public static FrameLine2d perpendicularLineThroughPoint(FrameLine2d line, FramePoint2d point) { line.checkReferenceFrameMatch(point); ReferenceFrame referenceFrame = line.referenceFrame; Line2d perpLine2d = line.line.perpendicularLineThroughPoint(point.getPointCopy()); return new FrameLine2d(referenceFrame, perpLine2d); }
protected void putYoValuesIntoFrameLine() { if (frameLine == null) { frameLine = new FrameLine2d(referenceFrame, new Point2d(pointX.getDoubleValue(), pointY.getDoubleValue()), new Vector2d(vectorX.getDoubleValue(), vectorY.getDoubleValue())); } else { frameLine.set(referenceFrame, pointX.getDoubleValue(), pointY.getDoubleValue(), vectorX.getDoubleValue(), vectorY.getDoubleValue()); } } }
backupFootPolygon = new FrameConvexPolygon2d(defaultFootPolygon); unsafePolygon = new FrameConvexPolygon2d(defaultFootPolygon); lineOfRotation = new FrameLine2d(soleFrame); rotationCalculators.put(RotationCalculatorType.VELOCITY, velocityFootRotationCalculator); rotationCalculators.put(RotationCalculatorType.GEOMETRY, geometricFootRotationCalculator); lineOfRotations.put(RotationCalculatorType.VELOCITY, new FrameLine2d(soleFrame)); lineOfRotations.put(RotationCalculatorType.GEOMETRY, new FrameLine2d(soleFrame));
throw new RuntimeException("distanceToBeInside = " + distanceToBeInside); FrameLine2d line = new FrameLine2d(pointToMove, vector); FramePoint2d[] intersections = polygon.intersectionWith(line);
public FrameConvexPolygon2dIntersector() { planeOne = new FramePlane3d(); planeTwo = new FramePlane3d(); intersectionOfPlanes = new FrameLine(); planeIntersectionOnPolygonPlane = new FrameLine2d(); lineIntersectionOnPolygonPlane = new Pair<FramePoint2d, FramePoint2d>(new FramePoint2d(), new FramePoint2d()); intersectionWithPolygonOne = new Pair<FramePoint, FramePoint>(new FramePoint(), new FramePoint()); intersectionWithPolygonTwo = new Pair<FramePoint, FramePoint>(new FramePoint(), new FramePoint()); point2Vector = new Vector3d(); point3Vector = new Vector3d(); point4Vector = new Vector3d(); noIntersection = false; }