cartesian_point.hpp
Go to the documentation of this file.
00001 
00010 /*****************************************************************************
00011 ** Ifdefs
00012 *****************************************************************************/
00013 
00014 #ifndef ECL_GEOMETRY_CARTESIAN_POINT_HPP_
00015 #define ECL_GEOMETRY_CARTESIAN_POINT_HPP_
00016 
00017 /*****************************************************************************
00018 ** Includes
00019 *****************************************************************************/
00020 
00021 #include <ecl/config/macros.hpp>
00022 #include <ecl/exceptions/standard_exception.hpp>
00023 #include <ecl/linear_algebra.hpp>
00024 #include <ecl/math.hpp>
00025 
00026 /*****************************************************************************
00027 ** Namespaces
00028 *****************************************************************************/
00029 
00030 namespace ecl {
00031 
00032 /*****************************************************************************
00033 ** Interface [CartesianPoint<T,N>]
00034 *****************************************************************************/
00045 template <typename T, unsigned int N>
00046 class ECL_PUBLIC CartesianPoint {
00047 public:
00051         CartesianPoint(const T &value = T()) : elements(ecl::linear_algebra::Matrix<T,N,1>::Constant(value)) {}
00057         CartesianPoint(const ecl::linear_algebra::Matrix<T,N,1> &point_vector) : elements(point_vector) {}
00058 
00059     /*********************
00060     ** Assignment
00061     **********************/
00075         ecl::linear_algebra::CommaInitializer< ecl::linear_algebra::Matrix<T,N,1> > operator<<(const T &value) {
00076                 return elements.operator<<(value);
00077     }
00078 
00086         T& operator [](const unsigned int& index) ecl_assert_throw_decl(StandardException) {
00087         ecl_assert_throw( index<N, StandardException(LOC,OutOfRangeError));
00088         return elements[index];
00089     }
00090 
00098         const T& operator [](const unsigned int& index) const ecl_assert_throw_decl(StandardException) {
00099         ecl_assert_throw( index<N, StandardException(LOC,OutOfRangeError));
00100         return elements[index];
00101     }
00102 
00103 
00104 
00105 
00113         ecl::linear_algebra::Matrix<T,N,1>& positionVector() { return elements; }
00121         const ecl::linear_algebra::Matrix<T,N,1>& positionVector() const { return elements; }
00122 
00123         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00124 
00125 private:
00126         ecl::linear_algebra::Matrix<T,N,1> elements;
00127 };
00128 
00129 /*****************************************************************************
00130 ** Interface [CartesianPoint<T,3>]
00131 *****************************************************************************/
00143 template<typename T>
00144 class ECL_PUBLIC CartesianPoint<T,3> {
00145 public:
00149         CartesianPoint(const T &value = T()) : elements(ecl::linear_algebra::Matrix<T,3,1>::Constant(value)) {}
00155         CartesianPoint(const ecl::linear_algebra::Matrix<T,3,1> &vec) : elements(vec) {}
00163         CartesianPoint(const T &x_i, const T &y_i, const T &z_i) {
00164                 elements << x_i, y_i, z_i;
00165         }
00166 
00167         virtual ~CartesianPoint() {}
00168 
00169     /*********************
00170     ** Assignment
00171     **********************/
00185         ecl::linear_algebra::CommaInitializer< ecl::linear_algebra::Matrix<T,3,1> > operator<<(const T &value) {
00186                 return elements.operator<<(value);
00187     }
00188 
00196         ecl::linear_algebra::Matrix<T,3,1>& positionVector() { return elements; }
00197 
00205         const ecl::linear_algebra::Matrix<T,3,1>& positionVector() const { return elements; }
00206 
00214         unsigned int size() { return 3; }
00215 
00221         const T& x() const { return elements[0]; }
00227         const T& y() const { return elements[1]; }
00233         const T& z() const { return elements[2]; }
00239         T x() { return elements[0]; }
00245         T y() { return elements[1]; }
00251         T z() { return elements[2]; }
00252 
00253         void x(const T& value) { elements[0] = value; } 
00254         void y(const T& value) { elements[1] = value; } 
00255         void z(const T& value) { elements[2] = value; } 
00257         template <typename OutputStream, typename Type>
00258         friend OutputStream& operator<<(OutputStream &ostream , const CartesianPoint<Type,3> &point);
00259 
00260 private:
00261         ecl::linear_algebra::Matrix<T,3,1> elements;
00262 };
00263 
00264 typedef CartesianPoint<double,3> CartesianPoint3d;  
00265 typedef CartesianPoint<float,3> CartesianPoint3f;  
00266 typedef CartesianPoint<int,3> CartesianPoint3i;  
00268 /*********************
00269 ** Streaming
00270 **********************/
00278 template <typename OutputStream, typename Type>
00279 OutputStream& operator<<(OutputStream &ostream , const CartesianPoint<Type,3> &point) {
00280         ostream << "[ " << point.x() << " " << point.y() << " " << point.z() << " ]";
00281         return ostream;
00282 }
00283 
00284 /*****************************************************************************
00285 ** Interface [CartesianPoint<T,2>]
00286 *****************************************************************************/
00298 template<typename T>
00299 class ECL_PUBLIC CartesianPoint<T,2> {
00300 public:
00304         CartesianPoint(const T &value = T()) : elements(ecl::linear_algebra::Matrix<T,2,1>::Constant(value)) {}
00310         CartesianPoint(const ecl::linear_algebra::Matrix<T,2,1> &vec) : elements(vec) {}
00316         CartesianPoint(const CartesianPoint<T,2> &point ) : elements( point.positionVector() ) {}
00317 
00318         CartesianPoint(const T &x_i, const T &y_i) {
00319                 elements << x_i, y_i;
00320         }
00321 
00322         virtual ~CartesianPoint() {}
00323 
00324     /*********************
00325     ** Assignment
00326     **********************/
00340         ecl::linear_algebra::CommaInitializer< ecl::linear_algebra::Matrix<T,2,1> > operator<<(const T &value) {
00341                 return elements.operator<<(value);
00342     }
00343 
00344         T& operator [](const unsigned int& index) ecl_assert_throw_decl(StandardException) {
00345         ecl_assert_throw( index<2, StandardException(LOC,OutOfRangeError));
00346         return elements[index];
00347     }
00348 
00349         const T  operator [](const unsigned int& index) const ecl_assert_throw_decl(StandardException) {
00350         ecl_assert_throw( index<2, StandardException(LOC,OutOfRangeError));
00351         return elements[index];
00352     }
00353 
00354         const CartesianPoint<T,2> & operator = (const CartesianPoint<T,2> &v)
00355         {
00356                 elements = v.positionVector();
00357                 return *this;
00358         }
00366         ecl::linear_algebra::Matrix<T,2,1>& positionVector() { return elements; }
00367 
00375         const ecl::linear_algebra::Matrix<T,2,1>& positionVector() const { return elements; }
00376 
00384         unsigned int size() { return 2; }
00385 
00391         const T& x() const { return elements[0]; }
00397         const T& y() const { return elements[1]; }
00403         T x() { return elements[0]; }
00409         T y() { return elements[1]; }
00410 
00411         bool    operator == (const CartesianPoint<T,2> & other ) const
00412         {
00413                 if( other.x() != x() || other.y() != y() ) return false;
00414                 else return true;
00415         }
00416 
00417         bool    operator != (const CartesianPoint<T,2> & other ) const
00418         {
00419                 if( other.x() != x() || other.y() != y() ) return true;
00420                 else return false;
00421         }
00422 
00423         void rotate( const double & angle )
00424         {
00425                 double c = cos(angle);
00426                 double s = sin(angle);
00427                 double tx = x()*c - y()*s;
00428                 double ty = x()*s + y()*c;
00429 
00430                 elements[0] = tx;
00431                 elements[1] = ty;
00432         }
00433 
00434         double get_angle(void)
00435         {
00436                 return atan2( y(), x() );
00437         }
00438 
00439         void operator += ( const  CartesianPoint<T,2> & other )
00440         {
00441                 elements += other.positionVector();
00442         }
00443 
00444         T distance ( const CartesianPoint<T,2> & other )
00445         {
00446                 ecl::linear_algebra::Matrix<T,2,1> temp_element = elements - other.positionVector();
00447                 return static_cast<T>( sqrt( temp_element[0]*temp_element[0]+temp_element[1]*temp_element[1]) );
00448         }
00449 
00450         T Normalize(void)
00451         {
00452                 T mag = ecl::EuclideanNorm()( x(), y() );
00453 //              T mag = static_cast<T>(sqrt( x()*x()+y()*y() ));
00454                 if ( mag == static_cast<T>(0) ) // make a unit vector in z-direction
00455                 {
00456                         elements[0] = 1.0;
00457                         elements[1] = 0.0;
00458                 } else
00459                 {
00460                         elements[0] *= (1.0/mag);
00461                         elements[1] *= (1.0/mag);
00462                 }
00463                 return mag;
00464         }
00465 
00466         CartesianPoint<T,2> operator * (double d) const
00467         {
00468                 return CartesianPoint<T,2>( elements*d );
00469         }
00470 
00471         CartesianPoint<T,2> operator + (const CartesianPoint<T,2> &v) const
00472         {
00473                 return CartesianPoint<T,2>( x()+v.x(), y()+v.y() );
00474         }
00475 
00476         CartesianPoint<T,2> operator - (const CartesianPoint<T,2> &v) const
00477         {
00478                 return CartesianPoint<T,2>( x()-v.x(), y()-v.y() );
00479         }
00480 
00481         double Norm(void)
00482         {
00483                 return static_cast<double>( ecl::EuclideanNorm()( x(), y() )  );
00484 //              return (sqrt( x()*x()+y()*y() ));
00485         }
00486 
00487         void x(const T& value) { elements[0] = value; } 
00488         void y(const T& value) { elements[1] = value; } 
00490         template <typename OutputStream, typename Type>
00491         friend OutputStream& operator<<(OutputStream &ostream , const CartesianPoint<Type,2> &point);
00492 
00493         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00494 
00495 private:
00496         ecl::linear_algebra::Matrix<T,2,1> elements;
00497 };
00498 
00499 typedef CartesianPoint<double,2> CartesianPoint2d;  
00500 typedef CartesianPoint<float,2> CartesianPoint2f;  
00501 typedef CartesianPoint<int,2> CartesianPoint2i;  
00503 /*********************
00504 ** Streaming
00505 **********************/
00513 template <typename OutputStream, typename Type>
00514 OutputStream& operator<<(OutputStream &ostream , const CartesianPoint<Type,2> &point) {
00515         ostream << "[ " << point.x() << " " << point.y() << " ]";
00516         return ostream;
00517 }
00518 
00519 }  // namespace ecl
00520 
00521 #endif /* ECL_GEOMETRY_CARTESIAN_POINT_HPP_ */


ecl_geometry
Author(s): Daniel Stonier (d.stonier@gmail.com)
autogenerated on Thu Jan 2 2014 11:13:11