Loading [MathJax]/extensions/tex2jax.js
Autoware.Auto
measurement_interface.hpp
Go to the documentation of this file.
1// Copyright 2021 Apex.AI, Inc.
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 STATE_ESTIMATION__MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
18#define STATE_ESTIMATION__MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
19
23
24#include <type_traits>
25
26namespace autoware
27{
28namespace common
29{
30namespace state_estimation
31{
32
38template<typename Derived>
39struct STATE_ESTIMATION_PUBLIC MeasurementInterface : public common::helper_functions::crtp<Derived>
40 {
42  auto & state()
43  {
44  using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
45  static_assert(
47  "\n\nFunction crtp_state must return a state.\n\n");
48  return this->impl().crtp_state();
49  }
51  const auto & state() const
52  {
53  using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
54  static_assert(
56  "\n\nFunction crtp_state must return a state.\n\n");
57  return this->impl().crtp_state();
58  }
59 
61  auto & covariance() {return this->impl().crtp_covariance();}
62  const auto & covariance() const {return this->impl().crtp_covariance();}
63 
79  template<typename OtherStateT>
80  auto create_new_instance_from(const OtherStateT & other_state) const
81  {
82  static_assert(
84  "\n\nThe other state must be a state.\n\n");
85  using ReturnType =
86  std::decay_t<decltype(this->impl().crtp_create_new_instance_from(other_state))>;
87  static_assert(
89  "\n\nFunction crtp_create_new_instance_from must return a state.\n\n");
90  return this->impl().crtp_create_new_instance_from(other_state);
91  }
92 
106  template<typename OtherStateT>
107  OtherStateT map_into(const OtherStateT & other_state) const
108  {
109  static_assert(
111  "\n\nThe other state must be a state.\n\n");
112  return this->impl().crtp_map_into(other_state);
113  }
114 
130  template<typename OtherStateT>
131  auto mapping_matrix_from(const OtherStateT & other_state) const
132  {
133  static_assert(
135  "The other state must be a state.");
136  return this->impl().crtp_mapping_matrix_from(other_state);
137  }
138 };
139 
140 
141 } // namespace state_estimation
142 } // namespace common
143 } // namespace autoware
144 
145 #endif // STATE_ESTIMATION__MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
autoware::common::state_estimation::MeasurementInterface::state
auto & state()
Get measurement as a state vector.
Definition: measurement_interface.hpp:42
autoware::common::state_vector::is_state
Forward-declare is_state trait.
Definition: generic_state.hpp:51
autoware::common::state_estimation::MeasurementInterface::state
const auto & state() const
Get measurement as a state vector.
Definition: measurement_interface.hpp:51
autoware::common::state_estimation::MeasurementInterface
A CRTP interface to any measurement.
Definition: measurement_interface.hpp:39
autoware::common::state_estimation::MeasurementInterface::covariance
auto & covariance()
Get covariance of the measurement as a matrix.
Definition: measurement_interface.hpp:61
autoware::common::state_estimation::MeasurementInterface::covariance
const auto & covariance() const
Definition: measurement_interface.hpp:62
autoware::common::state_estimation::MeasurementInterface::map_into
OtherStateT map_into(const OtherStateT &other_state) const
Map this measurement into another state space.
Definition: measurement_interface.hpp:107
autoware::common::state_estimation::MeasurementInterface::mapping_matrix_from
auto mapping_matrix_from(const OtherStateT &other_state) const
Get a matrix that maps a state to this measurement's state space.
Definition: measurement_interface.hpp:131
generic_state.hpp
This file defines a class for a generic state vector representation.
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::helper_functions::crtp
Definition: crtp.hpp:29
crtp.hpp
This file includes common helper functions.
visibility_control.hpp
autoware::common::state_estimation::MeasurementInterface::create_new_instance_from
auto create_new_instance_from(const OtherStateT &other_state) const
Create a new instance of the measurement from another state.
Definition: measurement_interface.hpp:80