Go to the documentation of this file.
9 #ifndef POSITIONWGS84_HPP
10 #define POSITIONWGS84_HPP
12 #include "../BasicDatatypes.hpp"
13 #include "../tools/MathToolbox.hpp"
582 #endif // POSITIONWGS84_HPP
void setLongitudeInRad(double val)
Sets the longitude value of the WGS-84 position.
void setPitchAngleInDeg(double val)
void setRollAngleSigmaInRad(double val)
double getLatitudeInDeg() const
Returns the latitude value of the WGS-84 position.
double getLatitudeInRad() const
Returns the latitude value of the WGS-84 position.
void setLongitudeInNMEA(double Dm, char H)
Sets the longitude value of the WGS-84 position.
double getYawAngleSigmaInRad() const
void setYawAngleInDeg(double val)
PositionWGS84SourceType getSource() const
Returns the type of source that identifies the type of the device that created this object.
bool operator==(const PositionWGS84 &other) const
Equality predicate.
bool operator!=(const PositionWGS84 &other) const
void setLongitudeInNMEA(double Dm)
Sets the longitude value of the WGS-84 position.
double m_courseAngleSigma
void setMeasurementTime(time_t val)
Sets the time when the position measurement was taken.
double NMEA2rad(double Dm)
Calculates the WGS84 coordinate in rad from the mixed degree-minute value usually found on NMEA compa...
void setLongitudeInDeg(double val)
Sets the longitude value of the WGS-84 position.
double getLongitudeInRad() const
Returns the longitude value of the WGS-84 position.
virtual const UINT32 getUsedMemory() const
double getLongitudeInDeg() const
Returns the longitude value of the WGS-84 position.
void setSource(const PositionWGS84SourceType val)
Sets the source of the position measurement.
void setAltitudeInMeterMSL(double val)
Sets altitude value.
std::string getSourceString() const
Returns a std::string with a describtion of the WGS-84 position source.
double getPitchAngleInDeg() const
void setYawAngleInRad(double val)
void setPitchAngleSigmaInDeg(double val)
double getPitchAngleInRad() const
void setPitchAngleInRad(double val)
double getYawAngleSigmaInDeg() const
double dist(const PositionWGS84 &pos) const
Calculates the distance in [m] from this to position in argument.
time_t m_timeOfMeasurement
double getRollAngleInDeg() const
double getCourseAngleInDeg() const
Returns the course angle in [deg].
void setCourseAngleSigmaInRad(double val)
Sets the sigma of the normal distribution describing the confidence about the course angle.
PositionWGS84()
Constructor.
void setRollAngleInDeg(double val)
void setYawAngleSigmaInRad(double val)
double getAltitudeInMeterMSL() const
Returns the altitude in meter above mean sea level.
This class defines a point in the three-dimensional plane.
double getPitchAngleSigmaInDeg() const
void setLatitudeInNMEA(double Dm, char H)
Sets the latitude value of the WGS-84 position.
void transformToTangentialPlane(const PositionWGS84 &origin, double *easting, double *northing, double *height) const
double getCourseAngleInRad() const
Returns the course angle in [rad].
void setAltitudeSigmaInMeterMSL(double val)
Sets the sigma value of the normal distribution describing the confidence about the altitude measurem...
double getYawAngleInDeg() const
Returns the yaw angle.
double getRollAngleSigmaInRad() const
std::string toString(const PositionWGS84::PositionWGS84SourceType &type)
double getYawAngleInRad() const
Returns the yaw angle in [rad].
double getRollAngleSigmaInDeg() const
void setYawAngleSigmaInDeg(double val)
void setLatitudeInRad(double val)
Sets the latitude value of the WGS-84 position.
static const std::string VERSION
PositionWGS84SourceType m_source
void setLatitudeInNMEA(double Dm)
Sets the latitude value of the WGS-84 position.
double getPitchAngleSigmaInRad() const
void setCourseAngleSigmaInDeg(double val)
Sets the sigma of the normal distribution describing the confidence about the course angle.
void setCourseAngleInRad(double val)
Sets the course angle.
double distanceToPos(const PositionWGS84 &pos) const
void transformFromTangentialPlane(double dX, double dY, const PositionWGS84 &origin)
const time_t & getTimestamp() const
Returns the time when the position measurement was taken.
std::string toString() const
Returns a std::string with a describtion of the WGS-84 position.
void setLongitudeSigmaInMeter(double val)
Sets the sigma value of the normal distribution describing the confidence about the longitude measure...
const time_t & getMeasurementTime() const
Returns the time when the position measurement was taken.
void setPitchAngleSigmaInRad(double val)
Point3D getCartesianRelPos(const PositionWGS84 &orign) const
double getRollAngleInRad() const
void setRollAngleInRad(double val)
void resetToDefault()
Resets all values of the position to their default values.
void setCourseAngleInDeg(double val)
Sets the course angle.
void setRollAngleSigmaInDeg(double val)
double m_altitudeMSLSigma
void setLatitudeSigmaInMeter(double val)
Sets the sigma value of the normal distribution describing the confidence about the latitude measurem...
void setLatitudeInDeg(double val)
Sets the latitude value of the WGS-84 position.
libsick_ldmrs
Author(s): SICK AG
, Martin Günther , Jochen Sprickerhof
autogenerated on Wed Oct 26 2022 02:11:57