Ellipse2D.hpp
Go to the documentation of this file.
1 // This is -*-c++-*-
2 //
3 
4 #ifndef ELLIPSE2D_H
5 #define ELLIPSE2D_H
6 
7 #include "../BasicDatatypes.hpp"
8 #include "Point2D.hpp"
9 #include <iosfwd> // for istream, ostream
10 #include <sstream>
11 
12 namespace datatypes
13 {
14 
16 
30 class Ellipse2D : public BasicData
31 {
32 public:
35 protected:
38  value_type m_rotation;
39 public:
41  Ellipse2D();
42 
44 
55  Ellipse2D(const Point2D& center, const Point2D& radius, value_type rotation = 0.0);
56 
58 
78  Ellipse2D(value_type x_center, value_type y_center, value_type x_radius, value_type y_radius, value_type rotation = 0.0);
79 
80 
81  // Estimate the memory usage of this object
82  virtual const UINT32 getUsedMemory() const { return sizeof(*this); };
83 
85  //\{
86 
88  const Point2D& getCenter() const { return m_center; }
89 
91 
97  const Point2D& getRadius() const { return m_radius; }
98 
104  value_type getRotation() const { return m_rotation; }
105 
106  //\}
107 
108 
110  //\{
111 
113  void setCenter(const Point2D& p) { m_center = p; }
114 
116  void setCenter(value_type x, value_type y) { m_center.setXY(x, y); }
117 
119  void setRadius(const Point2D& p);
120 
122  void setRadius(value_type x_length, value_type y_width);
123 
131  void setRotation(value_type r);
132 
133  //\}
134 
135 
137  //\{
138 
140 
145  bool containsPoint(const Point2D& point) const;
146 
147  //\}
148 
149  std::string toString() const; // Konvertierung zu string
150 
151 
152  friend inline bool operator==(const Ellipse2D &, const Ellipse2D &);
153  friend inline bool operator!=(const Ellipse2D &, const Ellipse2D &);
154 
155 private:
156  void verifyNumericRanges();
157 
158 };
159 
160 
161 inline bool operator==(const Ellipse2D &b1, const Ellipse2D &b2)
162 {
163  return (b1.m_center == b2.m_center)
164  && (b1.m_radius == b2.m_radius)
165  && (fuzzyCompare(b1.m_rotation,
166  b2.m_rotation)
167  || (isNaN(b1.m_rotation) && isNaN(b2.m_rotation)));
168 }
169 
170 inline bool operator!=(const Ellipse2D &b1, const Ellipse2D &b2)
171 {
172  return ! operator==(b1, b2);
173 }
174 
175 } // namespace datatypes
176 
177 #endif // ELLIPSE2D_H
Point2D::value_type value_type
The type of the stored x, y coordinates, and the rotation.
Definition: Ellipse2D.hpp:34
const Point2D & getCenter() const
Returns the center point of this Ellipse.
Definition: Ellipse2D.hpp:88
uint32_t UINT32
bool containsPoint(const Point2D &point) const
Returns true if the given Point2D is inside this ellipse or on its outline.
Definition: Ellipse2D.cpp:66
virtual const UINT32 getUsedMemory() const
Definition: Ellipse2D.hpp:82
value_type getRotation() const
Definition: Ellipse2D.hpp:104
friend bool operator!=(const Ellipse2D &, const Ellipse2D &)
Definition: Ellipse2D.hpp:170
void setCenter(const Point2D &p)
Sets the center point of this Ellipse2D.
Definition: Ellipse2D.hpp:113
void setRotation(value_type r)
Definition: Ellipse2D.cpp:60
void setXY(value_type x, value_type y)
Definition: Point2D.hpp:147
friend bool operator==(const Ellipse2D &, const Ellipse2D &)
Definition: Ellipse2D.hpp:161
double value_type
The type of the stored x and y coordinates.
Definition: Point2D.hpp:31
bool fuzzyCompare(double a, double b)
Tests if two double values are nearly equal.
Definition: MathToolbox.hpp:28
A rotated 2-dimensional ellipse in the plane.
Definition: Ellipse2D.hpp:30
void setCenter(value_type x, value_type y)
Sets the center point of this Ellipse2D.
Definition: Ellipse2D.hpp:116
void setRadius(const Point2D &p)
Sets the radius of this Ellipse. Must be non-negative.
Definition: Ellipse2D.cpp:49
const Point2D & getRadius() const
Returns the radius of this Ellipse.
Definition: Ellipse2D.hpp:97
Ellipse2D()
Constructor for an all-zero Ellipse2D.
Definition: Ellipse2D.cpp:18
bool isNaN(floatT x)
Checks if a floating point value is Not-a-Number (NaN)
Definition: MathToolbox.hpp:63
std::string toString() const
Definition: Ellipse2D.cpp:145
value_type m_rotation
Definition: Ellipse2D.hpp:38


libsick_ldmrs
Author(s): SICK AG , Martin Günther , Jochen Sprickerhof
autogenerated on Sat Jun 8 2019 17:57:33