Quad-SDK
Loading...
Searching...
No Matches
Public Member Functions | Private Member Functions | Private Attributes | List of all members
FastTerrainMap Class Reference

A terrain map class built for fast and efficient sampling. More...

#include <fast_terrain_map.h>

Public Member Functions

 FastTerrainMap ()
 Constructor for FastTerrainMap Class.
 
void loadData (int x_size, int y_size, std::vector< double > x_data, std::vector< double > y_data, std::vector< std::vector< double > > z_data, std::vector< std::vector< double > > nx_data, std::vector< std::vector< double > > ny_data, std::vector< std::vector< double > > nz_data, std::vector< std::vector< double > > z_data_filt, std::vector< std::vector< double > > nx_data_filt, std::vector< std::vector< double > > ny_data_filt, std::vector< std::vector< double > > nz_data_filt)
 Load data from a grid_map::GridMap object into a FastTerrainMap object.
 
void loadFlat ()
 Load in a default terrain map 10x10m, four corners with flat terrain.
 
void loadFlatElevated (double height)
 Load in a default terrain map 10x10m, four corners with elevated terrain.
 
void loadSlope (double grade)
 Load in a default terrain map 10x10m, four corners with sloped terrain.
 
void loadStep (double height)
 Load in a terrain map with a step at x = 0.
 
void loadDataFromGridMap (const grid_map::GridMap map)
 Load data from a grid_map::GridMap object into a FastTerrainMap object.
 
bool isInRange (const double x, const double y) const
 Check if map data is defined at a requested location.
 
double getGroundHeight (const double x, const double y) const
 Return the ground height at a requested location.
 
std::array< double, 3 > getSurfaceNormal (const double x, const double y) const
 Return the surface normal at a requested location.
 
double getGroundHeightFiltered (const double x, const double y) const
 Return the filtered ground height at a requested location.
 
std::array< double, 3 > getSurfaceNormalFiltered (const double x, const double y) const
 Return the filtered surface normal at a requested location.
 
Eigen::Vector3d getSurfaceNormalFilteredEigen (const double x, const double y) const
 Return the filtered surface normal at a requested location.
 
Eigen::Vector3d projectToMap (const Eigen::Vector3d point, const Eigen::Vector3d direction)
 Return the (approximate) intersection of the height map and a vector. Returned point lies exactly on the map but not entirely on the vector.
 
std::vector< double > getXData () const
 Return the vector of x_data of the map.
 
std::vector< double > getYData () const
 Return the vector of y_data of the map.
 
bool isEmpty () const
 Determine if the map is empty.
 

Private Member Functions

int getXIndex (const double x) const
 Return the x index.
 
int getYIndex (const double y) const
 Return the y index.
 

Private Attributes

int x_size_ = 0
 The number of elements in the x direction.
 
int y_size_ = 0
 The number of elements in the y direction.
 
double x_diff_
 Distance between nodes in x.
 
double y_diff_
 Distance between nodes in y.
 
std::vector< double > x_data_
 The vector of x data.
 
std::vector< double > y_data_
 The vector of y data.
 
std::vector< std::vector< double > > z_data_
 The nested vector of z data at each [x,y] location.
 
std::vector< std::vector< double > > nx_data_
 
std::vector< std::vector< double > > ny_data_
 
std::vector< std::vector< double > > nz_data_
 
std::vector< std::vector< double > > z_data_filt_
 The nested vector of filtered z data at each [x,y] location.
 
std::vector< std::vector< double > > nx_data_filt_
 
std::vector< std::vector< double > > ny_data_filt_
 
std::vector< std::vector< double > > nz_data_filt_
 

Detailed Description

A terrain map class built for fast and efficient sampling.

FastTerrainMap is a class built for lightweight and efficient sampling of the terrain for height and slope.

Constructor & Destructor Documentation

◆ FastTerrainMap()

FastTerrainMap::FastTerrainMap ( )

Constructor for FastTerrainMap Class.

Returns
Constructed object of type FastTerrainMap

Member Function Documentation

◆ getGroundHeight()

double FastTerrainMap::getGroundHeight ( const double  x,
const double  y 
) const

Return the ground height at a requested location.

Parameters
[in]doublex location
[in]doubley location
Returns
double ground height at location [x,y]

◆ getGroundHeightFiltered()

double FastTerrainMap::getGroundHeightFiltered ( const double  x,
const double  y 
) const

Return the filtered ground height at a requested location.

Parameters
[in]doublex location
[in]doubley location
Returns
double ground height at location [x,y]

◆ getSurfaceNormal()

std::array< double, 3 > FastTerrainMap::getSurfaceNormal ( const double  x,
const double  y 
) const

Return the surface normal at a requested location.

Parameters
[in]doublex location
[in]doubley location
Returns
std::array<double, 3> surface normal at location [x,y]

◆ getSurfaceNormalFiltered()

std::array< double, 3 > FastTerrainMap::getSurfaceNormalFiltered ( const double  x,
const double  y 
) const

Return the filtered surface normal at a requested location.

Parameters
[in]doublex location
[in]doubley location
Returns
std::array<double, 3> surface normal at location [x,y]

◆ getSurfaceNormalFilteredEigen()

Eigen::Vector3d FastTerrainMap::getSurfaceNormalFilteredEigen ( const double  x,
const double  y 
) const

Return the filtered surface normal at a requested location.

Parameters
[in]doublex location
[in]doubley location
Returns
std::array<double, 3> surface normal at location [x,y]

◆ getXData()

std::vector< double > FastTerrainMap::getXData ( ) const

Return the vector of x_data of the map.

Returns
std::vector<double> of x locations in the grid

◆ getXIndex()

int FastTerrainMap::getXIndex ( const double  x) const
inlineprivate

Return the x index.

Parameters
[in]xX location of the point
Returns
X index of location

◆ getYData()

std::vector< double > FastTerrainMap::getYData ( ) const

Return the vector of y_data of the map.

Returns
std::vector<double> of y locations in the grid

◆ getYIndex()

int FastTerrainMap::getYIndex ( const double  y) const
inlineprivate

Return the y index.

Parameters
[in]yY location of the point
Returns
Y index of location

◆ isEmpty()

bool FastTerrainMap::isEmpty ( ) const

Determine if the map is empty.

Returns
boolean for map emptiness (true = empty)

◆ isInRange()

bool FastTerrainMap::isInRange ( const double  x,
const double  y 
) const

Check if map data is defined at a requested location.

Parameters
[in]doublex location
[in]doubley location
Returns
bool location [x,y] is or is not in range

◆ loadData()

void FastTerrainMap::loadData ( int  x_size,
int  y_size,
std::vector< double >  x_data,
std::vector< double >  y_data,
std::vector< std::vector< double > >  z_data,
std::vector< std::vector< double > >  nx_data,
std::vector< std::vector< double > >  ny_data,
std::vector< std::vector< double > >  nz_data,
std::vector< std::vector< double > >  z_data_filt,
std::vector< std::vector< double > >  nx_data_filt,
std::vector< std::vector< double > >  ny_data_filt,
std::vector< std::vector< double > >  nz_data_filt 
)

Load data from a grid_map::GridMap object into a FastTerrainMap object.

Parameters
[in]intThe number of elements in the x direction
[in]intThe number of elements in the xy direction
[in]std::vector<double>The vector of x data
[in]std::vector<double>The vector of y data
[in]std::vector<std::vector<double>>The nested vector of z data at each [x,y] location
[in]std::vector<std::vector<double>>The nested vector of the x component of the gradient at each [x,y] location
[in]std::vector<std::vector<double>>The nested vector of the y component of the gradient at each [x,y] location
[in]std::vector<std::vector<double>>The nested vector of the z component of the gradient at each [x,y] location

◆ loadDataFromGridMap()

void FastTerrainMap::loadDataFromGridMap ( const grid_map::GridMap  map)

Load data from a grid_map::GridMap object into a FastTerrainMap object.

Parameters
[in]grid_map::GridMapobject with map data

◆ loadFlatElevated()

void FastTerrainMap::loadFlatElevated ( double  height)

Load in a default terrain map 10x10m, four corners with elevated terrain.

Parameters
[in]heightHeight of elevated terrain

◆ loadSlope()

void FastTerrainMap::loadSlope ( double  grade)

Load in a default terrain map 10x10m, four corners with sloped terrain.

Parameters
[in]gradeGrade of terrain data (grade = tan(slope))

◆ loadStep()

void FastTerrainMap::loadStep ( double  height)

Load in a terrain map with a step at x = 0.

Parameters
[in]heightHeight of step

◆ projectToMap()

Eigen::Vector3d FastTerrainMap::projectToMap ( const Eigen::Vector3d  point,
const Eigen::Vector3d  direction 
)

Return the (approximate) intersection of the height map and a vector. Returned point lies exactly on the map but not entirely on the vector.

Parameters
[in]pointThe point at which the vector originates
[in]directionThe direction along which to project the point

Member Data Documentation

◆ nx_data_

std::vector<std::vector<double> > FastTerrainMap::nx_data_
private

The nested vector of the x component of the gradient at each [x,y] location

◆ nx_data_filt_

std::vector<std::vector<double> > FastTerrainMap::nx_data_filt_
private

The nested vector of the x component of the filtered gradient at each [x,y] location

◆ ny_data_

std::vector<std::vector<double> > FastTerrainMap::ny_data_
private

The nested vector of the y component of the gradient at each [x,y] location

◆ ny_data_filt_

std::vector<std::vector<double> > FastTerrainMap::ny_data_filt_
private

The nested vector of the y component of the filtered gradient at each [x,y] location

◆ nz_data_

std::vector<std::vector<double> > FastTerrainMap::nz_data_
private

The nested vector of the z component of the gradient at each [x,y] location

◆ nz_data_filt_

std::vector<std::vector<double> > FastTerrainMap::nz_data_filt_
private

The nested vector of the z component of the filtered gradient at each [x,y] location


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