Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 #define _USE_MATH_DEFINES // for MSVC
00007 #include <cmath>
00008 #include "Point2D.hpp"
00009 #include "Point3D.hpp"
00010 
00011 namespace datatypes
00012 {
00013         
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 Point3D::Point3D(const Point2D& p)
00022         : m_x(double(p.getX()))
00023         , m_y(double(p.getY()))
00024         , m_z(0.0)
00025 {
00026         m_datatype = Datatype_Point3D;
00027 }
00028 
00029 
00035 bool Point3D::isZero() const
00036 {
00037         return (fuzzyCompare(m_x, 0.0) &&
00038                         fuzzyCompare(m_y, 0.0) &&
00039                         fuzzyCompare(m_z, 0.0));
00040 }
00041 
00042 
00043 double Point3D::dist( const Point3D& point ) const
00044 {
00045         return hypot(m_x - point.getX(), m_y - point.getY(), m_z - point.getZ());
00046 }
00047 
00048 Point2D Point3D::toPoint2D() const
00049 {
00050         Point2D result(m_x, m_y);
00051         return result;
00052 }
00053 
00058 Point3D Point3D::vectorProduct(const Point3D& v1, const Point3D& v2)
00059 {
00060         Point3D kreuz;
00061 
00062         kreuz.m_x = + ((v1.getY() * v2.getZ()) - (v1.getZ() * v2.getY()));
00063         kreuz.m_y = -((v1.getX() * v2.getZ()) - (v1.getZ() * v2.getX()));
00064         kreuz.m_z = + ((v1.getX() * v2.getY()) - (v1.getY() * v2.getX()));
00065 
00066         return kreuz;
00067 }
00068 
00074 void Point3D::normalize()
00075 {
00076         if (isZero())
00077                 
00078                 return;
00079 
00080         double len = length();
00081         
00082         if (fuzzyCompare(len, 0.0))
00083         {
00084                 
00085                 return;
00086         }
00087 
00088         *this /= len;
00089 }
00090 
00091 
00096 void Point3D::rotateAroundZ(double yawAngle)
00097 {
00098         double dCos = cos(yawAngle);
00099         double dSin = sin(yawAngle);
00100 
00101         double x = m_x * dCos - m_y * dSin;
00102         double y = m_x * dSin + m_y * dCos;
00103 
00104         m_x = x;
00105         m_y = y;
00106 }
00107 
00108 
00113 void Point3D::rotateAroundX(double rollAngle)
00114 {
00115         double dCos = cos(rollAngle);
00116         double dSin = sin(rollAngle);
00117 
00118         double y = -m_z * dSin + m_y * dCos;
00119         double z = m_z * dCos + m_y * dSin;
00120 
00121         m_z = z;
00122         m_y = y;
00123 }
00124 
00129 void Point3D::rotateAroundY(double pitchAngle)
00130 {
00131         double dCos = cos(pitchAngle);
00132         double dSin = sin(pitchAngle);
00133 
00134         double x = m_z * dSin + m_x * dCos;
00135         double z = m_z * dCos - m_x * dSin;
00136 
00137         m_z = z;
00138         m_x = x;
00139 }
00140 
00141 
00146 double Point3D::distFromOrigin() const
00147 {
00148         return hypot(m_x, m_y, m_z);
00149 }
00150 
00155 double Point3D::length() const
00156 {
00157         return distFromOrigin();
00158 }
00159 
00160 
00179 double Point3D::getAngleAroundZ() const
00180 {
00181         double angle;
00182 
00183         
00184         angle = std::atan2(m_y, m_x);
00185 
00186         return angle;
00187 }
00188 
00207 double Point3D::getAngleAroundY() const
00208 {
00209         double angle;
00210 
00211         
00212         angle = std::atan2(m_x, m_z);
00213 
00214         return angle;
00215 }
00216 
00217 
00235 double Point3D::getAngleAroundX() const
00236 {
00237         double angle;
00238 
00239         
00240         angle = std::atan2(m_z, m_y);
00241 
00242         return angle;
00243 }
00244 
00245 
00246 
00250 double Point3D::getDistanceBetweenPoints(const Point3D& pt1, const Point3D& pt2)
00251 {
00252         return pt1.dist(pt2);
00253 }
00254 
00255 
00256 
00257 
00258 
00262 std::string Point3D::toString() const
00263 {
00264 
00265         std::ostringstream ostr;
00266         ostr << *this;
00267         return ostr.str();
00268 }
00269 
00273 std::ostream& operator<<(std::ostream& os, const Point3D& point)
00274 {
00275         os << "(" << point.getX() << ", " << point.getY() << ", " << point.getZ() << ")";
00276         return os;
00277 }
00278 
00279 
00293 Point3D Point3D::calcIntersectionPointOfVectorWithPlane(const Point3D& PlaneStartpoint,
00294                 const Point3D& PlaneNormal,
00295                 const Point3D& VectorStartpoint,
00296                 const Point3D& VectorDirection)
00297 {
00298         Point3D intersectionPoint;
00299         double nenner;
00300 
00301         nenner = PlaneNormal * VectorDirection;
00302         if (fuzzyCompare(nenner, 0.0) == false)
00303         {
00304                 
00305                 intersectionPoint = VectorStartpoint + ((PlaneNormal * (PlaneStartpoint - VectorStartpoint)) / nenner) * VectorDirection;
00306         }
00307         else
00308         {
00309                 
00310                 intersectionPoint.setXYZ(NaN_double, NaN_double, NaN_double);
00311         }
00312 
00313         return intersectionPoint;
00314 }
00315 
00316 }