Autoware.Auto
covariance_insertion.hpp
Go to the documentation of this file.
1 // Copyright 2020 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 
17 
18 #ifndef COVARIANCE_INSERTION__COVARIANCE_INSERTION_HPP_
19 #define COVARIANCE_INSERTION__COVARIANCE_INSERTION_HPP_
20 
21 #include <common/types.hpp>
24 
25 #include <map>
26 #include <string>
27 #include <vector>
28 
29 namespace autoware
30 {
31 namespace covariance_insertion
32 {
34 class COVARIANCE_INSERTION_PUBLIC CovarianceInsertion
35 {
36 public:
39 
42  template<typename MsgT>
43  void set_all_covariances(MsgT * msg)
44  {
45  if (!msg) {return;}
46  for (const auto & kv : m_covariances) {
47  const auto & field = kv.first;
48  const auto & covariance = kv.second;
49  add_covariance(msg, covariance, field);
50  }
51  }
52 
54  bool covariances_empty();
55 
59  void insert_covariance(
60  const std::string & field,
61  const std::vector<common::types::float64_t> & covariance);
62 
63 private:
65  std::map<std::string, std::vector<common::types::float64_t>> m_covariances;
66 };
67 } // namespace covariance_insertion
68 } // namespace autoware
69 
70 #endif // COVARIANCE_INSERTION__COVARIANCE_INSERTION_HPP_
void add_covariance(MsgT *msg, const std::vector< ScalarT > &covariance, const std::enable_if_t< has_covariance_member< MsgT >::value, std::string > &field)
Definition: add_covariance.hpp:40
Class for performing covariance insertion.
Definition: covariance_insertion.hpp:34
This file includes common type definition.
void set_all_covariances(MsgT *msg)
populate msg from the covarianes
Definition: covariance_insertion.hpp:43
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24