6 #define _USE_MATH_DEFINES // for MSVC 22 : m_x(double(p.getX()))
23 , m_y(double(p.getY()))
98 double dCos = cos(yawAngle);
99 double dSin = sin(yawAngle);
101 double x =
m_x * dCos -
m_y * dSin;
102 double y =
m_x * dSin +
m_y * dCos;
115 double dCos = cos(rollAngle);
116 double dSin = sin(rollAngle);
118 double y = -
m_z * dSin +
m_y * dCos;
119 double z =
m_z * dCos +
m_y * dSin;
131 double dCos = cos(pitchAngle);
132 double dSin = sin(pitchAngle);
134 double x =
m_z * dSin +
m_x * dCos;
135 double z =
m_z * dCos -
m_x * dSin;
184 angle = std::atan2(
m_y,
m_x);
212 angle = std::atan2(
m_x,
m_z);
240 angle = std::atan2(
m_z,
m_y);
252 return pt1.
dist(pt2);
265 std::ostringstream ostr;
275 os <<
"(" << point.
getX() <<
", " << point.
getY() <<
", " << point.
getZ() <<
")";
295 const Point3D& VectorStartpoint,
296 const Point3D& VectorDirection)
301 nenner = PlaneNormal * VectorDirection;
305 intersectionPoint = VectorStartpoint + ((PlaneNormal * (PlaneStartpoint - VectorStartpoint)) / nenner) * VectorDirection;
313 return intersectionPoint;
void setXYZ(double x, double y, double z)
Sets the coordinates of this point to the given values.
double distFromOrigin() const
Dist from the point (0,0,0) to this point.
This class defines a point in the three-dimensional plane.
static Point3D calcIntersectionPointOfVectorWithPlane(const Point3D &PlaneStartpoint, const Point3D &PlaneNormal, const Point3D &VectorStartpoint, const Point3D &VectorDirection)
std::string toString() const
Text output for debugging.
double dist(const Point3D &point) const
Calculates the distance to the given point.
void normalize()
Normalizes this vector (point) to length 1.0.
void rotateAroundZ(double dYawAngle)
Rotate the point around the Z-axis ("Yaw angle")
double getZ() const
Returns the z-coordinate of this point.
double getY() const
Returns the y-coordinate of this point.
static Point3D vectorProduct(const Point3D &v1, const Point3D &v2)
Returns the vector product ("Kreuzprodukt") of the two vectors.
double getX() const
Returns the x-coordinate of this point.
Point2D toPoint2D() const
Returns the x/y components of this class, converted into a Point2D object.
double getAngleAroundX() const
Returns the rotation angle around x (in the z-y-plane)
double getAngleAroundY() const
Returns the rotation angle around y (in the z-x-plane)
double length() const
Length of the vector (identical to distFromOrigin())
void rotateAroundX(double rollAngle)
Rotate the point around the X-axis ("Roll angle")
static double getDistanceBetweenPoints(const Point3D &pt1, const Point3D &pt2)
Returns the distance between the two point coordinates.
double getAngleAroundZ() const
Returns the rotation angle around z (in the x-y-plane)
std::ostream & operator<<(std::ostream &os, const EvalCaseResult &result)
bool isZero() const
Check against (near-)zero.
void rotateAroundY(double pitchAngle)
Rotate the point around the Y-axis ("Pitch angle")