Go to the documentation of this file.
17 #ifndef NDT__NDT_LOCALIZER_HPP_
18 #define NDT__NDT_LOCALIZER_HPP_
21 #include <sensor_msgs/msg/point_cloud2.hpp>
22 #include <geometry_msgs/msg/transform.hpp>
31 namespace localization
35 using CloudT = sensor_msgs::msg::PointCloud2;
46 typename NDTOptimizationProblemT,
47 typename OptimizationProblemConfigT,
50 CloudT, localization_common::OptimizedRegistrationSummary>
70 const OptimizationProblemConfigT & optimization_problem_config,
71 const OptimizerT & optimizer,
75 m_optimization_problem_config{optimization_problem_config},
76 m_optimizer{optimizer},
77 m_scan{std::forward<ScanT>(scan)},
78 m_map{std::forward<MapT>(map)} {}
95 validate_guess(msg, transform_initial);
99 eig_pose_initial.setZero();
100 eig_pose_result.setZero();
109 NDTOptimizationProblemT problem(m_scan, m_map, m_optimization_problem_config);
110 const auto opt_summary = m_optimizer.solve(problem, eig_pose_initial, eig_pose_result);
113 throw std::runtime_error(
114 "NDT localizer has likely encountered a numerical "
115 "error during optimization.");
123 pose_out.header.stamp = msg.header.stamp;
124 pose_out.header.frame_id = map_frame_id();
127 set_covariance(problem, eig_pose_initial, eig_pose_result, pose_out);
147 const ScanT &
scan() const noexcept
152 const MapT &
map() const noexcept
169 return m_optimization_problem_config;
174 return m_map.frame_id();
178 std::chrono::system_clock::time_point
map_stamp() const noexcept
override
180 return m_map.stamp();
191 const NDTOptimizationProblemT & problem,
197 (void) initial_guess;
211 if (message_time < m_map.stamp()) {
212 throw std::logic_error(
213 "Lidar scan should not have a timestamp older than the timestamp of"
229 const auto stamp_tol = m_config.guess_time_tolerance();
232 std::chrono::duration_cast<std::decay_t<decltype(stamp_tol)>>(guess_scan_diff).
234 std::abs(stamp_tol.count()))
236 throw std::domain_error(
237 "Initial guess is not within: " + std::to_string(stamp_tol.count()) +
238 "ns range of the scan's time stamp. Either increase the tolerance range or"
239 "make sure the localizer takes in timely initial pose guesses.");
245 OptimizationProblemConfigT m_optimization_problem_config;
246 OptimizerT m_optimizer;
256 template<
typename OptimizerT,
typename MapT = StaticNDTMap>
258 P2DNDTScan, MapT, P2DNDTOptimizationProblem<MapT>, P2DNDTOptimizationConfig, OptimizerT>
261 using CloudT = sensor_msgs::msg::PointCloud2;
270 const OptimizerT & optimizer,
271 const Real outlier_ratio)
294 #endif // NDT__NDT_LOCALIZER_HPP_
sensor_msgs::msg::PointCloud2 CloudT
Definition: ndt_localizer.hpp:261
uint32_t scan_capacity() const noexcept
Definition: ndt_config.hpp:119
Definition: optimization_problem.hpp:332
void insert_to_map_impl(const CloudT &msg) override
Definition: ndt_localizer.hpp:141
const NDTLocalizerConfigBase & config() const noexcept
Get the localizer configuration.
Definition: ndt_localizer.hpp:162
const OptimizerT & optimizer() const noexcept
Get the optimizer.
Definition: ndt_localizer.hpp:157
Definition: localizer_base.hpp:40
virtual void validate_msg(const CloudT &msg) const
Definition: ndt_localizer.hpp:207
float64_t Real
Definition: ndt_common.hpp:39
geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: localizer_base.hpp:61
virtual void set_covariance(const NDTOptimizationProblemT &problem, const EigenPose< Real > &initial_guess, const EigenPose< Real > &pose_result, PoseWithCovarianceStamped &solution) const
Definition: ndt_localizer.hpp:190
const MapConfig & map_config() const noexcept
Definition: ndt_config.hpp:61
std::chrono::system_clock::time_point map_stamp() const noexcept override
Get the timestamp of the current map. (Required for base interface)
Definition: ndt_localizer.hpp:178
const OptimizationProblemConfigT & optimization_problem_config() const noexcept
Get the optimization problem configuration.
Definition: ndt_localizer.hpp:167
P2DNDTLocalizer(const P2DNDTLocalizerConfig &config, const OptimizerT &optimizer, const Real outlier_ratio)
Definition: ndt_localizer.hpp:268
const ScanT & scan() const noexcept
Get the last used scan.
Definition: ndt_localizer.hpp:147
Config class for p2d optimziation problem.
Definition: ndt_config.hpp:80
Eigen::Matrix< T, 6U, 1U > EigenPose
Definition: localization/ndt/include/ndt/utils.hpp:83
virtual void validate_guess(const CloudT &msg, const Transform &transform_initial) const
Definition: ndt_localizer.hpp:223
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: ndt_scan.hpp:99
Definition: ndt_localizer.hpp:257
Definition: ndt_config.hpp:32
geometry_msgs::msg::TransformStamped Transform
Definition: recordreplay_planner_node.hpp:56
typename ParentT::Transform Transform
Definition: ndt_localizer.hpp:264
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
TIME_UTILS_PUBLIC std::chrono::system_clock::time_point from_message(builtin_interfaces::msg::Time t) noexcept
Convert from std::chrono::time_point from time message.
Definition: time_utils.cpp:84
RegistrationSummary register_measurement_impl(const CloudT &msg, const Transform &transform_initial, PoseWithCovarianceStamped &pose_out) override
Definition: ndt_localizer.hpp:90
NDTLocalizerBase(const NDTLocalizerConfigBase &config, const OptimizationProblemConfigT &optimization_problem_config, const OptimizerT &optimizer, ScanT &&scan, MapT &&map)
Definition: ndt_localizer.hpp:68
geometry_msgs::msg::TransformStamped Transform
Definition: localizer_base.hpp:62
typename ParentT::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: ndt_localizer.hpp:265
sensor_msgs::msg::PointCloud2 CloudT
Definition: ndt_localizer.hpp:35
Definition: ndt_localizer.hpp:49
void set_map_impl(const CloudT &msg) override
Definition: ndt_localizer.hpp:133
const std::string & map_frame_id() const noexcept override
Get the frame id of the current map.(Required for base interface)
Definition: ndt_localizer.hpp:172
Definition: localizer_base.hpp:58
const MapT & map() const noexcept
Get the current map.
Definition: ndt_localizer.hpp:152
geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: ndt_localizer.hpp:54
void set_covariance(const P2DNDTOptimizationProblem< MapT > &, const EigenPose< Real > &, const EigenPose< Real > &, PoseWithCovarianceStamped &) const override
Definition: ndt_localizer.hpp:280
config class for p2d ndt localizer
Definition: ndt_config.hpp:99