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 
22 #include <sensor_msgs/msg/point_cloud2.hpp>
23 #include <geometry_msgs/msg/transform.hpp>
24 #include <geometry_msgs/msg/transform_stamped.hpp>
25 #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
26 #include <ndt/ndt_common.hpp>
28 #include <ndt/constraints.hpp>
30 #include <experimental/optional>
31 #include <utility>
32 #include <string>
33 
34 namespace autoware
35 {
36 namespace localization
37 {
38 namespace ndt
39 {
41 
47 template<
48  typename ScanT,
49  typename NDTOptimizationProblemT,
50  typename OptimizationProblemConfigT,
51  typename OptimizerT>
52 class NDT_PUBLIC NDTLocalizerBase
53 {
54 public:
56  using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped;
58 
68  explicit NDTLocalizerBase(
69  const NDTLocalizerConfigBase & config,
70  const OptimizationProblemConfigT & optimization_problem_config,
71  const OptimizerT & optimizer,
72  ScanT && scan)
73  : m_config{config},
74  m_optimization_problem_config{optimization_problem_config},
75  m_optimizer{optimizer},
76  m_scan{std::forward<ScanT>(scan)} {}
77 
92  template<typename MapT,
95  const CloudT & msg,
96  const Transform & transform_initial,
97  const MapT & map,
98  Summary * const summary = nullptr)
99  {
100  PoseWithCovarianceStamped pose_out{};
101  validate_msg(msg, map);
102  validate_guess(msg, transform_initial);
103  // Initial checks passed, proceed with initialization
104  // Eigen representations to be used for internal computations.
105  EigenPose<Real> eig_pose_initial, eig_pose_result;
106  eig_pose_initial.setZero();
107  eig_pose_result.setZero();
108  // Convert the ros transform/pose to eigen pose vector
109  transform_adapters::transform_to_pose(transform_initial.transform, eig_pose_initial);
110 
111  // Set the scan
112  m_scan.clear();
113  m_scan.insert(msg);
114 
115  // Define and solve the problem.
116  NDTOptimizationProblemT problem(m_scan, map, m_optimization_problem_config);
117  const auto opt_summary = m_optimizer.solve(problem, eig_pose_initial, eig_pose_result);
118 
119  if (opt_summary.termination_type() == common::optimization::TerminationType::FAILURE) {
120  throw std::runtime_error(
121  "NDT localizer has likely encountered a numerical "
122  "error during optimization.");
123  }
124 
125  // Convert eigen pose back to ros pose/transform
127  eig_pose_result,
128  pose_out.pose.pose);
129 
130  pose_out.header.stamp = msg.header.stamp;
131  pose_out.header.frame_id = map.frame_id();
132 
133  // Populate covariance information. It is implementation defined.
134  set_covariance(problem, eig_pose_initial, eig_pose_result, pose_out);
135  if (summary != nullptr) {
137  }
138  return pose_out;
139  }
140 
141 
143  const ScanT & scan() const noexcept
144  {
145  return m_scan;
146  }
148  const OptimizerT & optimizer() const noexcept
149  {
150  return m_optimizer;
151  }
153  const NDTLocalizerConfigBase & config() const noexcept
154  {
155  return m_config;
156  }
158  const OptimizationProblemConfigT & optimization_problem_config() const noexcept
159  {
160  return m_optimization_problem_config;
161  }
162 
163 protected:
170  virtual void set_covariance(
171  const NDTOptimizationProblemT & problem,
172  const EigenPose<Real> & initial_guess,
173  const EigenPose<Real> & pose_result,
174  PoseWithCovarianceStamped & solution) const
175  {
176  (void) problem;
177  (void) initial_guess;
178  (void) pose_result;
179  (void) solution;
180  // For now, do nothing.
181  }
182 
188  template<typename MapT>
189  void validate_msg(const CloudT & msg, const MapT & map) const
190  {
191  const auto message_time = ::time_utils::from_message(msg.header.stamp);
192  // Map shouldn't be newer than a measurement.
193  if (message_time < map.stamp()) {
194  throw std::logic_error(
195  "Lidar scan should not have a timestamp older than the timestamp of"
196  "the current map.");
197  }
198  }
199 
205  virtual void validate_guess(const CloudT & msg, const Transform & transform_initial) const
206  {
207  const auto message_time = ::time_utils::from_message(msg.header.stamp);
208 
209  const auto guess_scan_diff = ::time_utils::from_message(transform_initial.header.stamp) -
210  message_time;
211  const auto stamp_tol = m_config.guess_time_tolerance();
212  // An initial estimate should be comparable in time to the measurement's time stamp
213  if (std::abs(
214  std::chrono::duration_cast<std::decay_t<decltype(stamp_tol)>>(guess_scan_diff).
215  count()) >
216  std::abs(stamp_tol.count()))
217  {
218  throw std::domain_error(
219  "Initial guess is not within: " + std::to_string(stamp_tol.count()) +
220  "ns range of the scan's time stamp. Either increase the tolerance range or"
221  "make sure the localizer takes in timely initial pose guesses.");
222  }
223  }
224 
225 private:
226  NDTLocalizerConfigBase m_config;
227  OptimizationProblemConfigT m_optimization_problem_config;
228  OptimizerT m_optimizer;
229  ScanT m_scan;
230 };
231 
237 template<typename OptimizerT, typename MapT = StaticNDTMap>
238 class NDT_PUBLIC P2DNDTLocalizer : public NDTLocalizerBase<
239  P2DNDTScan, P2DNDTOptimizationProblem<MapT>, P2DNDTOptimizationConfig, OptimizerT>
240 {
241 public:
243  using ParentT = NDTLocalizerBase<
245  using Transform = typename ParentT::Transform;
247  using ScanT = P2DNDTScan;
248 
249  explicit P2DNDTLocalizer(
250  const P2DNDTLocalizerConfig & config,
251  const OptimizerT & optimizer,
252  const Real outlier_ratio)
253  : ParentT{
254  config,
255  P2DNDTOptimizationConfig{outlier_ratio},
256  optimizer,
257  ScanT{config.scan_capacity()}} {}
258 
259 protected:
262  const EigenPose<Real> &,
263  const EigenPose<Real> &,
264  PoseWithCovarianceStamped &) const override
265  {
266  // For now, do nothing.
267  }
268 };
269 
270 } // namespace ndt
271 } // namespace localization
272 } // namespace autoware
273 
274 #endif // NDT__NDT_LOCALIZER_HPP_
autoware::localization::ndt::P2DNDTLocalizer::CloudT
sensor_msgs::msg::PointCloud2 CloudT
Definition: ndt_localizer.hpp:242
autoware::localization::ndt::P2DNDTLocalizerConfig::scan_capacity
uint32_t scan_capacity() const noexcept
Definition: ndt_config.hpp:89
autoware::common::optimization::UnconstrainedOptimizationProblem
Definition: optimization_problem.hpp:333
autoware::localization::ndt::NDTLocalizerBase< P2DNDTScan, P2DNDTOptimizationProblem< StaticNDTMap >, P2DNDTOptimizationConfig, OptimizerT >::Transform
geometry_msgs::msg::TransformStamped Transform
Definition: ndt_localizer.hpp:55
autoware::localization::ndt::NDTLocalizerBase::validate_msg
void validate_msg(const CloudT &msg, const MapT &map) const
Definition: ndt_localizer.hpp:189
autoware::localization::ndt::NDTLocalizerBase::optimizer
const OptimizerT & optimizer() const noexcept
Get the optimizer.
Definition: ndt_localizer.hpp:148
autoware::localization::ndt::NDTLocalizerBase::register_measurement
PoseWithCovarianceStamped register_measurement(const CloudT &msg, const Transform &transform_initial, const MapT &map, Summary *const summary=nullptr)
Definition: ndt_localizer.hpp:94
autoware::localization::localization_common::OptimizedRegistrationSummary
Definition: optimized_registration_summary.hpp:32
autoware::localization::ndt::NDTLocalizerBase::validate_guess
virtual void validate_guess(const CloudT &msg, const Transform &transform_initial) const
Definition: ndt_localizer.hpp:205
autoware::localization::ndt::Real
float64_t Real
Definition: ndt_common.hpp:38
autoware::localization::ndt::NDTLocalizerBase::scan
const ScanT & scan() const noexcept
Get the last used scan.
Definition: ndt_localizer.hpp:143
autoware::localization::ndt::NDTLocalizerBase::NDTLocalizerBase
NDTLocalizerBase(const NDTLocalizerConfigBase &config, const OptimizationProblemConfigT &optimization_problem_config, const OptimizerT &optimizer, ScanT &&scan)
Definition: ndt_localizer.hpp:68
ndt_optimization_problem.hpp
autoware::localization::ndt::P2DNDTLocalizer::P2DNDTLocalizer
P2DNDTLocalizer(const P2DNDTLocalizerConfig &config, const OptimizerT &optimizer, const Real outlier_ratio)
Definition: ndt_localizer.hpp:249
autoware::localization::ndt::P2DNDTOptimizationConfig
Config class for p2d optimziation problem.
Definition: ndt_config.hpp:54
optimizer_options.hpp
autoware::localization::ndt::EigenPose
Eigen::Matrix< T, 6U, 1U > EigenPose
Definition: localization/ndt/include/ndt/utils.hpp:128
autoware::localization::ndt::Requires
Requires
Definition: ndt/include/ndt/constraints.hpp:31
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::P2DNDTScan
Definition: ndt_scan.hpp:101
autoware::localization::ndt::P2DNDTLocalizer
Definition: ndt_localizer.hpp:238
autoware::common::optimization::TerminationType::FAILURE
@ FAILURE
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:170
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:245
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:80
autoware::localization::ndt::transform_adapters::transform_to_pose
void transform_to_pose(const TransformT &transform, PoseT &pose)
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:246
autoware::localization::ndt::CloudT
sensor_msgs::msg::PointCloud2 CloudT
Definition: ndt_localizer.hpp:40
autoware::localization::ndt::NDTLocalizerBase
Definition: ndt_localizer.hpp:52
autoware::localization::ndt::traits::LocalizationMapConstraint::value
static constexpr Requires value
Definition: ndt/include/ndt/constraints.hpp:61
autoware::localization::ndt::NDTLocalizerBase< P2DNDTScan, P2DNDTOptimizationProblem< StaticNDTMap >, P2DNDTOptimizationConfig, OptimizerT >::PoseWithCovarianceStamped
geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: ndt_localizer.hpp:56
autoware::localization::ndt::NDTLocalizerBase::optimization_problem_config
const OptimizationProblemConfigT & optimization_problem_config() const noexcept
Get the optimization problem configuration.
Definition: ndt_localizer.hpp:158
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:260
template_utils.hpp
autoware::perception::filters::filter_node_base::PointCloud2
sensor_msgs::msg::PointCloud2 PointCloud2
Definition: filter_node_base.cpp:32
optimized_registration_summary.hpp
autoware::localization::ndt::P2DNDTLocalizerConfig
config class for p2d ndt localizer
Definition: ndt_config.hpp:73
autoware::localization::ndt::NDTLocalizerBase::config
const NDTLocalizerConfigBase & config() const noexcept
Get the localizer configuration.
Definition: ndt_localizer.hpp:153
constraints.hpp