Gazebo Common

API Reference

6.0.0~pre2

#include <Dem.hh>

Public Member Functions

 Dem ()
 Constructor.
 
virtual ~Dem ()
 Destructor.
 
double Elevation (double _x, double _y)
 Get the elevation of a terrain's point in meters.
 
std::string Filename () const override
 Get the full filename of loaded heightmap image/dem.
 
void FillHeightMap (const int _subSampling, const unsigned int _vertSize, const gz::math::Vector3d &_size, const gz::math::Vector3d &_scale, const bool _flipY, std::vector< float > &_heights) const override
 Create a lookup table of the terrain's height.
 
bool GeoReferenceOrigin (gz::math::Angle &_latitude, gz::math::Angle &_longitude) const
 Get the georeferenced coordinates (lat, long) of the terrain's origin.
 
unsigned int Height () const override
 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 Data() adds the padding if necessary.
 
int Load (const std::string &_filename="")
 Load a DEM file.
 
float MaxElevation () const override
 Get the terrain's maximum elevation in meters.
 
float MinElevation () const override
 Get the terrain's minimum elevation in meters.
 
unsigned int RasterXSizeLimit ()
 Gets the X size limit of the raster data to be loaded. This is useful for large raster files.
 
unsigned int RasterYSizeLimit ()
 Gets the Y size limit of the raster data to be loaded. This is useful for large raster files.
 
void SetRasterXSizeLimit (const unsigned int &_xLimit)
 Sets the X size limit of the raster data to be loaded. This is useful for large raster files.
 
void SetRasterYSizeLimit (const unsigned int &_yLimit)
 Sets the Y size limit of the raster data to be loaded. This is useful for large raster files.
 
void SetSphericalCoordinates (const math::SphericalCoordinates &_worldSphericalCoordinates)
 Sets the spherical coordinates reference object.
 
unsigned int Width () const override
 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.
 
double WorldHeight () const
 Get the real world height in meters.
 
double WorldWidth () const
 Get the real world width in meters.
 
- Public Member Functions inherited from HeightmapData
virtual ~HeightmapData ()=default
 Destructor.
 

Constructor & Destructor Documentation

◆ Dem()

Dem ( )

Constructor.

◆ ~Dem()

virtual ~Dem ( )
virtual

Destructor.

Member Function Documentation

◆ Elevation()

double Elevation ( double  _x,
double  _y 
)

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

Parameters
[in]_xX coordinate of the terrain in raster coordinates.
[in]_yY coordinate of the terrain in raster coordinates.
Returns
Terrain's elevation at (x,y) in meters or infinity if illegal coordinates were provided.

◆ Filename()

std::string Filename ( ) const
overridevirtual

Get the full filename of loaded heightmap image/dem.

Returns
The filename used to load the heightmap image/dem

Implements HeightmapData.

◆ FillHeightMap()

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

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.

◆ GeoReferenceOrigin()

bool GeoReferenceOrigin ( gz::math::Angle _latitude,
gz::math::Angle _longitude 
) const

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

Parameters
[out]_latitudeGeoreferenced latitude.
[out]_longitudeGeoreferenced longitude.
Returns
True if able to retrieve origin coordinates. False otherwise.

◆ Height()

unsigned int Height ( ) const
overridevirtual

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 Data() 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.

◆ Load()

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.

◆ MaxElevation()

float MaxElevation ( ) const
overridevirtual

Get the terrain's maximum elevation in meters.

Returns
The maximum elevation (meters).

Implements HeightmapData.

◆ MinElevation()

float MinElevation ( ) const
overridevirtual

Get the terrain's minimum elevation in meters.

Returns
The minimum elevation (meters).

Reimplemented from HeightmapData.

◆ RasterXSizeLimit()

unsigned int RasterXSizeLimit ( )

Gets the X size limit of the raster data to be loaded. This is useful for large raster files.

Returns
The maximium size of the raster data to load in the X direction

◆ RasterYSizeLimit()

unsigned int RasterYSizeLimit ( )

Gets the Y size limit of the raster data to be loaded. This is useful for large raster files.

Returns
The maximium size of the raster data to load in the X direction

◆ SetRasterXSizeLimit()

void SetRasterXSizeLimit ( const unsigned int &  _xLimit)

Sets the X size limit of the raster data to be loaded. This is useful for large raster files.

Parameters
[in]_xLimitThe maximium size of the raster data to load in the X direction

◆ SetRasterYSizeLimit()

void SetRasterYSizeLimit ( const unsigned int &  _yLimit)

Sets the Y size limit of the raster data to be loaded. This is useful for large raster files.

Parameters
[in]_yLimitThe maximium size of the raster data to load in the X direction

◆ SetSphericalCoordinates()

void SetSphericalCoordinates ( const math::SphericalCoordinates _worldSphericalCoordinates)

Sets the spherical coordinates reference object.

Parameters
[in]_worldSphericalCoordinatesThe spherical coordinates object contained in the world. This is used to compute accurate sizes of the DEM object.

◆ Width()

unsigned int Width ( ) const
overridevirtual

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.

◆ WorldHeight()

double WorldHeight ( ) const

Get the real world height in meters.

Returns
Terrain's real world height in meters.

◆ WorldWidth()

double WorldWidth ( ) const

Get the real world width in meters.

Returns
Terrain's real world width in meters.

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