Public Types | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
datatypes::PositionWGS84 Class Reference

#include <PositionWGS84.hpp>

Inheritance diagram for datatypes::PositionWGS84:
Inheritance graph
[legend]

Public Types

enum  PositionWGS84SourceType {
  Unknown = 0, GPS_SPS, GPS_PPS, GPS_SBAS,
  GPS_SBAS_Omnistar_VBS, GPS_SBAS_Omnistar_HP, GPS_GBAS, GPS_GBAS_RTK_Float,
  GPS_GBAS_RTK_Integer, IMU, LandmarkPositioning, Manual,
  CAN
}
 

Public Member Functions

double dist (const PositionWGS84 &pos) const
 Calculates the distance in [m] from this to position in argument. More...
 
double getAltitudeInMeterMSL () const
 Returns the altitude in meter above mean sea level. More...
 
Point3D getCartesianRelPos (const PositionWGS84 &orign) const
 
PositionWGS84SourceType getSource () const
 Returns the type of source that identifies the type of the device that created this object. More...
 
std::string getSourceString () const
 Returns a std::string with a describtion of the WGS-84 position source. More...
 
virtual const UINT32 getUsedMemory () const
 
 PositionWGS84 ()
 Constructor. More...
 
std::string toString () const
 Returns a std::string with a describtion of the WGS-84 position. More...
 
virtual ~PositionWGS84 ()
 
Setter methods

Use these methods to change the object'S data fields.

void setMeasurementTime (time_t val)
 Sets the time when the position measurement was taken. More...
 
void setLatitudeInRad (double val)
 Sets the latitude value of the WGS-84 position. More...
 
void transformToTangentialPlane (const PositionWGS84 &origin, double *easting, double *northing, double *height) const
 
void transformToTangentialPlane (const PositionWGS84 &origin, double *easting, double *northing) const
 
void transformFromTangentialPlane (double dX, double dY, const PositionWGS84 &origin)
 
double distanceToPos (const PositionWGS84 &pos) const
 
void setLatitudeInDeg (double val)
 Sets the latitude value of the WGS-84 position. More...
 
void setLatitudeInNMEA (double Dm, char H)
 Sets the latitude value of the WGS-84 position. More...
 
void setLatitudeInNMEA (double Dm)
 Sets the latitude value of the WGS-84 position. More...
 
void setLatitudeSigmaInMeter (double val)
 Sets the sigma value of the normal distribution describing the confidence about the latitude measurement. More...
 
void setLongitudeInRad (double val)
 Sets the longitude value of the WGS-84 position. More...
 
void setLongitudeInDeg (double val)
 Sets the longitude value of the WGS-84 position. More...
 
void setLongitudeInNMEA (double Dm, char H)
 Sets the longitude value of the WGS-84 position. More...
 
void setLongitudeInNMEA (double Dm)
 Sets the longitude value of the WGS-84 position. More...
 
void setLongitudeSigmaInMeter (double val)
 Sets the sigma value of the normal distribution describing the confidence about the longitude measurement. More...
 
void setAltitudeInMeterMSL (double val)
 Sets altitude value. More...
 
void setAltitudeSigmaInMeterMSL (double val)
 Sets the sigma value of the normal distribution describing the confidence about the altitude measurement. More...
 
void setCourseAngleInRad (double val)
 Sets the course angle. More...
 
void setCourseAngleInDeg (double val)
 Sets the course angle. More...
 
void setCourseAngleSigmaInRad (double val)
 Sets the sigma of the normal distribution describing the confidence about the course angle. More...
 
void setCourseAngleSigmaInDeg (double val)
 Sets the sigma of the normal distribution describing the confidence about the course angle. More...
 
void setYawAngleInRad (double val)
 
void setYawAngleInDeg (double val)
 
void setYawAngleSigmaInRad (double val)
 
void setYawAngleSigmaInDeg (double val)
 
void setPitchAngleInRad (double val)
 
void setPitchAngleInDeg (double val)
 
void setPitchAngleSigmaInRad (double val)
 
void setPitchAngleSigmaInDeg (double val)
 
void setRollAngleInRad (double val)
 
void setRollAngleInDeg (double val)
 
void setRollAngleSigmaInRad (double val)
 
void setRollAngleSigmaInDeg (double val)
 
void setSource (const PositionWGS84SourceType val)
 Sets the source of the position measurement. More...
 
void resetToDefault ()
 Resets all values of the position to their default values. More...
 
Getter methods

Use these methods to retrieve position information.

const time_t & getMeasurementTime () const
 Returns the time when the position measurement was taken. More...
 
const time_t & getTimestamp () const
 Returns the time when the position measurement was taken. More...
 
double getLatitudeInRad () const
 Returns the latitude value of the WGS-84 position. More...
 
double getLatitudeInDeg () const
 Returns the latitude value of the WGS-84 position. More...
 
double getLongitudeInRad () const
 Returns the longitude value of the WGS-84 position. More...
 
double getLongitudeInDeg () const
 Returns the longitude value of the WGS-84 position. More...
 
double getCourseAngleInRad () const
 Returns the course angle in [rad]. More...
 
double getCourseAngleInDeg () const
 Returns the course angle in [deg]. More...
 
double getYawAngleInRad () const
 Returns the yaw angle in [rad]. More...
 
double getYawAngleInDeg () const
 Returns the yaw angle. More...
 
double getYawAngleSigmaInRad () const
 
double getYawAngleSigmaInDeg () const
 
double getPitchAngleInRad () const
 
double getPitchAngleInDeg () const
 
double getPitchAngleSigmaInRad () const
 
double getPitchAngleSigmaInDeg () const
 
double getRollAngleInRad () const
 
double getRollAngleInDeg () const
 
double getRollAngleSigmaInRad () const
 
double getRollAngleSigmaInDeg () const
 
bool operator== (const PositionWGS84 &other) const
 Equality predicate. More...
 
bool operator!= (const PositionWGS84 &other) const
 
- Public Member Functions inherited from datatypes::BasicData
 BasicData ()
 
UINT16 getDatatype ()
 
UINT16 getSourceId ()
 
virtual void setSourceId (UINT16 id)
 
virtual ~BasicData ()
 

Private Member Functions

double NMEA2rad (double Dm)
 Calculates the WGS84 coordinate in rad from the mixed degree-minute value usually found on NMEA compatible GPS receivers. More...
 

Private Attributes

double m_altitudeMSL
 
double m_altitudeMSLSigma
 
double m_courseAngle
 
double m_courseAngleSigma
 
double m_latitude
 
double m_latitudeSigma
 
double m_longitude
 
double m_longitudeSigma
 
double m_pitchAngle
 
double m_pitchAngleSigma
 
double m_rollAngle
 
double m_rollAngleSigma
 
PositionWGS84SourceType m_source
 
time_t m_timeOfMeasurement
 
double m_yawAngle
 
double m_yawAngleSigma
 

Static Private Attributes

static const std::string VERSION
 

Additional Inherited Members

- Protected Attributes inherited from datatypes::BasicData
UINT16 m_datatype
 
UINT16 m_sourceId
 

Detailed Description

Definition at line 25 of file PositionWGS84.hpp.

Member Enumeration Documentation

that provide WGS-84 position information.

Enumerator
Unknown 
GPS_SPS 
GPS_PPS 
GPS_SBAS 
GPS_SBAS_Omnistar_VBS 
GPS_SBAS_Omnistar_HP 
GPS_GBAS 
GPS_GBAS_RTK_Float 
GPS_GBAS_RTK_Integer 
IMU 
LandmarkPositioning 
Manual 
CAN 

Definition at line 33 of file PositionWGS84.hpp.

Constructor & Destructor Documentation

datatypes::PositionWGS84::PositionWGS84 ( )

Constructor.

All values are initialized with default values: latitude, longitude, and altitude are set to zero, all sigma values are set to negative values and the source is set to SourceType::Unknown.

Definition at line 23 of file PositionWGS84.cpp.

datatypes::PositionWGS84::~PositionWGS84 ( )
virtual

Definition at line 29 of file PositionWGS84.cpp.

Member Function Documentation

double datatypes::PositionWGS84::dist ( const PositionWGS84 pos) const

Calculates the distance in [m] from this to position in argument.

Parameters
[in]posPosition of other point on planet.
Returns
Distance in [m] between the two positions.

Definition at line 228 of file PositionWGS84.cpp.

double datatypes::PositionWGS84::distanceToPos ( const PositionWGS84 pos) const

Returns the distance, in [m], to the given position. Note that this distance is reliable only in the vicinity of our position, for some 100 m, before the curvature of the earth introduces a relatively high error.

Definition at line 34 of file PositionWGS84.cpp.

double datatypes::PositionWGS84::getAltitudeInMeterMSL ( ) const
inline

Returns the altitude in meter above mean sea level.

Returns
Altitude in [m] above mean sea level (MSL).

Definition at line 520 of file PositionWGS84.hpp.

Point3D datatypes::PositionWGS84::getCartesianRelPos ( const PositionWGS84 orign) const

Get a cartesian coordinate from the latitude/longitude position relative to the gigen reference point (origin). Note: this function is only valid, if the reference point is not to far (some km) from the given reference point.

Definition at line 400 of file PositionWGS84.cpp.

double datatypes::PositionWGS84::getCourseAngleInDeg ( ) const
inline

Returns the course angle in [deg].

The course angle is the angle the vehicle is travelling to. If you drift, it's different to the yaw angle, which is the direction of the vehicle is heading/looking at.

The angle in between is called slip angle.

The angle is always counted positive in counter-clockwise direction, since in our system the z-axis is pointing upwards.

Example: If the car is heading to the north, but driving backwards, the yaw angle is 0 degrees and the course angle 180 degrees.

Returns
Course angle in [deg]. (0 = North, 90 = West)

Definition at line 454 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getCourseAngleInRad ( ) const
inline

Returns the course angle in [rad].

The course angle is the angle the vehicle is travelling to. If you drift, it's different to the yaw angle, which is the direction of the vehicle is heading/looking at.

The angle in between is called slip angle.

The angle is always counted positive in counter-clockwise direction, since in our system the z-axis is pointing upwards.

Example: If the car is heading to the north, but driving backwards, the yaw angle is 0 degrees and the course angle 180 degrees.

Returns
Course angle in [rad]. (0 = North, pi/2 = West)

Definition at line 435 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getLatitudeInDeg ( ) const
inline

Returns the latitude value of the WGS-84 position.

Returns
Latitude value in [deg].
See also
getLatitudeInRad()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 394 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getLatitudeInRad ( ) const
inline

Returns the latitude value of the WGS-84 position.

Returns
Latitude value in [rad].
See also
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 383 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getLongitudeInDeg ( ) const
inline

Returns the longitude value of the WGS-84 position.

Returns
Longitude value in [deg].
See also
getLongitudeInRad()
getLatitudeInRad()
getLatitudeInDeg()

Definition at line 416 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getLongitudeInRad ( ) const
inline

Returns the longitude value of the WGS-84 position.

Returns
Longitude value in [rad].
See also
getLongitudeInRad()
getLatitudeInRad()
getLatitudeInDeg()

Definition at line 405 of file PositionWGS84.hpp.

const time_t& datatypes::PositionWGS84::getMeasurementTime ( ) const
inline

Returns the time when the position measurement was taken.

The time should be as close to the real measurement time as possible.

Returns
Time specific to the measurement device.

Definition at line 363 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getPitchAngleInDeg ( ) const
inline

Definition at line 498 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getPitchAngleInRad ( ) const
inline

Definition at line 497 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getPitchAngleSigmaInDeg ( ) const
inline

Definition at line 501 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getPitchAngleSigmaInRad ( ) const
inline

Definition at line 500 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getRollAngleInDeg ( ) const
inline

Definition at line 504 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getRollAngleInRad ( ) const
inline

Definition at line 503 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getRollAngleSigmaInDeg ( ) const
inline

Definition at line 507 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getRollAngleSigmaInRad ( ) const
inline

Definition at line 506 of file PositionWGS84.hpp.

PositionWGS84SourceType datatypes::PositionWGS84::getSource ( ) const
inline

Returns the type of source that identifies the type of the device that created this object.

Returns
Type of source that created this object.

Definition at line 530 of file PositionWGS84.hpp.

std::string datatypes::PositionWGS84::getSourceString ( ) const

Returns a std::string with a describtion of the WGS-84 position source.

Returns
String with current source description.

Definition at line 223 of file PositionWGS84.cpp.

const time_t& datatypes::PositionWGS84::getTimestamp ( ) const
inline

Returns the time when the position measurement was taken.

The time should be as close to the real measurement time as possible.

Returns
UTC time stamp of measurement recording time.

Definition at line 372 of file PositionWGS84.hpp.

virtual const UINT32 datatypes::PositionWGS84::getUsedMemory ( ) const
inlinevirtual

Implements datatypes::BasicData.

Definition at line 55 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getYawAngleInDeg ( ) const
inline

Returns the yaw angle.

The yaw angle is the angle the vehicle is heading/looking at. If you drift, it's different to the course angle, which is the direction of travelling or the track angle.

The angle in between is called slip angle.

The angle is always counted positive in counter-clockwise direction, since in our system the z-axis is pointing upwards.

Example: If the car is heading to the north, but driving backwards, the yaw angle is 0 degrees and the course angle 180 degrees.

Returns
Yaw angle in [deg]. (0 = North, 90 = West)

Definition at line 492 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getYawAngleInRad ( ) const
inline

Returns the yaw angle in [rad].

The yaw angle is the angle the vehicle is heading/looking at. If you drift, it's different to the course angle, which is the direction of travelling or the track angle.

The angle in between is called slip angle.

The angle is always counted positive in counter-clockwise direction, since in our system the z-axis is pointing upwards.

Example: If the car is heading to the north, but driving backwards, the yaw angle is 0 degrees and the course angle 180 degrees.

Returns
Yaw angle in [rad]. (0 = North, pi/2 = West)

Definition at line 473 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getYawAngleSigmaInDeg ( ) const
inline

Definition at line 495 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::getYawAngleSigmaInRad ( ) const
inline

Definition at line 494 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::NMEA2rad ( double  Dm)
private

Calculates the WGS84 coordinate in rad from the mixed degree-minute value usually found on NMEA compatible GPS receivers.

Parameters
[in]DmMixed degree-minute value DDDmm.mmmm
Returns
Angle in [rad].

Definition at line 123 of file PositionWGS84.cpp.

bool datatypes::PositionWGS84::operator!= ( const PositionWGS84 other) const
inline

Definition at line 511 of file PositionWGS84.hpp.

bool datatypes::PositionWGS84::operator== ( const PositionWGS84 other) const

Equality predicate.

Definition at line 43 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::resetToDefault ( )

Resets all values of the position to their default values.

See also
PositionWGS84()

Definition at line 71 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::setAltitudeInMeterMSL ( double  val)
inline

Sets altitude value.

This function sets the altitude above the mean sea level (MSL) in [m].

Parameters
[in]valAltitude value in [m].
See also
setLongitudeInRad()
setLongitudeInDeg()
setLongitudeInNMEA()
setLatitudeInRad()
setLatitudeInDeg()
setLatitudeInNMEA()

Definition at line 252 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setAltitudeSigmaInMeterMSL ( double  val)
inline

Sets the sigma value of the normal distribution describing the confidence about the altitude measurement.

Negative values mean that no accuracy knowledge is available.

Parameters
[in]valSigma value in [m].
See also
setLongitudeSigmaInMeter()
setLatitudeSigmaInMeter()

Definition at line 265 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setCourseAngleInDeg ( double  val)
inline

Sets the course angle.

Parameters
[in]valCourse angle value in [deg]. (0 = North, 90 = West)
See also
setCourseAngleInRad()
setCourceAngleSigma()

Definition at line 292 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setCourseAngleInRad ( double  val)
inline

Sets the course angle.

Parameters
[in]valCourse angle value in [rad].
See also
setCourseAngleInDeg()
setCourceAngleSigma()

Definition at line 275 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setCourseAngleSigmaInDeg ( double  val)
inline

Sets the sigma of the normal distribution describing the confidence about the course angle.

Negative values mean that no accuracy knowledge is available.

Parameters
[in]valSigma value in [dev].
See also
setCourseAngleInRad()
setCourseAngleInDeg()

Definition at line 318 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setCourseAngleSigmaInRad ( double  val)
inline

Sets the sigma of the normal distribution describing the confidence about the course angle.

Negative values mean that no accuracy knowledge is available.

Parameters
[in]valSigma value in [rad].
See also
setCourseAngleInRad()
setCourseAngleInDeg()

Definition at line 305 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setLatitudeInDeg ( double  val)
inline

Sets the latitude value of the WGS-84 position.

Parameters
[in]valLatitude value in [deg]. Must be in the interval [-90,90] degree.
See also
setLatitudeInRad()
setLatitudeInNMEA()
setLongitudeInRad()
setLongitudeInDeg()
setLongitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 117 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setLatitudeInNMEA ( double  Dm,
char  H 
)

Sets the latitude value of the WGS-84 position.

Parameters
[in]DmLatitude value [0...9000] where format is DDmm.mmmmm. D stands for value in degree and m for value in decimal minutes.
[in]HHemisphere. For Latitude it can be [N]orth or [S]outh.
See also
setLatitudeInDeg()
setLatitudeInRad()
setLongitudeInRad()
setLongitudeInDeg()
setLongitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 148 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::setLatitudeInNMEA ( double  Dm)
inline

Sets the latitude value of the WGS-84 position.

Parameters
[in]DmLatitude value in DDmm.mmmmm, where D stands for value in degree and m for value in decimal minutes (signed).
See also
setLatitudeInDeg()
setLatitudeInRad()
setLongitudeInRad()
setLongitudeInDeg()
setLongitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 137 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setLatitudeInRad ( double  val)

Sets the latitude value of the WGS-84 position.

Parameters
[in]valLatitude value in [rad]. Must be in the interval [-Pi/2, Pi/2] radians which corresponds to [-90,90] degree.
See also
setLatitudeInDeg()
setLatitudeInNMEA()
setLongitudeInRad()
setLongitudeInDeg()
setLongitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 91 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::setLatitudeSigmaInMeter ( double  val)
inline

Sets the sigma value of the normal distribution describing the confidence about the latitude measurement.

Negative values mean that no accuracy knowledge is available.

ATTENTION: Sigma value is stored in meter. If you use the value in combination with the latitude value be aware that the units differ!

Parameters
[in]valSigma value in [m].
See also
setLongitudeSigmaInMeter()
setAltitudeInMeter()

Definition at line 154 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setLongitudeInDeg ( double  val)
inline

Sets the longitude value of the WGS-84 position.

Parameters
[in]valLongitude value in [deg]. Must be in the range [-180, 180] degree.
See also
setLongitudeInRad()
setLongitudeInNMEA()
setLatitudeInRad()
setLatitudeInDeg()
setLatitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 182 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setLongitudeInNMEA ( double  Dm,
char  H 
)

Sets the longitude value of the WGS-84 position.

Parameters
[in]DmLatitude value in DDmm.mmmmm, where D stands for value in degree and m for value in decimal minutes.
[in]HHemisphere. For longitude it can be [W]est or [E]ast.
See also
setLongitudeInRad()
setLongitudeInDeg()
setLatitudeInRad()
setLatitudeInDeg()
setLatitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()
Parameters
[in]DmLongitude value [0...18000] where format is DDDmm.mmmmm. D stands for value in degree and m for value in decimal minutes.
[in]HHemisphere. For Longitude it can be [W]est or [E]ast.
See also
setLongitudeInDeg()
setLongitudeInNMEA()
setLatitudeInRad()
setLatitudeInDeg()
setLatitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 177 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::setLongitudeInNMEA ( double  Dm)
inline

Sets the longitude value of the WGS-84 position.

Parameters
[in]DmLatitude value in DDmm.mmmmm, where D stands for value in degree and m for value in decimal minutes (signed).
See also
setLongitudeInRad()
setLongitudeInDeg()
setLatitudeInRad()
setLatitudeInDeg()
setLatitudeInNMEA()
setAltitudeInMeter()
getLatitudeInRad()
getLatitudeInDeg()
getLongitudeInRad()
getLongitudeInDeg()

Definition at line 219 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setLongitudeInRad ( double  val)

Sets the longitude value of the WGS-84 position.

Parameters
[in]valLongitude value in [deg]. Must be in the range [-Pi, Pi] radians which corresponds to [-180, 180] degree.

Definition at line 104 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::setLongitudeSigmaInMeter ( double  val)
inline

Sets the sigma value of the normal distribution describing the confidence about the longitude measurement.

Negative values mean that no accuracy knowledge is available.

ATTENTION: Sigma value is stored in meter. If you use the value in combination with the longitude value be aware that the units differ!

Parameters
[in]valSigma value in [m].
See also
setLatitudeSigmaInMeter()
setAltitudeSigmaInMeter()

Definition at line 236 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setMeasurementTime ( time_t  val)
inline

Sets the time when the position measurement was taken.

The time should be as close to the real measurement time as possible.

Parameters
[in]valTime specific to the measurement device.

Definition at line 68 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setPitchAngleInDeg ( double  val)
inline

Definition at line 327 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setPitchAngleInRad ( double  val)
inline

Definition at line 326 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setPitchAngleSigmaInDeg ( double  val)
inline

Definition at line 330 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setPitchAngleSigmaInRad ( double  val)
inline

Definition at line 329 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setRollAngleInDeg ( double  val)
inline

Definition at line 333 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setRollAngleInRad ( double  val)
inline

Definition at line 332 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setRollAngleSigmaInDeg ( double  val)
inline

Definition at line 336 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setRollAngleSigmaInRad ( double  val)
inline

Definition at line 335 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setSource ( const PositionWGS84SourceType  val)
inline

Sets the source of the position measurement.

Parameters
[in]valSource of measurement.
See also
SourceType

Definition at line 345 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setYawAngleInDeg ( double  val)
inline

Definition at line 321 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setYawAngleInRad ( double  val)
inline

Definition at line 320 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setYawAngleSigmaInDeg ( double  val)
inline

Definition at line 324 of file PositionWGS84.hpp.

void datatypes::PositionWGS84::setYawAngleSigmaInRad ( double  val)
inline

Definition at line 323 of file PositionWGS84.hpp.

std::string datatypes::PositionWGS84::toString ( ) const

Returns a std::string with a describtion of the WGS-84 position.

Returns
String with describtion.

Definition at line 195 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::transformFromTangentialPlane ( double  dX,
double  dY,
const PositionWGS84 origin 
)

transformFromTangentialPlane()

Inverse function of transformToTangentialPlane: Generates this point from x-y-coordinates on a tangential plane defined by the origin. Note that the x-y-coordinates should be somewhat close to the origin to get accurate results.

Definition at line 322 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::transformToTangentialPlane ( const PositionWGS84 origin,
double *  easting,
double *  northing,
double *  height 
) const

Definition at line 250 of file PositionWGS84.cpp.

void datatypes::PositionWGS84::transformToTangentialPlane ( const PositionWGS84 origin,
double *  easting,
double *  northing 
) const

transformToTangentialPlane()

Transforms this point (given in WGS-coordinates) onto a tangential (x-y-) plane. The plane is defined by a reference point (origin), relative to which the x-y-coordinates are calculated. Note that this point should be somewhat close to the origin (several km is ok) as the tangential plane is flat.

Die Ausrichtung ist in beiden Koordinatensystemen gleich.

Definition at line 244 of file PositionWGS84.cpp.

Member Data Documentation

double datatypes::PositionWGS84::m_altitudeMSL
private

Definition at line 561 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_altitudeMSLSigma
private

Definition at line 562 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_courseAngle
private

Definition at line 563 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_courseAngleSigma
private

Definition at line 564 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_latitude
private

Definition at line 557 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_latitudeSigma
private

Definition at line 558 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_longitude
private

Definition at line 559 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_longitudeSigma
private

Definition at line 560 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_pitchAngle
private

Definition at line 567 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_pitchAngleSigma
private

Definition at line 568 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_rollAngle
private

Definition at line 569 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_rollAngleSigma
private

Definition at line 570 of file PositionWGS84.hpp.

PositionWGS84SourceType datatypes::PositionWGS84::m_source
private

Definition at line 571 of file PositionWGS84.hpp.

time_t datatypes::PositionWGS84::m_timeOfMeasurement
private

Definition at line 553 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_yawAngle
private

Definition at line 565 of file PositionWGS84.hpp.

double datatypes::PositionWGS84::m_yawAngleSigma
private

Definition at line 566 of file PositionWGS84.hpp.

const std::string datatypes::PositionWGS84::VERSION
staticprivate

Version of this file. Used for trace and debug output.

Definition at line 551 of file PositionWGS84.hpp.


The documentation for this class was generated from the following files:


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