public class AngleUtils
extends java.lang.Object
Modifier and Type | Field and Description |
---|---|
static double |
TWO_PI_RADS
2Pi constant
|
Modifier and Type | Method and Description |
---|---|
static double |
calcAngle(double x1,
double y1,
double x2,
double y2)
Calculates the angle between two 2D points.
|
static java.util.Vector<java.awt.geom.Point2D> |
linearizePoint2D(java.util.Vector<java.awt.geom.Point2D> points,
double angleTolerance)
This method linearizes an vector of 2D points.
|
static void |
main(java.lang.String[] args) |
static double |
nomalizeAngleDegrees180(double angle)
Normalizes an angle in degrees.
|
static double |
nomalizeAngleDegrees360(double angle)
Normalizes an angle in degrees.
|
static double |
nomalizeAngleRads2Pi(double angle)
Normalizes an angle in radians.
|
static double |
nomalizeAngleRadsPi(double angle)
Normalizes an angle in radians.
|
static double[] |
rotate(double angleRadians,
double x,
double y,
boolean clockwiseRotation)
XY Coordinate conversion considering a rotation angle.
|
public static final double TWO_PI_RADS
public static java.util.Vector<java.awt.geom.Point2D> linearizePoint2D(java.util.Vector<java.awt.geom.Point2D> points, double angleTolerance)
points
- The points to linearizeangleTolerance
- The acceptable angle to consider a straight linepublic static double calcAngle(double x1, double y1, double x2, double y2)
x1
- y1
- x2
- y2
- public static double nomalizeAngleRads2Pi(double angle)
angle
- The angle to normalizepublic static double nomalizeAngleRadsPi(double angle)
angle
- The angle to normalizepublic static double nomalizeAngleDegrees360(double angle)
angle
- The angle to normalizepublic static double nomalizeAngleDegrees180(double angle)
angle
- The angle to normalizepublic static double[] rotate(double angleRadians, double x, double y, boolean clockwiseRotation)
angleRadians
- Anglex
- original x value on entry, rotated x value on exit.y
- original y value on entry, rotated y value on exit.clockwiseRotation
- ClockwiseRotation rotation or notpublic static void main(java.lang.String[] args)
Copyright © 2004-2020 FEUP-LSTS and Neptus developers. All Rights Reserved.