Encapsulates an image that will be interpreted as a heightmap.
More...
#include <common/common.hh>
Inherits HeightmapData.
|
| ImageHeightmap () |
| Constructor. More...
|
|
void | FillHeightMap (int _subSampling, unsigned int _vertSize, const math::Vector3 &_size, const math::Vector3 &_scale, bool _flipY, std::vector< float > &_heights) |
|
void | FillHeightMap (int _subSampling, unsigned int _vertSize, const ignition::math::Vector3d &_size, const ignition::math::Vector3d &_scale, bool _flipY, std::vector< float > &_heights) |
| Create a lookup table of the terrain's height. More...
|
|
std::string | GetFilename () const |
| Get the full filename of the image. More...
|
|
unsigned int | GetHeight () const |
| Get the terrain's height. More...
|
|
float | GetMaxElevation () const |
| Get the maximum terrain's elevation. More...
|
|
unsigned int | GetWidth () const |
| Get the terrain's width. More...
|
|
int | Load (const std::string &_filename="") |
| Load an image file as a heightmap. More...
|
|
Encapsulates an image that will be interpreted as a heightmap.
§ ImageHeightmap()
Constructor.
- Parameters
-
[in] | _filename | the path to the image |
§ FillHeightMap() [1/2]
void FillHeightMap |
( |
int |
_subSampling, |
|
|
unsigned int |
_vertSize, |
|
|
const math::Vector3 & |
_size, |
|
|
const math::Vector3 & |
_scale, |
|
|
bool |
_flipY, |
|
|
std::vector< float > & |
_heights |
|
) |
| |
§ FillHeightMap() [2/2]
void FillHeightMap |
( |
int |
_subSampling, |
|
|
unsigned int |
_vertSize, |
|
|
const ignition::math::Vector3d & |
_size, |
|
|
const ignition::math::Vector3d & |
_scale, |
|
|
bool |
_flipY, |
|
|
std::vector< float > & |
_heights |
|
) |
| |
|
virtual |
Create a lookup table of the terrain's height.
- Parameters
-
[in] | _subsampling | Multiplier 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] | _vertSize | Number of points per row. |
[in] | _size | Real dimmensions of the terrain. |
[in] | _scale | Vector3 used to scale the height. |
[in] | _flipY | If true, it inverts the order in which the vector is filled. |
[out] | _heights | Vector containing the terrain heights. |
Implements HeightmapData.
§ GetFilename()
std::string GetFilename |
( |
| ) |
const |
Get the full filename of the image.
- Returns
- The filename used to load the image
§ GetHeight()
unsigned int GetHeight |
( |
| ) |
const |
|
virtual |
Get the terrain's height.
- Returns
- The terrain's height.
Implements HeightmapData.
§ GetMaxElevation()
float GetMaxElevation |
( |
| ) |
const |
|
virtual |
Get the maximum terrain's elevation.
- Returns
- The maximum terrain's elevation.
Implements HeightmapData.
§ GetWidth()
unsigned int GetWidth |
( |
| ) |
const |
|
virtual |
Get the terrain's width.
- Returns
- The terrain's width.
Implements HeightmapData.
§ Load()
int Load |
( |
const std::string & |
_filename = "" | ) |
|
Load an image file as a heightmap.
- Parameters
-
[in] | _filename | the path to the image file. |
- Returns
- True when the operation succeeds to open a file.
The documentation for this class was generated from the following file: