PositionWGS84.hpp
Go to the documentation of this file.
1 //
2 // PositionWGS84.hpp
3 //
4 // Type of positions in the WGS-84 coordinate system.
5 //
6 // 2011-11-11, Willhvo
7 //
8 
9 #ifndef POSITIONWGS84_HPP
10 #define POSITIONWGS84_HPP
11 
12 #include "../BasicDatatypes.hpp"
13 #include "../tools/MathToolbox.hpp"
14 #include "Point3D.hpp"
15 
16 namespace datatypes
17 {
18 
19 //
20 // Position in the WGS-84 coordinate system.
21 //
22 // WGS-84 coordinates can be provided by several data sources like GPS
23 // receivers, IMUs or other positioning systems.
24 //
25 class PositionWGS84 : public BasicData
26 {
27 public:
28 
34  {
35  Unknown = 0,
44  IMU,
48  };
49 
50  PositionWGS84();
51 
52  virtual ~PositionWGS84();
53 
54  // Estimate the memory usage of this object
55  inline virtual const UINT32 getUsedMemory() const {return (sizeof(*this));};
56 
68  void setMeasurementTime(time_t val) { m_timeOfMeasurement = val; }
69 
87  void setLatitudeInRad(double val);
88 
89  void transformToTangentialPlane(const PositionWGS84& origin, double* easting, double* northing, double* height) const;
90  void transformToTangentialPlane(const PositionWGS84& origin, double* easting, double* northing) const;
91  void transformFromTangentialPlane(double dX, double dY, const PositionWGS84& origin);
92 
98  double distanceToPos(const PositionWGS84& pos) const;
99 
117  void setLatitudeInDeg(double val) { setLatitudeInRad(val * deg2rad); }
118 
119  void setLatitudeInNMEA(double Dm, char H);
120 
137  void setLatitudeInNMEA(double Dm) { setLatitudeInNMEA(Dm, 'N'); }
138 
154  void setLatitudeSigmaInMeter(double val) { m_latitudeSigma = val; }
155 
163  void setLongitudeInRad(double val);
164 
182  void setLongitudeInDeg(double val) { setLongitudeInRad(val * deg2rad); }
183 
201  void setLongitudeInNMEA(double Dm, char H);
202 
219  void setLongitudeInNMEA(double Dm) { setLongitudeInNMEA(Dm, 'E'); }
220 
236  void setLongitudeSigmaInMeter(double val) { m_longitudeSigma = val; }
237 
252  void setAltitudeInMeterMSL(double val) { m_altitudeMSL = val; }
253 
265  void setAltitudeSigmaInMeterMSL(double val) { m_altitudeMSLSigma = val; }
266 
275  void setCourseAngleInRad(double val)
276  {
278  if (m_courseAngle <= 0.0)
279  {
280  m_courseAngle += 2.0 * PI;
281  }
282  }
283 
292  void setCourseAngleInDeg(double val) { setCourseAngleInRad(val * deg2rad); }
293 
305  void setCourseAngleSigmaInRad(double val) { m_courseAngleSigma = val; }
306 
319 
320  void setYawAngleInRad(double val) { m_yawAngle = val; }
321  void setYawAngleInDeg(double val) { setYawAngleInRad(val * deg2rad); }
322 
323  void setYawAngleSigmaInRad(double val) { m_yawAngleSigma = val; }
325 
326  void setPitchAngleInRad(double val) { m_pitchAngle = val; }
327  void setPitchAngleInDeg(double val) { setPitchAngleInRad(val * deg2rad); }
328 
329  void setPitchAngleSigmaInRad(double val) { m_pitchAngleSigma = val; }
331 
332  void setRollAngleInRad(double val) { m_rollAngle = val; }
333  void setRollAngleInDeg(double val) { setRollAngleInRad(val * deg2rad); }
334 
335  void setRollAngleSigmaInRad(double val) { m_rollAngleSigma = val; }
337 
345  void setSource(const PositionWGS84SourceType val) { m_source = val; }
346 
347  void resetToDefault();
348 
350 
355 
363  const time_t& getMeasurementTime() const { return m_timeOfMeasurement; }
364 
372  const time_t& getTimestamp() const { return m_timeOfMeasurement; }
373 
383  double getLatitudeInRad() const { return m_latitude; }
384 
394  double getLatitudeInDeg() const { return (m_latitude * rad2deg); }
395 
405  double getLongitudeInRad() const { return m_longitude; }
406 
416  double getLongitudeInDeg() const { return (m_longitude * rad2deg); }
417 
435  double getCourseAngleInRad() const { return m_courseAngle; }
436 
454  double getCourseAngleInDeg() const { return (m_courseAngle * rad2deg); }
455 
473  double getYawAngleInRad() const { return m_yawAngle; }
474 
492  double getYawAngleInDeg() const { return (m_yawAngle * rad2deg); }
493 
494  double getYawAngleSigmaInRad() const { return m_yawAngleSigma; }
495  double getYawAngleSigmaInDeg() const { return (m_yawAngleSigma * rad2deg); }
496 
497  double getPitchAngleInRad() const { return m_pitchAngle; }
498  double getPitchAngleInDeg() const { return (m_pitchAngle * rad2deg); }
499 
500  double getPitchAngleSigmaInRad() const { return m_pitchAngleSigma; }
501  double getPitchAngleSigmaInDeg() const { return (m_pitchAngleSigma * rad2deg); }
502 
503  double getRollAngleInRad() const { return m_rollAngle; }
504  double getRollAngleInDeg() const { return (m_rollAngle * rad2deg); }
505 
506  double getRollAngleSigmaInRad() const { return m_rollAngleSigma; }
507  double getRollAngleSigmaInDeg() const { return (m_rollAngleSigma * rad2deg); }
508 
510  bool operator==(const PositionWGS84& other) const;
511  bool operator!=(const PositionWGS84& other) const { return !(*this == other); }
512 
514 
520  double getAltitudeInMeterMSL() const { return m_altitudeMSL; }
521 
522  std::string toString() const;
523 
531 
532  std::string getSourceString() const;
533 
534 
541  double dist( const PositionWGS84& pos ) const;
542 
543  Point3D getCartesianRelPos(const PositionWGS84& orign) const;
544 
545 private:
546  double NMEA2rad( double Dm );
547 
549  // NOTE 2008/01/18 (dw) : Change VERSION in cpp file when the interface is changed or bugs are fixed.
550  // Document changes in the HISTORY above.
551  static const std::string VERSION;
552 
554 
555  // Unit Serialized size:
556 // UINT8 m_deviceID; // ID of device + 1 Bytes
557  double m_latitude; // [rad] + 8 Bytes
558  double m_latitudeSigma; // [m] + 8 Bytes
559  double m_longitude; // [rad] + 8 Bytes
560  double m_longitudeSigma; // [m] + 8 Bytes
561  double m_altitudeMSL; // [m] + 8 Bytes
562  double m_altitudeMSLSigma; // [m] + 8 Bytes
563  double m_courseAngle; // [rad] + 8 Bytes
564  double m_courseAngleSigma; // [rad] + 8 Bytes
565  double m_yawAngle; // [rad] + 8 Bytes
566  double m_yawAngleSigma; // [rad] + 8 Bytes
567  double m_pitchAngle; // [rad] + 8 Bytes
568  double m_pitchAngleSigma; // [rad] + 8 Bytes
569  double m_rollAngle; // [rad] + 8 Bytes
570  double m_rollAngleSigma; // [rad] + 8 Bytes
571  PositionWGS84SourceType m_source; // Source of position information + 2 Bytes (encoded as UINT16)
572  // = 115 Bytes
573 };
574 
575 std::string toString(const PositionWGS84::PositionWGS84SourceType& type);
576 
577 
578 } // namespace datatypes
579 
580 
581 
582 #endif // POSITIONWGS84_HPP
PositionWGS84SourceType getSource() const
Returns the type of source that identifies the type of the device that created this object...
double getPitchAngleSigmaInDeg() const
void setLongitudeInRad(double val)
Sets the longitude value of the WGS-84 position.
double getLatitudeInDeg() const
Returns the latitude value of the WGS-84 position.
This class defines a point in the three-dimensional plane.
Definition: Point3D.hpp:25
static const std::string VERSION
void setPitchAngleInDeg(double val)
double getRollAngleInRad() const
bool operator==(const PositionWGS84 &other) const
Equality predicate.
#define rad2deg
void setCourseAngleSigmaInRad(double val)
Sets the sigma of the normal distribution describing the confidence about the course angle...
Point3D getCartesianRelPos(const PositionWGS84 &orign) const
void setYawAngleInDeg(double val)
void setYawAngleSigmaInDeg(double val)
void setYawAngleSigmaInRad(double val)
void setLatitudeSigmaInMeter(double val)
Sets the sigma value of the normal distribution describing the confidence about the latitude measurem...
double getLongitudeInRad() const
Returns the longitude value of the WGS-84 position.
void setRollAngleSigmaInRad(double val)
double getYawAngleSigmaInRad() const
void setMeasurementTime(time_t val)
Sets the time when the position measurement was taken.
uint32_t UINT32
void setRollAngleSigmaInDeg(double val)
PositionWGS84()
Constructor.
void setRollAngleInDeg(double val)
double getLatitudeInRad() const
Returns the latitude value of the WGS-84 position.
double dist(const PositionWGS84 &pos) const
Calculates the distance in [m] from this to position in argument.
void setCourseAngleSigmaInDeg(double val)
Sets the sigma of the normal distribution describing the confidence about the course angle...
void setLatitudeInNMEA(double Dm, char H)
Sets the latitude value of the WGS-84 position.
#define deg2rad
void transformToTangentialPlane(const PositionWGS84 &origin, double *easting, double *northing, double *height) const
double getPitchAngleInRad() const
void setAltitudeSigmaInMeterMSL(double val)
Sets the sigma value of the normal distribution describing the confidence about the altitude measurem...
std::string getSourceString() const
Returns a std::string with a describtion of the WGS-84 position source.
double getCourseAngleInRad() const
Returns the course angle in [rad].
double getRollAngleSigmaInDeg() const
double getLongitudeInDeg() const
Returns the longitude value of the WGS-84 position.
virtual const UINT32 getUsedMemory() const
void setSource(const PositionWGS84SourceType val)
Sets the source of the position measurement.
void setAltitudeInMeterMSL(double val)
Sets altitude value.
void setLatitudeInNMEA(double Dm)
Sets the latitude value of the WGS-84 position.
double NMEA2rad(double Dm)
Calculates the WGS84 coordinate in rad from the mixed degree-minute value usually found on NMEA compa...
double distanceToPos(const PositionWGS84 &pos) const
double getAltitudeInMeterMSL() const
Returns the altitude in meter above mean sea level.
double getPitchAngleSigmaInRad() const
double getPitchAngleInDeg() const
void setCourseAngleInRad(double val)
Sets the course angle.
double getRollAngleInDeg() const
const time_t & getMeasurementTime() const
Returns the time when the position measurement was taken.
const time_t & getTimestamp() const
Returns the time when the position measurement was taken.
void transformFromTangentialPlane(double dX, double dY, const PositionWGS84 &origin)
double getYawAngleInDeg() const
Returns the yaw angle.
double normalizeRadians(double radians)
Definition: MathToolbox.cpp:31
bool operator!=(const PositionWGS84 &other) const
void setPitchAngleSigmaInDeg(double val)
double getYawAngleInRad() const
Returns the yaw angle in [rad].
void setPitchAngleSigmaInRad(double val)
void setLatitudeInDeg(double val)
Sets the latitude value of the WGS-84 position.
PositionWGS84SourceType m_source
void setRollAngleInRad(double val)
void setLatitudeInRad(double val)
Sets the latitude value of the WGS-84 position.
void resetToDefault()
Resets all values of the position to their default values.
void setCourseAngleInDeg(double val)
Sets the course angle.
void setLongitudeInDeg(double val)
Sets the longitude value of the WGS-84 position.
void setLongitudeInNMEA(double Dm, char H)
Sets the longitude value of the WGS-84 position.
void setYawAngleInRad(double val)
void setPitchAngleInRad(double val)
double getCourseAngleInDeg() const
Returns the course angle in [deg].
#define PI
double getRollAngleSigmaInRad() const
void setLongitudeInNMEA(double Dm)
Sets the longitude value of the WGS-84 position.
std::string toString() const
Returns a std::string with a describtion of the WGS-84 position.
double getYawAngleSigmaInDeg() const
void setLongitudeSigmaInMeter(double val)
Sets the sigma value of the normal distribution describing the confidence about the longitude measure...


libsick_ldmrs
Author(s): SICK AG , Martin Günther , Jochen Sprickerhof
autogenerated on Mon Oct 26 2020 03:27:30