Autoware.Auto
autoware::localization::ndt::StaticNDTMap Class Reference

#include <ndt_map.hpp>

Public Types

using Voxel = StaticNDTVoxel
 
using Config = autoware::perception::filters::voxel_grid::Config
 
using TimePoint = std::chrono::system_clock::time_point
 
using Point = Eigen::Vector3d
 
using VoxelViewVector = std::vector< VoxelView< Voxel > >
 
using VoxelGrid = NDTGrid< Voxel >::Grid
 
using ConfigPoint = NDTGrid< Voxel >::ConfigPoint
 

Public Member Functions

void set (const sensor_msgs::msg::PointCloud2 &msg)
 
const VoxelViewVectorcell (const Point &pt) const
 
const VoxelViewVectorcell (float32_t x, float32_t y, float32_t z) const
 
const std::string & frame_id () const noexcept
 
TimePoint stamp () const noexcept
 
bool valid () const noexcept
 Check if the map is valid. More...
 
const ConfigPointcell_size () const
 
std::size_t size () const
 
VoxelGrid::const_iterator begin () const
 Returns an const iterator to the first element of the map. More...
 
VoxelGrid::const_iterator end () const
 Returns a const iterator to one past the last element of the map. More...
 
void clear ()
 Clear all voxels in the map. More...
 

Detailed Description

NDT map using StaticNDTVoxels. This class is to be used when the pointcloud messages to be inserted already have the correct format (see validate_pcl_map(...)) and represent a transformed map. No centroid/covariance computation is done during run-time.

Member Typedef Documentation

◆ Config

◆ ConfigPoint

◆ Point

◆ TimePoint

using autoware::localization::ndt::StaticNDTMap::TimePoint = std::chrono::system_clock::time_point

◆ Voxel

◆ VoxelGrid

◆ VoxelViewVector

Member Function Documentation

◆ begin()

StaticNDTMap::VoxelGrid::const_iterator autoware::localization::ndt::StaticNDTMap::begin ( ) const

Returns an const iterator to the first element of the map.

Returns
Iterator

◆ cell() [1/2]

const StaticNDTMap::VoxelViewVector & autoware::localization::ndt::StaticNDTMap::cell ( const Point pt) const

Lookup the cell at location.

Parameters
ptpoint to lookup
Returns
A vector containing the cell at given coordinates. A vector is used to support near-neighbour cell queries in the future.

◆ cell() [2/2]

const StaticNDTMap::VoxelViewVector & autoware::localization::ndt::StaticNDTMap::cell ( float32_t  x,
float32_t  y,
float32_t  z 
) const

Lookup the cell at location.

Parameters
xx coordinate
yy coordinate
zz coordinate
Returns
A vector containing the cell at given coordinates. A vector is used to support near-neighbour cell queries in the future.

◆ cell_size()

const StaticNDTMap::ConfigPoint & autoware::localization::ndt::StaticNDTMap::cell_size ( ) const

Get size of the cell.

Returns
A point representing the dimensions of the cell.

◆ clear()

void autoware::localization::ndt::StaticNDTMap::clear ( )

Clear all voxels in the map.

◆ end()

StaticNDTMap::VoxelGrid::const_iterator autoware::localization::ndt::StaticNDTMap::end ( ) const

Returns a const iterator to one past the last element of the map.

Returns
Iterator

◆ frame_id()

const std::string & autoware::localization::ndt::StaticNDTMap::frame_id ( ) const
noexcept

Get map's frame id.

Returns
Frame id of the map.

◆ set()

void autoware::localization::ndt::StaticNDTMap::set ( const sensor_msgs::msg::PointCloud2 &  msg)

Set point cloud message representing the map to the map representation instance. Map is assumed to have correct format (see validate_pcl_map(...)) and was generated by a dense map representation with identical configuration to this representation.

Parameters
msgPointCloud2 message to add. Each point in this cloud should correspond to a single voxel in the underlying voxel grid. This is checked via the cell_id field in the pcl message which is expected to be equal to the voxel grid ID in the map's voxel grid. Since the grid's index will be a long value to avoid overflows, cell_id field should be an array of 2 unsigned integers. That is because there is no direct long support as a PointField.

◆ size()

std::size_t autoware::localization::ndt::StaticNDTMap::size ( ) const

Get size of the map

Returns
Number of voxels in the map. This number includes the voxels that do not have enough numbers to be used yet.

◆ stamp()

StaticNDTMap::TimePoint autoware::localization::ndt::StaticNDTMap::stamp ( ) const
noexcept

Get map's time stamp.

Returns
map's time stamp.

◆ valid()

bool autoware::localization::ndt::StaticNDTMap::valid ( ) const
noexcept

Check if the map is valid.

Returns
True if the map and frame ID are not empty and the stamp is initialized.

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