Dem Class Reference

#include <Dem.hh>

Inherits HeightmapData.

Public Member Functions

 Dem ()
 Constructor. More...
 
virtual ~Dem ()
 Destructor. More...
 
void FillHeightMap (const int _subSampling, const unsigned int _vertSize, const ignition::math::Vector3d &_size, const ignition::math::Vector3d &_scale, const bool _flipY, std::vector< float > &_heights)
 Create a lookup table of the terrain's height. More...
 
double GetElevation (double _x, double _y)
 Get the elevation of a terrain's point in meters. More...
 
void GetGeoReferenceOrigin (ignition::math::Angle &_latitude, ignition::math::Angle &_longitude) const
 Get the georeferenced coordinates (lat, long) of the terrain's origin in WGS84. More...
 
unsigned int GetHeight () const
 Get the terrain's height. More...
 
float GetMaxElevation () const
 Get the terrain's maximum elevation in meters. More...
 
float GetMinElevation () const
 Get the terrain's minimum elevation in meters. More...
 
unsigned int GetWidth () const
 Get the terrain's width. More...
 
double GetWorldHeight () const
 Get the real world height in meters. More...
 
double GetWorldWidth () const
 Get the real world width in meters. More...
 
int Load (const std::string &_filename="")
 Load a DEM file. More...
 

Constructor & Destructor Documentation

Dem ( )

Constructor.

virtual ~Dem ( )
virtual

Destructor.

Member Function Documentation

void FillHeightMap ( const int  _subSampling,
const unsigned int  _vertSize,
const ignition::math::Vector3d &  _size,
const ignition::math::Vector3d &  _scale,
const bool  _flipY,
std::vector< float > &  _heights 
)
virtual

Create a lookup table of the terrain's height.

Parameters
[in]_subsamplingMultiplier used to increase the resolution. Ex: A subsampling of 2 in a terrain of 129x129 means that the height vector will be 257 * 257.
[in]_vertSizeNumber of points per row.
[in]_sizeReal dimmensions of the terrain in meters.
[in]_scaleVector3 used to scale the height.
[in]_flipYIf true, it inverts the order in which the vector is filled.
[out]_heightsVector containing the terrain heights.

Implements HeightmapData.

double GetElevation ( double  _x,
double  _y 
)

Get the elevation of a terrain's point in meters.

Parameters
[in]_xX coordinate of the terrain.
[in]_yY coordinate of the terrain.
Returns
Terrain's elevation at (x,y) in meters.
void GetGeoReferenceOrigin ( ignition::math::Angle &  _latitude,
ignition::math::Angle &  _longitude 
) const

Get the georeferenced coordinates (lat, long) of the terrain's origin in WGS84.

Parameters
[out]_latitudeGeoreferenced latitude.
[out]_longitudeGeoreferenced longitude.
unsigned int GetHeight ( ) const
virtual

Get the terrain's height.

Due to the Ogre constrains, this value will be a power of two plus one. The value returned might be different that the original DEM height because GetData() adds the padding if necessary.

Returns
The terrain's height (points) satisfying the ogre constrains (squared terrain with a height value that must be a power of two plus one).

Implements HeightmapData.

float GetMaxElevation ( ) const
virtual

Get the terrain's maximum elevation in meters.

Returns
The maximum elevation (meters).

Implements HeightmapData.

float GetMinElevation ( ) const

Get the terrain's minimum elevation in meters.

Returns
The minimum elevation (meters).
unsigned int GetWidth ( ) const
virtual

Get the terrain's width.

Due to the Ogre constrains, this value will be a power of two plus one. The value returned might be different that the original DEM width because GetData() adds the padding if necessary.

Returns
The terrain's width (points) satisfying the ogre constrains (squared terrain with a width value that must be a power of two plus one).

Implements HeightmapData.

double GetWorldHeight ( ) const

Get the real world height in meters.

Returns
Terrain's real world height in meters.
double GetWorldWidth ( ) const

Get the real world width in meters.

Returns
Terrain's real world width in meters.
int Load ( const std::string &  _filename = "")

Load a DEM file.

Parameters
[in]_filenamethe path to the terrain file.
Returns
0 when the operation succeeds to open a file.

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