Autoware.Auto
autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires > Class Template Reference

#include <point_cloud_map.hpp>

Public Types

using Cloud = sensor_msgs::msg::PointCloud2
 
using CloudConstIt = sensor_msgs::PointCloud2ConstIterator< float32_t >
 

Public Member Functions

 DualVoxelMap (const perception::filters::voxel_grid::Config &grid_config, const std::string &frame_id, LocalizerMapT &&localizer_map)
 
MapUpdateSummary update (const Cloud &observation)
 
void write (const std::string &file_name_prefix) const
 
std::size_t size () const noexcept
 Size of the voxel grid. More...
 
std::size_t capacity () const noexcept
 Capacity of the voxel grid. More...
 
void clear ()
 Clear the voxel grid. More...
 
const LocalizerMapT & localizer_map () const noexcept
 Get the localizer map. More...
 
const std::string & frame_id () const noexcept
 Get the frame ID of the map. More...
 
bool empty ()
 Get if the map is empty. More...
 

Static Public Attributes

static constexpr auto NUM_FIELDS {4U}
 

Detailed Description

template<typename LocalizerMapT, Requires = LocalizationMapConstraint<LocalizerMapT>::value>
class autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >

A map that accumulates lidar scans in a downsampled format using a voxel grid. A voxel grid is used for accumulating the lidar scans in a downsampled manner. A separate map is stored for the localizer implementation. The expected interface is defined via the Requires keyword.

Member Typedef Documentation

◆ Cloud

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
using autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::Cloud = sensor_msgs::msg::PointCloud2

◆ CloudConstIt

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
using autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::CloudConstIt = sensor_msgs::PointCloud2ConstIterator<float32_t>

Constructor & Destructor Documentation

◆ DualVoxelMap()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::DualVoxelMap ( const perception::filters::voxel_grid::Config grid_config,
const std::string &  frame_id,
LocalizerMapT &&  localizer_map 
)
inlineexplicit

Constructor

Parameters
grid_configGrid configuration of the underlying voxel grid.
frame_idFrame id of the map.
localizer_mapLocalizer map to be stored.

Member Function Documentation

◆ capacity()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
std::size_t autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::capacity ( ) const
inlinenoexcept

Capacity of the voxel grid.

◆ clear()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
void autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::clear ( )
inline

Clear the voxel grid.

◆ empty()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
bool autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::empty ( )
inline

Get if the map is empty.

◆ frame_id()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
const std::string& autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::frame_id ( ) const
inlinenoexcept

Get the frame ID of the map.

◆ localizer_map()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
const LocalizerMapT& autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::localizer_map ( ) const
inlinenoexcept

Get the localizer map.

◆ size()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
std::size_t autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::size ( ) const
inlinenoexcept

Size of the voxel grid.

◆ update()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
MapUpdateSummary autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::update ( const Cloud observation)
inline

Try to extend the map with the given point cloud.

Parameters
observationPoint cloud in the "map" frame to add to the map.
Returns
A struct summarizing the outcome of the insertion attempt.

◆ write()

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
void autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::write ( const std::string &  file_name_prefix) const
inline

Convert the voxel grid to a point cloud and write it to a pcd file.

Parameters
file_name_prefixFile name prefix of the file.

Member Data Documentation

◆ NUM_FIELDS

template<typename LocalizerMapT , Requires = LocalizationMapConstraint<LocalizerMapT>::value>
constexpr auto autoware::mapping::point_cloud_mapping::DualVoxelMap< LocalizerMapT, Requires >::NUM_FIELDS {4U}
static

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