PositionWGS84.hpp
Go to the documentation of this file.
00001 //
00002 // PositionWGS84.hpp
00003 //
00004 // Type of positions in the WGS-84 coordinate system.
00005 //
00006 // 2011-11-11, Willhvo
00007 //
00008 
00009 #ifndef POSITIONWGS84_HPP
00010 #define POSITIONWGS84_HPP
00011 
00012 #include "../BasicDatatypes.hpp"
00013 #include "../tools/MathToolbox.hpp"
00014 #include "Point3D.hpp"
00015 
00016 namespace datatypes
00017 {
00018         
00019 //
00020 // Position in the WGS-84 coordinate system.
00021 //
00022 // WGS-84 coordinates can be provided by several data sources like GPS
00023 // receivers, IMUs or other positioning systems.
00024 //
00025 class PositionWGS84 : public BasicData
00026 {
00027 public:
00028 
00033         enum PositionWGS84SourceType
00034         {
00035                 Unknown = 0,
00036                 GPS_SPS,
00037                 GPS_PPS,
00038                 GPS_SBAS,
00039                 GPS_SBAS_Omnistar_VBS,
00040                 GPS_SBAS_Omnistar_HP,
00041                 GPS_GBAS,
00042                 GPS_GBAS_RTK_Float,
00043                 GPS_GBAS_RTK_Integer,
00044                 IMU,
00045                 LandmarkPositioning,
00046                 Manual,
00047                 CAN
00048         };
00049 
00050         PositionWGS84();
00051 
00052         virtual ~PositionWGS84();
00053 
00054         // Estimate the memory usage of this object
00055         inline virtual const UINT32 getUsedMemory() const {return (sizeof(*this));};
00056         
00068         void setMeasurementTime(time_t val) { m_timeOfMeasurement = val; }
00069 
00087         void setLatitudeInRad(double val);
00088 
00089         void transformToTangentialPlane(const PositionWGS84& origin, double* easting, double* northing, double* height) const;
00090         void transformToTangentialPlane(const PositionWGS84& origin, double* easting, double* northing) const;
00091         void transformFromTangentialPlane(double dX, double dY, const PositionWGS84& origin);
00092 
00098         double distanceToPos(const PositionWGS84& pos) const;
00099 
00117         void setLatitudeInDeg(double val) { setLatitudeInRad(val * deg2rad); }
00118 
00119         void setLatitudeInNMEA(double Dm, char H);
00120 
00137         void setLatitudeInNMEA(double Dm) { setLatitudeInNMEA(Dm, 'N'); }
00138 
00154         void setLatitudeSigmaInMeter(double val) { m_latitudeSigma = val; }
00155 
00163         void setLongitudeInRad(double val);
00164 
00182         void setLongitudeInDeg(double val) { setLongitudeInRad(val * deg2rad); }
00183 
00201         void setLongitudeInNMEA(double Dm, char H);
00202 
00219         void setLongitudeInNMEA(double Dm) { setLongitudeInNMEA(Dm, 'E'); }
00220 
00236         void setLongitudeSigmaInMeter(double val) { m_longitudeSigma = val; }
00237 
00252         void setAltitudeInMeterMSL(double val) { m_altitudeMSL = val; }
00253 
00265         void setAltitudeSigmaInMeterMSL(double val) { m_altitudeMSLSigma = val; }
00266 
00275         void setCourseAngleInRad(double val)
00276         {
00277                 m_courseAngle = normalizeRadians(val);
00278                 if (m_courseAngle <= 0.0)
00279                 {
00280                         m_courseAngle += 2.0 * PI;
00281                 }
00282         }
00283 
00292         void setCourseAngleInDeg(double val) { setCourseAngleInRad(val * deg2rad); }
00293 
00305         void setCourseAngleSigmaInRad(double val) { m_courseAngleSigma = val; }
00306 
00318         void setCourseAngleSigmaInDeg(double val) { setCourseAngleSigmaInRad(val * deg2rad); }
00319 
00320         void setYawAngleInRad(double val) { m_yawAngle = val; }
00321         void setYawAngleInDeg(double val) { setYawAngleInRad(val * deg2rad); }
00322 
00323         void setYawAngleSigmaInRad(double val) { m_yawAngleSigma = val; }
00324         void setYawAngleSigmaInDeg(double val) { setYawAngleSigmaInRad(val * deg2rad); }
00325 
00326         void setPitchAngleInRad(double val) { m_pitchAngle = val; }
00327         void setPitchAngleInDeg(double val) { setPitchAngleInRad(val * deg2rad); }
00328 
00329         void setPitchAngleSigmaInRad(double val) { m_pitchAngleSigma = val; }
00330         void setPitchAngleSigmaInDeg(double val) { setPitchAngleSigmaInRad(val * deg2rad); }
00331 
00332         void setRollAngleInRad(double val) { m_rollAngle = val; }
00333         void setRollAngleInDeg(double val) { setRollAngleInRad(val * deg2rad); }
00334 
00335         void setRollAngleSigmaInRad(double val) { m_rollAngleSigma = val; }
00336         void setRollAngleSigmaInDeg(double val) { setRollAngleSigmaInRad(val * deg2rad); }
00337 
00345         void setSource(const PositionWGS84SourceType val) { m_source = val; }
00346 
00347         void resetToDefault();
00348 
00350 
00355 
00363         const time_t& getMeasurementTime() const { return m_timeOfMeasurement; }
00364 
00372         const time_t& getTimestamp() const { return m_timeOfMeasurement; }
00373 
00383         double getLatitudeInRad() const { return m_latitude; }
00384 
00394         double getLatitudeInDeg() const { return (m_latitude * rad2deg); }
00395 
00405         double getLongitudeInRad() const { return m_longitude; }
00406 
00416         double getLongitudeInDeg() const { return (m_longitude * rad2deg); }
00417 
00435         double getCourseAngleInRad() const { return m_courseAngle; }
00436 
00454         double getCourseAngleInDeg() const { return (m_courseAngle * rad2deg); }
00455 
00473         double getYawAngleInRad() const { return m_yawAngle; }
00474 
00492         double getYawAngleInDeg() const { return (m_yawAngle * rad2deg); }
00493 
00494         double getYawAngleSigmaInRad() const { return m_yawAngleSigma; }
00495         double getYawAngleSigmaInDeg() const { return (m_yawAngleSigma * rad2deg); }
00496 
00497         double getPitchAngleInRad() const { return m_pitchAngle; }
00498         double getPitchAngleInDeg() const { return (m_pitchAngle * rad2deg); }
00499 
00500         double getPitchAngleSigmaInRad() const { return m_pitchAngleSigma; }
00501         double getPitchAngleSigmaInDeg() const { return (m_pitchAngleSigma * rad2deg); }
00502 
00503         double getRollAngleInRad() const { return m_rollAngle; }
00504         double getRollAngleInDeg() const { return (m_rollAngle * rad2deg); }
00505 
00506         double getRollAngleSigmaInRad() const { return m_rollAngleSigma; }
00507         double getRollAngleSigmaInDeg() const { return (m_rollAngleSigma * rad2deg); }
00508 
00510         bool operator==(const PositionWGS84& other) const;
00511         bool operator!=(const PositionWGS84& other) const { return !(*this == other); }
00512 
00514 
00520         double getAltitudeInMeterMSL() const { return m_altitudeMSL; }
00521 
00522         std::string toString() const;
00523 
00530         PositionWGS84SourceType getSource() const { return m_source; }
00531 
00532         std::string getSourceString() const;
00533 
00534         
00541         double dist( const PositionWGS84& pos ) const;
00542 
00543         Point3D getCartesianRelPos(const PositionWGS84& orign) const;
00544 
00545 private:
00546         double NMEA2rad( double Dm );
00547 
00549         // NOTE 2008/01/18 (dw) : Change VERSION in cpp file when the interface is changed or bugs are fixed.
00550         //                                                Document changes in the HISTORY above.
00551         static const std::string VERSION;
00552 
00553         time_t  m_timeOfMeasurement;
00554 
00555         //                                                                 Unit                                                         Serialized size:
00556 //      UINT8 m_deviceID;                               // ID of device                                         + 1 Bytes
00557         double m_latitude;                              // [rad]                                                        + 8 Bytes
00558         double m_latitudeSigma;                 // [m]                                                          + 8 Bytes
00559         double m_longitude;                             // [rad]                                                        + 8 Bytes
00560         double m_longitudeSigma;                // [m]                                                          + 8 Bytes
00561         double m_altitudeMSL;                   // [m]                                                          + 8 Bytes
00562         double m_altitudeMSLSigma;              // [m]                                                          + 8 Bytes
00563         double m_courseAngle;                   // [rad]                                                        + 8 Bytes
00564         double m_courseAngleSigma;              // [rad]                                                        + 8 Bytes
00565         double m_yawAngle;                              // [rad]                                                        + 8 Bytes
00566         double m_yawAngleSigma;                 // [rad]                                                        + 8 Bytes
00567         double m_pitchAngle;                    // [rad]                                                        + 8 Bytes
00568         double m_pitchAngleSigma;               // [rad]                                                        + 8 Bytes
00569         double m_rollAngle;                             // [rad]                                                        + 8 Bytes
00570         double m_rollAngleSigma;                // [rad]                                                        + 8 Bytes
00571         PositionWGS84SourceType m_source;                       // Source of position information       + 2 Bytes (encoded as UINT16)
00572         //                                                                                                                                      = 115 Bytes
00573 };
00574 
00575 std::string toString(const PositionWGS84::PositionWGS84SourceType& type);
00576 
00577 
00578 }       // namespace datatypes
00579 
00580 
00581 
00582 #endif // POSITIONWGS84_HPP


libsick_ldmrs
Author(s): SICK AG , Martin Günther , Jochen Sprickerhof
autogenerated on Wed Jun 14 2017 04:04:50