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

#include <ndt_map.hpp>

Public Types

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

Public Member Functions

 DynamicNDTMap (const Config &voxel_grid_config)
 
void set (const sensor_msgs::msg::PointCloud2 &msg)
 Set the contents of the pointcloud as the new map. More...
 
void insert (const sensor_msgs::msg::PointCloud2 &msg)
 
template<typename DeserializingMapT >
void serialize_as (sensor_msgs::msg::PointCloud2 &msg_out) const
 
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 noexcept
 
std::size_t size () const noexcept
 
VoxelGrid::const_iterator begin () const noexcept
 Returns an const iterator to the first element of the map. More...
 
VoxelGrid::const_iterator end () const noexcept
 Returns a const iterator to one past the last element of the map. More...
 
void clear () noexcept
 Clear all voxels in the map. More...
 
template<>
void serialize_as (sensor_msgs::msg::PointCloud2 &msg_out) const
 

Static Public Attributes

static constexpr uint32_t kNumConfigPoints = 3U
 First 3 points of a serialized message will contain 3 extra points: Min point, max point and the voxel size. More...
 

Detailed Description

Ndt Map for a dynamic voxel type. This map representation is only to be used when a dense point cloud is intended to be represented as a map. (i.e. by the map publisher)

Member Typedef Documentation

◆ Config

◆ ConfigPoint

◆ Point

◆ TimePoint

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

◆ Voxel

◆ VoxelGrid

◆ VoxelViewVector

Constructor & Destructor Documentation

◆ DynamicNDTMap()

autoware::localization::ndt::DynamicNDTMap::DynamicNDTMap ( const Config voxel_grid_config)
explicit

Member Function Documentation

◆ begin()

DynamicNDTMap::VoxelGrid::const_iterator autoware::localization::ndt::DynamicNDTMap::begin ( ) const
noexcept

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

Returns
Iterator

◆ cell() [1/2]

const DynamicNDTMap::VoxelViewVector & autoware::localization::ndt::DynamicNDTMap::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 DynamicNDTMap::VoxelViewVector & autoware::localization::ndt::DynamicNDTMap::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 DynamicNDTMap::ConfigPoint & autoware::localization::ndt::DynamicNDTMap::cell_size ( ) const
noexcept

Get size of the cell.

Returns
A point representing the dimensions of the cell.

◆ clear()

void autoware::localization::ndt::DynamicNDTMap::clear ( )
noexcept

Clear all voxels in the map.

◆ end()

DynamicNDTMap::VoxelGrid::const_iterator autoware::localization::ndt::DynamicNDTMap::end ( ) const
noexcept

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

Returns
Iterator

◆ frame_id()

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

Get map's frame id.

Returns
Frame id of the map.

◆ insert()

void autoware::localization::ndt::DynamicNDTMap::insert ( const sensor_msgs::msg::PointCloud2 &  msg)

Insert the dense point cloud to the map. This is intended for converting a dense point cloud into the ndt representation. Ideal for reading dense pcd files.

Parameters
msgPointCloud2 message to add.

◆ serialize_as() [1/2]

template<typename DeserializingMapT >
void autoware::localization::ndt::DynamicNDTMap::serialize_as ( sensor_msgs::msg::PointCloud2 &  msg_out) const

Iterate over the map representation and convert it into a PointCloud2 message where each voxel in the map corresponds to a single point in the PointCloud2 field.

Template Parameters
DeserializingMapTThe map type that can deserialize the serialized message.
Parameters
msg_outReference to the initialized pointcloud message that will store the serialized map data.

◆ serialize_as() [2/2]

template<>
void autoware::localization::ndt::DynamicNDTMap::serialize_as ( sensor_msgs::msg::PointCloud2 &  msg_out) const

The resulting point cloud has the following fields: x, y, z, cov_xx, cov_xy, cov_xz, cov_yy, cov_yz, cov_zz, cell_id.

Parameters
msg_outReference to the pointcloud message that will store the serialized map data. The message will be initialized before use.

◆ set()

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

Set the contents of the pointcloud as the new map.

Parameters
msgPointcloud to be inserted.

◆ size()

std::size_t autoware::localization::ndt::DynamicNDTMap::size ( ) const
noexcept

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

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

Get map's time stamp.

Returns
map's time stamp.

◆ valid()

bool autoware::localization::ndt::DynamicNDTMap::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.

Member Data Documentation

◆ kNumConfigPoints

constexpr uint32_t autoware::localization::ndt::DynamicNDTMap::kNumConfigPoints = 3U
staticconstexpr

First 3 points of a serialized message will contain 3 extra points: Min point, max point and the voxel size.


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