9 #ifndef POSITIONWGS84_HPP 10 #define POSITIONWGS84_HPP 12 #include "../BasicDatatypes.hpp" 13 #include "../tools/MathToolbox.hpp" 582 #endif // POSITIONWGS84_HPP
double getLongitudeInDeg() const
Returns the longitude value of the WGS-84 position.
double dist(const PositionWGS84 &pos) const
Calculates the distance in [m] from this to position in argument.
void setLongitudeInRad(double val)
Sets the longitude value of the WGS-84 position.
double getRollAngleInRad() const
This class defines a point in the three-dimensional plane.
double getLatitudeInDeg() const
Returns the latitude value of the WGS-84 position.
static const std::string VERSION
void setPitchAngleInDeg(double val)
double distanceToPos(const PositionWGS84 &pos) const
void setCourseAngleSigmaInRad(double val)
Sets the sigma of the normal distribution describing the confidence about the course angle...
double getPitchAngleInDeg() const
double getPitchAngleInRad() 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 getYawAngleSigmaInDeg() const
void setRollAngleSigmaInRad(double val)
double getCourseAngleInDeg() const
Returns the course angle in [deg].
double getRollAngleInDeg() const
void setMeasurementTime(time_t val)
Sets the time when the position measurement was taken.
void setRollAngleSigmaInDeg(double val)
PositionWGS84()
Constructor.
const time_t & getMeasurementTime() const
Returns the time when the position measurement was taken.
void setRollAngleInDeg(double val)
double getYawAngleInRad() const
Returns the yaw angle in [rad].
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.
virtual const UINT32 getUsedMemory() const
void transformToTangentialPlane(const PositionWGS84 &origin, double *easting, double *northing, double *height) const
std::string getSourceString() const
Returns a std::string with a describtion of the WGS-84 position source.
double getRollAngleSigmaInRad() const
void setAltitudeSigmaInMeterMSL(double val)
Sets the sigma value of the normal distribution describing the confidence about the altitude measurem...
time_t m_timeOfMeasurement
double getLongitudeInRad() const
Returns the longitude value of the WGS-84 position.
double getAltitudeInMeterMSL() const
Returns the altitude in meter above mean sea level.
double getPitchAngleSigmaInDeg() 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 m_altitudeMSLSigma
double getPitchAngleSigmaInRad() const
double getCourseAngleInRad() const
Returns the course angle in [rad].
void setCourseAngleInRad(double val)
Sets the course angle.
double getYawAngleInDeg() const
Returns the yaw angle.
double getLatitudeInRad() const
Returns the latitude value of the WGS-84 position.
std::string toString() const
Returns a std::string with a describtion of the WGS-84 position.
void transformFromTangentialPlane(double dX, double dY, const PositionWGS84 &origin)
double getYawAngleSigmaInRad() const
void setPitchAngleSigmaInDeg(double val)
double getRollAngleSigmaInDeg() const
bool operator==(const PositionWGS84 &other) const
Equality predicate.
void setPitchAngleSigmaInRad(double val)
bool operator!=(const PositionWGS84 &other) const
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.
double m_courseAngleSigma
void setYawAngleInRad(double val)
void setPitchAngleInRad(double val)
PositionWGS84SourceType getSource() const
Returns the type of source that identifies the type of the device that created this object...
void setLongitudeInNMEA(double Dm)
Sets the longitude value of the WGS-84 position.
Point3D getCartesianRelPos(const PositionWGS84 &orign) const
void setLongitudeSigmaInMeter(double val)
Sets the sigma value of the normal distribution describing the confidence about the longitude measure...
const time_t & getTimestamp() const
Returns the time when the position measurement was taken.