Autoware.Auto
ndt_localizer.hpp
Go to the documentation of this file.
1 // Copyright 2019 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef NDT__NDT_LOCALIZER_HPP_
18 #define NDT__NDT_LOCALIZER_HPP_
19 
21 #include <sensor_msgs/msg/point_cloud2.hpp>
22 #include <geometry_msgs/msg/transform.hpp>
23 #include <ndt/ndt_common.hpp>
26 #include <utility>
27 #include <string>
28 
29 namespace autoware
30 {
31 namespace localization
32 {
33 namespace ndt
34 {
35 using CloudT = sensor_msgs::msg::PointCloud2;
36 
43 template<
44  typename ScanT,
45  typename MapT,
46  typename NDTOptimizationProblemT,
47  typename OptimizationProblemConfigT,
48  typename OptimizerT>
50  CloudT, localization_common::OptimizedRegistrationSummary>
51 {
52 public:
54  using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped;
55 
68  explicit NDTLocalizerBase(
69  const NDTLocalizerConfigBase & config,
70  const OptimizationProblemConfigT & optimization_problem_config,
71  const OptimizerT & optimizer,
72  ScanT && scan,
73  MapT && map)
74  : m_config{config},
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)} {}
79 
91  const CloudT & msg,
92  const Transform & transform_initial, PoseWithCovarianceStamped & pose_out) override
93  {
94  validate_msg(msg);
95  validate_guess(msg, transform_initial);
96  // Initial checks passed, proceed with initialization
97  // Eigen representations to be used for internal computations.
98  EigenPose<Real> eig_pose_initial, eig_pose_result;
99  eig_pose_initial.setZero();
100  eig_pose_result.setZero();
101  // Convert the ros transform/pose to eigen pose vector
102  transform_adapters::transform_to_pose(transform_initial.transform, eig_pose_initial);
103 
104  // Set the scan
105  m_scan.clear();
106  m_scan.insert(msg);
107 
108  // Define and solve the problem.
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);
111 
112  if (opt_summary.termination_type() == common::optimization::TerminationType::FAILURE) {
113  throw std::runtime_error(
114  "NDT localizer has likely encountered a numerical "
115  "error during optimization.");
116  }
117 
118  // Convert eigen pose back to ros pose/transform
120  eig_pose_result,
121  pose_out.pose.pose);
122 
123  pose_out.header.stamp = msg.header.stamp;
124  pose_out.header.frame_id = map_frame_id();
125 
126  // Populate covariance information. It is implementation defined.
127  set_covariance(problem, eig_pose_initial, eig_pose_result, pose_out);
129  }
130 
133  void set_map_impl(const CloudT & msg) override
134  {
135  m_map.clear();
136  m_map.insert(msg);
137  }
138 
141  void insert_to_map_impl(const CloudT & msg) override
142  {
143  m_map.insert(msg);
144  }
145 
147  const ScanT & scan() const noexcept
148  {
149  return m_scan;
150  }
152  const MapT & map() const noexcept
153  {
154  return m_map;
155  }
157  const OptimizerT & optimizer() const noexcept
158  {
159  return m_optimizer;
160  }
162  const NDTLocalizerConfigBase & config() const noexcept
163  {
164  return m_config;
165  }
167  const OptimizationProblemConfigT & optimization_problem_config() const noexcept
168  {
169  return m_optimization_problem_config;
170  }
172  const std::string & map_frame_id() const noexcept override
173  {
174  return m_map.frame_id();
175  }
176 
178  std::chrono::system_clock::time_point map_stamp() const noexcept override
179  {
180  return m_map.stamp();
181  }
182 
183 protected:
190  virtual void set_covariance(
191  const NDTOptimizationProblemT & problem,
192  const EigenPose<Real> & initial_guess,
193  const EigenPose<Real> & pose_result,
194  PoseWithCovarianceStamped & solution) const
195  {
196  (void) problem;
197  (void) initial_guess;
198  (void) pose_result;
199  (void) solution;
200  // For now, do nothing.
201  }
202 
207  virtual void validate_msg(const CloudT & msg) const
208  {
209  const auto message_time = ::time_utils::from_message(msg.header.stamp);
210  // Map shouldn't be newer than a measurement.
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"
214  "the current map.");
215  }
216  }
217 
223  virtual void validate_guess(const CloudT & msg, const Transform & transform_initial) const
224  {
225  const auto message_time = ::time_utils::from_message(msg.header.stamp);
226 
227  const auto guess_scan_diff = ::time_utils::from_message(transform_initial.header.stamp) -
228  message_time;
229  const auto stamp_tol = m_config.guess_time_tolerance();
230  // An initial estimate should be comparable in time to the measurement's time stamp
231  if (std::abs(
232  std::chrono::duration_cast<std::decay_t<decltype(stamp_tol)>>(guess_scan_diff).
233  count()) >
234  std::abs(stamp_tol.count()))
235  {
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.");
240  }
241  }
242 
243 private:
244  NDTLocalizerConfigBase m_config;
245  OptimizationProblemConfigT m_optimization_problem_config;
246  OptimizerT m_optimizer;
247  ScanT m_scan;
248  MapT m_map;
249 };
250 
256 template<typename OptimizerT, typename MapT = StaticNDTMap>
257 class NDT_PUBLIC P2DNDTLocalizer : public NDTLocalizerBase<
258  P2DNDTScan, MapT, P2DNDTOptimizationProblem<MapT>, P2DNDTOptimizationConfig, OptimizerT>
259 {
260 public:
261  using CloudT = sensor_msgs::msg::PointCloud2;
262  using ParentT = NDTLocalizerBase<
264  using Transform = typename ParentT::Transform;
266  using ScanT = P2DNDTScan;
267 
268  explicit P2DNDTLocalizer(
269  const P2DNDTLocalizerConfig & config,
270  const OptimizerT & optimizer,
271  const Real outlier_ratio)
272  : ParentT{
273  config,
274  P2DNDTOptimizationConfig{outlier_ratio},
275  optimizer,
276  ScanT{config.scan_capacity()},
277  MapT{config.map_config()}} {}
278 
279 protected:
282  const EigenPose<Real> &,
283  const EigenPose<Real> &,
284  PoseWithCovarianceStamped &) const override
285  {
286  // For now, do nothing.
287  }
288 };
289 
290 } // namespace ndt
291 } // namespace localization
292 } // namespace autoware
293 
294 #endif // NDT__NDT_LOCALIZER_HPP_
autoware::localization::ndt::P2DNDTLocalizer::CloudT
sensor_msgs::msg::PointCloud2 CloudT
Definition: ndt_localizer.hpp:261
autoware::localization::ndt::P2DNDTLocalizerConfig::scan_capacity
uint32_t scan_capacity() const noexcept
Definition: ndt_config.hpp:119
autoware::common::optimization::UnconstrainedOptimizationProblem
Definition: optimization_problem.hpp:332
autoware::localization::ndt::NDTLocalizerBase::insert_to_map_impl
void insert_to_map_impl(const CloudT &msg) override
Definition: ndt_localizer.hpp:141
localizer_base.hpp
autoware::localization::ndt::NDTLocalizerBase::config
const NDTLocalizerConfigBase & config() const noexcept
Get the localizer configuration.
Definition: ndt_localizer.hpp:162
autoware::localization::ndt::NDTLocalizerBase::optimizer
const OptimizerT & optimizer() const noexcept
Get the optimizer.
Definition: ndt_localizer.hpp:157
autoware::localization::localization_common::OptimizedRegistrationSummary
Definition: localizer_base.hpp:40
autoware::localization::ndt::NDTLocalizerBase::validate_msg
virtual void validate_msg(const CloudT &msg) const
Definition: ndt_localizer.hpp:207
autoware::localization::ndt::Real
float64_t Real
Definition: ndt_common.hpp:39
autoware::localization::localization_common::RelativeLocalizerBase< CloudT, CloudT, localization_common::OptimizedRegistrationSummary >::PoseWithCovarianceStamped
geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: localizer_base.hpp:61
autoware::localization::ndt::NDTLocalizerBase::set_covariance
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
autoware::localization::ndt::NDTLocalizerConfigBase::map_config
const MapConfig & map_config() const noexcept
Definition: ndt_config.hpp:61
ndt_optimization_problem.hpp
autoware::localization::ndt::NDTLocalizerBase::map_stamp
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
autoware::localization::ndt::NDTLocalizerBase::optimization_problem_config
const OptimizationProblemConfigT & optimization_problem_config() const noexcept
Get the optimization problem configuration.
Definition: ndt_localizer.hpp:167
autoware::localization::ndt::P2DNDTLocalizer::P2DNDTLocalizer
P2DNDTLocalizer(const P2DNDTLocalizerConfig &config, const OptimizerT &optimizer, const Real outlier_ratio)
Definition: ndt_localizer.hpp:268
autoware::localization::ndt::NDTLocalizerBase::scan
const ScanT & scan() const noexcept
Get the last used scan.
Definition: ndt_localizer.hpp:147
autoware::localization::ndt::P2DNDTOptimizationConfig
Config class for p2d optimziation problem.
Definition: ndt_config.hpp:80
optimizer_options.hpp
autoware::localization::ndt::EigenPose
Eigen::Matrix< T, 6U, 1U > EigenPose
Definition: localization/ndt/include/ndt/utils.hpp:83
autoware::localization::ndt::NDTLocalizerBase::validate_guess
virtual void validate_guess(const CloudT &msg, const Transform &transform_initial) const
Definition: ndt_localizer.hpp:223
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::P2DNDTScan
Definition: ndt_scan.hpp:99
autoware::localization::ndt::P2DNDTLocalizer
Definition: ndt_localizer.hpp:257
autoware::common::optimization::TerminationType::FAILURE
@ FAILURE
ndt_common.hpp
autoware::localization::ndt::NDTLocalizerConfigBase
Definition: ndt_config.hpp:32
motion::planning::recordreplay_planner_nodes::Transform
geometry_msgs::msg::TransformStamped Transform
Definition: recordreplay_planner_node.hpp:56
autoware::localization::ndt::P2DNDTLocalizer::Transform
typename ParentT::Transform Transform
Definition: ndt_localizer.hpp:264
motion::motion_testing_nodes::TransformStamped
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
time_utils::from_message
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
autoware::localization::ndt::NDTLocalizerBase::register_measurement_impl
RegistrationSummary register_measurement_impl(const CloudT &msg, const Transform &transform_initial, PoseWithCovarianceStamped &pose_out) override
Definition: ndt_localizer.hpp:90
autoware::localization::ndt::NDTLocalizerBase::NDTLocalizerBase
NDTLocalizerBase(const NDTLocalizerConfigBase &config, const OptimizationProblemConfigT &optimization_problem_config, const OptimizerT &optimizer, ScanT &&scan, MapT &&map)
Definition: ndt_localizer.hpp:68
autoware::localization::ndt::transform_adapters::transform_to_pose
void transform_to_pose(const TransformT &transform, PoseT &pose)
autoware::localization::localization_common::RelativeLocalizerBase< CloudT, CloudT, localization_common::OptimizedRegistrationSummary >::Transform
geometry_msgs::msg::TransformStamped Transform
Definition: localizer_base.hpp:62
autoware::localization::ndt::transform_adapters::pose_to_transform
void pose_to_transform(const PoseT &pose, TransformT &transform)
autoware::localization::ndt::P2DNDTLocalizer::PoseWithCovarianceStamped
typename ParentT::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: ndt_localizer.hpp:265
autoware::localization::ndt::CloudT
sensor_msgs::msg::PointCloud2 CloudT
Definition: ndt_localizer.hpp:35
autoware::localization::ndt::NDTLocalizerBase
Definition: ndt_localizer.hpp:49
autoware::localization::ndt::NDTLocalizerBase::set_map_impl
void set_map_impl(const CloudT &msg) override
Definition: ndt_localizer.hpp:133
autoware::localization::ndt::NDTLocalizerBase::map_frame_id
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
autoware::localization::localization_common::RelativeLocalizerBase
Definition: localizer_base.hpp:58
autoware::localization::ndt::NDTLocalizerBase::map
const MapT & map() const noexcept
Get the current map.
Definition: ndt_localizer.hpp:152
autoware::localization::ndt::NDTLocalizerBase::PoseWithCovarianceStamped
geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: ndt_localizer.hpp:54
autoware::localization::ndt::P2DNDTLocalizer::set_covariance
void set_covariance(const P2DNDTOptimizationProblem< MapT > &, const EigenPose< Real > &, const EigenPose< Real > &, PoseWithCovarianceStamped &) const override
Definition: ndt_localizer.hpp:280
autoware::localization::ndt::P2DNDTLocalizerConfig
config class for p2d ndt localizer
Definition: ndt_config.hpp:99