Height Map

A height map is a grid of points that are triangulated to form a surface. Since it is axis-aligned, collision checking is very efficient and it is a recommended way to create terrain.

You can get the following two properties from a height map instance:

  • height: getHeight()

  • normal vector: getNormal()

Example

API

HeightMap

class HeightMap : public raisim::SingleBodyObject

Public Functions

HeightMap(double centerX, double centerY, const std::string &raisimHeightMapFileName)

loading heightmap from a text file

void update(double centerX, double centerY, const TerrainProperties &terrainProperties)

Update the existing heightmap with a new terrain properties. The size should be the same. You cannot change the topology. If you want to create a new topology, delete an old one and make a new heightmap.

Parameters:
  • centerX[in] center of the heightmap

  • centerY[in] center of the heightmap

  • terrainProperties[in] new terrain properties. You cannot change the sample size

void update(double centerX, double centerY, double sizeX, double sizeY, const std::vector<double> &height)

Update the existing heightmap with a new terrain properties. The size should be the same. You cannot change the topology. If you want to create a new topology, delete an old one and make a new heightmap.

Parameters:
  • centerX[in] center of the heightmap

  • centerY[in] center of the heightmap

  • sizeX[in] height map size in the x direction

  • sizeY[in] height map size in the y direction

  • height[in] height samples (row-major)

double getHeight(double x, double y) const

Get height at a given coordinate

Parameters:
  • x[in] x position

  • y[in] y position

Returns:

height

void getNormal(double x, double y, Vec<3> &normal) const

Get normal at a given coordinate

Parameters:
  • x[in] x position

  • y[in] y position

  • normal[out] normal vector

inline size_t getXSamples() const

Get the number of points in x direction

Returns:

the number of points

inline size_t getYSamples() const

Get the number of points in y direction

Returns:

the number of points

inline double getXSize() const

Get the size of the heightmap in x direction

Returns:

the length

inline double getYSize() const

Get the number of the heightmap in y direction

Returns:

the width

inline double getCenterX() const

Get the center position of the heightmap in x-axis

Returns:

position

inline double getCenterY() const

Get the center position of the heightmap in y-axis

Returns:

position

inline const std::vector<double> &getHeightVector() const

Get the vector of height values

Returns:

vector containing height values

inline void setUpdatedFalse()

If the height is updated. This triggers the server to send the geomtry again

inline bool isUpdated() const

Get if the height is updated

Returns:

if the height is updated or not

inline virtual void setPosition(const Eigen::Ref<const Eigen::Vector3d, Eigen::Unaligned> &originPosition) final

Set position of the object (using Eigen)

Parameters:

originPosition[in] Position

inline virtual void setPosition(double x, double y, double z) final

Set position of the object (using three doubles)

Parameters:
  • x[in] x position

  • y[in] y position

  • z[in] z position

inline virtual void setOrientation(const Eigen::Quaterniond &quaternion) final

Set orientation of the object (using Eigen::Quaterniond)

Parameters:

quaternion[in] quaternion

inline virtual void setOrientation(const Eigen::Vector4d &quaternion) final

Set orientation of the object (using Eigen::Vector4d)

Parameters:

quaternion[in] quaternion

inline virtual void setOrientation(double w, double x, double y, double z) final

Set orientation of the object (using doubles)

Parameters:
  • w[in] w

  • x[in] w

  • y[in] w

  • z[in] w

inline virtual void setOrientation(const Eigen::Matrix3d &rotationMatrix) final

Set orientation of the object (using Eigen::Matrix3d)

Parameters:

rotationMatrix[in] rotation matrix

inline void setColor(const std::vector<ColorRGB> &colorLevel)

Set varying color on the heightmap If set, the appearance will be ignored. Set emtpy vector to the color level to make the appearance active

Parameters:

colorLevel[in] per-vertex color values (same size as the height vector)

inline const std::vector<ColorRGB> &getColorMap() const

Get the whole color vector. If set, the appearance will be ignored in unreal. Unity color map is not supported yet

Returns:

color

inline ColorRGB getColor(double x, double y) const

Returns color of the heightmap at specified point. The color from an RGB camera can be different from this because this is the base color and lighting changes the appearance.

Parameters:
  • x[in] x position in world coordinates

  • y[in] y position in world coordinates

Returns:

the RGB color

Terrain properties

struct TerrainProperties

Public Members

double xSize

Terrain size in x direction (meters).

double ySize

Terrain size in y direction (meters).

double zScale

Height scale multiplier.

double fractalLacunarity

Fractal lacunarity (frequency multiplier).

double fractalGain

Fractal gain (amplitude multiplier).

double stepSize

Quantization step size for stair-like terrain (0 disables).

double heightOffset

Constant height offset added to all samples.

size_t fractalOctaves

Number of fractal octaves.

size_t xSamples

Number of samples in x direction.

size_t ySamples

Number of samples in y direction.

std::uint32_t seed

Seed for the noise generator.