Autoware.Auto
differential_drive_motion_model.hpp
Go to the documentation of this file.
1 // Copyright 2021 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 // Developed by Apex.AI, Inc.
16 
21 
22 #ifndef MOTION_MODEL__DIFFERENTIAL_DRIVE_MOTION_MODEL_HPP_
23 #define MOTION_MODEL__DIFFERENTIAL_DRIVE_MOTION_MODEL_HPP_
24 
29 
30 namespace autoware
31 {
32 namespace prediction
33 {
34 
37 template<typename StateT>
38 class KALMAN_FILTER_PUBLIC DifferentialDriveMotionModel
39  : public MotionModelInterface<DifferentialDriveMotionModel<StateT>>
40 {
41 public:
42  using State = StateT;
43 
44 protected:
45  // Allow the CRTP interface to call private functions.
47 
49  State crtp_predict(const State &, const std::chrono::nanoseconds &) const
50  {
51  static_assert(
52  sizeof(StateT) == 0,
53  "Function crtp_predict is expected to be specialized for every state it is used with.");
54  }
55 
57  typename State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
58  {
59  static_assert(
60  sizeof(StateT) == 0,
61  "Function crtp_jacobian is expected to be specialized for every state it is used with.");
62  }
63 };
64 
71 
72 
74 template<>
76  const CvtrMotionModel::State & state,
77  const std::chrono::nanoseconds & dt) const;
78 
80 template<>
81 KALMAN_FILTER_PUBLIC CvtrMotionModel::State::Matrix CvtrMotionModel::crtp_jacobian(
82  const CvtrMotionModel::State & state,
83  const std::chrono::nanoseconds & dt) const;
84 
85 
87 template<>
89  const CatrMotionModel::State & state,
90  const std::chrono::nanoseconds & dt) const;
91 
93 template<>
94 KALMAN_FILTER_PUBLIC CatrMotionModel::State::Matrix CatrMotionModel::crtp_jacobian(
95  const CatrMotionModel::State & state,
96  const std::chrono::nanoseconds & dt) const;
97 
98 
99 } // namespace prediction
100 } // namespace autoware
101 
102 #endif // MOTION_MODEL__DIFFERENTIAL_DRIVE_MOTION_MODEL_HPP_
visibility_control.hpp
autoware::prediction::MotionModelInterface
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:41
autoware::prediction::DifferentialDriveMotionModel
A generic differential motion model. This class only exists to be specialized for specific motion mod...
Definition: differential_drive_motion_model.hpp:38
motion_model_interface.hpp
This file defines an interface for the motion model.
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::prediction::DifferentialDriveMotionModel::State
StateT State
Definition: differential_drive_motion_model.hpp:42
autoware::prediction::DifferentialDriveMotionModel::crtp_predict
State crtp_predict(const State &, const std::chrono::nanoseconds &) const
A crtp-called function that predicts the state forward.
Definition: differential_drive_motion_model.hpp:49
common_states.hpp
This file holds a collection of states that are commonly used in this package.
autoware::prediction::DifferentialDriveMotionModel::crtp_jacobian
State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
A crtp-called function that computes a Jacobian.
Definition: differential_drive_motion_model.hpp:57