Autoware.Auto
|
|
#include <ndt_localizer.hpp>
Public Types | |
using | CloudT = sensor_msgs::msg::PointCloud2 |
using | ParentT = NDTLocalizerBase< P2DNDTScan, P2DNDTOptimizationProblem< MapT >, P2DNDTOptimizationConfig, OptimizerT > |
using | Transform = typename ParentT::Transform |
using | PoseWithCovarianceStamped = typename ParentT::PoseWithCovarianceStamped |
using | ScanT = P2DNDTScan |
Public Types inherited from autoware::localization::ndt::NDTLocalizerBase< P2DNDTScan, P2DNDTOptimizationProblem< StaticNDTMap >, P2DNDTOptimizationConfig, OptimizerT > | |
using | Transform = geometry_msgs::msg::TransformStamped |
using | PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped |
using | Summary = localization_common::OptimizedRegistrationSummary |
Protected Member Functions | |
void | set_covariance (const P2DNDTOptimizationProblem< MapT > &, const EigenPose< Real > &, const EigenPose< Real > &, PoseWithCovarianceStamped &) const override |
Protected Member Functions inherited from autoware::localization::ndt::NDTLocalizerBase< P2DNDTScan, P2DNDTOptimizationProblem< StaticNDTMap >, P2DNDTOptimizationConfig, OptimizerT > | |
virtual void | set_covariance (const P2DNDTOptimizationProblem< StaticNDTMap > &problem, const EigenPose< Real > &initial_guess, const EigenPose< Real > &pose_result, PoseWithCovarianceStamped &solution) const |
void | validate_msg (const CloudT &msg, const MapT &map) const |
virtual void | validate_guess (const CloudT &msg, const Transform &transform_initial) const |
P2D localizer implementation. This implementation specifies a covariance computation method for the P2D optimization problem.
OptimizerT | Optimizer type. |
OptimizerOptionsT | Optimizer options type. |
MapT | Type of map to be used. By default it is StaticNDTMap. |
using autoware::localization::ndt::P2DNDTLocalizer< OptimizerT, MapT >::CloudT = sensor_msgs::msg::PointCloud2 |
using autoware::localization::ndt::P2DNDTLocalizer< OptimizerT, MapT >::ParentT = NDTLocalizerBase< P2DNDTScan, P2DNDTOptimizationProblem<MapT>, P2DNDTOptimizationConfig, OptimizerT> |
using autoware::localization::ndt::P2DNDTLocalizer< OptimizerT, MapT >::PoseWithCovarianceStamped = typename ParentT::PoseWithCovarianceStamped |
using autoware::localization::ndt::P2DNDTLocalizer< OptimizerT, MapT >::ScanT = P2DNDTScan |
using autoware::localization::ndt::P2DNDTLocalizer< OptimizerT, MapT >::Transform = typename ParentT::Transform |
|
inlineexplicit |
|
inlineoverrideprotected |