Autoware.Auto
autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT > Class Template Reference

#include <ndt_scan.hpp>

Inheritance diagram for autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >:
Collaboration diagram for autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >:

Public Types

using Point = NDTUnit
 
using TimePoint = std::chrono::system_clock::time_point
 

Public Member Functions

IteratorT begin () const
 
IteratorT end () const
 
void clear ()
 Clear the states and the internal cache of the scan. More...
 
bool8_t empty ()
 
void insert (const sensor_msgs::msg::PointCloud2 &msg)
 
std::size_t size () const
 
TimePoint stamp ()
 

Additional Inherited Members

- Protected Member Functions inherited from autoware::common::helper_functions::crtp< Derived >
const Derived & impl () const
 
Derived & impl ()
 

Detailed Description

template<typename Derived, typename NDTUnit, typename IteratorT>
class autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >

CRTP Base class defining the required minimal API of an NDTScan.

Template Parameters
DerivedDerived class
NDTUnitThe unit representing a single element within the scan.
IteratorTThe type of iterator to iterate the scan.

Member Typedef Documentation

◆ Point

template<typename Derived , typename NDTUnit , typename IteratorT >
using autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::Point = NDTUnit

◆ TimePoint

template<typename Derived , typename NDTUnit , typename IteratorT >
using autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::TimePoint = std::chrono::system_clock::time_point

Member Function Documentation

◆ begin()

template<typename Derived , typename NDTUnit , typename IteratorT >
IteratorT autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::begin ( ) const
inline

Get iterator pointing to the beginning of the internal container.

Returns
Begin iterator.

◆ clear()

template<typename Derived , typename NDTUnit , typename IteratorT >
void autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::clear ( )
inline

Clear the states and the internal cache of the scan.

◆ empty()

template<typename Derived , typename NDTUnit , typename IteratorT >
bool8_t autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::empty ( )
inline

Check if there is any data in the scan.

Returns
True if the internal container is empty.

◆ end()

template<typename Derived , typename NDTUnit , typename IteratorT >
IteratorT autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::end ( ) const
inline

Get iterator pointing to the end of the internal container.

Returns
End iterator.

◆ insert()

template<typename Derived , typename NDTUnit , typename IteratorT >
void autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::insert ( const sensor_msgs::msg::PointCloud2 &  msg)
inline

Insert a point cloud into the NDTScan. This is the step where the pointcloud is converted into the ndt scan representation.

Parameters
msgPoint cloud to insert.

◆ size()

template<typename Derived , typename NDTUnit , typename IteratorT >
std::size_t autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::size ( ) const
inline

Number of points inside the scan.

Returns
Number of points

◆ stamp()

template<typename Derived , typename NDTUnit , typename IteratorT >
TimePoint autoware::localization::ndt::NDTScanBase< Derived, NDTUnit, IteratorT >::stamp ( )
inline

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