@Override public Line2d initialValue() { return new Line2d(); } };
@Override public Line2d initialValue() { return new Line2d(); } };
public Line2d getLine2dCopy() { return new Line2d(line); }
public FrameLine2d(ReferenceFrame referenceFrame, Point2d firstPointOnLine, Point2d secondPointOnLine) { this(referenceFrame, new Line2d(firstPointOnLine, secondPointOnLine)); }
public FrameLine2d(ReferenceFrame referenceFrame, Point2d point2d, Vector2d vector2d) { this(referenceFrame, new Line2d(point2d, vector2d)); }
public ConvexPolygonShrinker() { for (int i=0; i<8; i++) { edgePool.add(new Line2d()); } }
private Line2d getARay(int index) { if (edgePool.size() <= index) { for (int i=0; i<index - edgePool.size() + 1; i++) { edgePool.add(new Line2d()); } } return edgePool.get(index); }
@Override public Line2d applyTransformAndProjectToXYPlaneCopy(RigidBodyTransform transform) { Line2d copy = new Line2d(this); copy.applyTransformAndProjectToXYPlane(transform); return copy; }
@Override public Line2d applyTransformCopy(RigidBodyTransform transform) { Line2d copy = new Line2d(this); copy.applyTransform(transform); return copy; }
public Line2d negateDirectionCopy() { Line2d ret = new Line2d(this); ret.normalizedVector.negate(); return ret; }
public Line2d perpendicularLineThroughPoint(Point2d point) { return new Line2d(point, perpendicularVector()); }
public FrameLine2d(FrameLine2d frameLine2d) { this(frameLine2d.getReferenceFrame(), new Line2d(frameLine2d.line)); }
public Line2d interiorBisector(Line2d secondLine) { Point2d pointOnLine = intersectionWith(secondLine); if (pointOnLine == null) { double distanceBetweenLines = secondLine.distance(point); double epsilon = 1E-7; boolean sameLines = distanceBetweenLines < epsilon; if (sameLines) { return new Line2d(this); } else { return null; } } Vector2d directionVector = new Vector2d(normalizedVector); directionVector.add(secondLine.normalizedVector); return new Line2d(pointOnLine, directionVector); }
public void setScreenDimension(Dimension screenDimension) { imageSize = screenDimension; axis = new Line2d(new Point2d(0, screenDimension.getHeight()), new Vector2d(1.0, 0.0)); }
public void setScreenDimension(Dimension screenDimension) { imageSize = screenDimension; axis = new Line2d(new Point2d(0, screenDimension.getHeight()), new Vector2d(1.0, 0.0)); }
private Point2d findEdgePoint(double x, double y) { if (x==0 && y==0) x=1; //as eccentricity=0 Line2d ray = new Line2d(new Point2d(0,0), new Vector2d(x,y)); Point2d[] edgePoints = polygon.intersectionWithRayCopy(ray); if(edgePoints.length!=1) throw new RuntimeException("intersecting points should be 1, but we get" + edgePoints.length); return edgePoints[0]; }
public void paint(Graphics graphics) { Color originalGraphicsColor = graphics.getColor(); graphics.setColor(Color.red); Graphics2D g2d = (Graphics2D) graphics; Stroke originalStroke = g2d.getStroke(); g2d.setStroke(new BasicStroke(lineThickness)); Line2d xMin = new Line2d(new Point2d(0, 0), new Vector2d(1.0, 0.0)); Line2d xMax = new Line2d(new Point2d(0, imageHeight), new Vector2d(1.0, 0.0)); for (Line2d line : lines) { Point2d p1 = line.intersectionWith(xMin); Point2d p2 = line.intersectionWith(xMax); graphics.drawLine((int) p1.getX(), (int)p1.getY(), (int)p2.getX(), (int) p2.getY()); } graphics.setColor(originalGraphicsColor); g2d.setStroke(originalStroke); } }
public FrameLine2d(FramePoint2d firstPointOnLine, FramePoint2d secondPointOnLine) { this(firstPointOnLine.getReferenceFrame(), new Line2d(firstPointOnLine.getPointCopy(), secondPointOnLine.getPointCopy())); firstPointOnLine.checkReferenceFrameMatch(secondPointOnLine); }
public FrameLine2d(FramePoint2d framePoint2d, FrameVector2d frameVector2d) { this(framePoint2d.getReferenceFrame(), new Line2d(framePoint2d.getPointCopy(), frameVector2d.getVectorCopy())); framePoint2d.checkReferenceFrameMatch(frameVector2d); }
public FrameLine2d(ReferenceFrame referenceFrame) { this(referenceFrame, new Line2d(new Point2d(), new Vector2d(1.0, 0.0))); }