Autoware.Auto
stationary_motion_model.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 // Developed by Apex.AI, Inc.
16 
17 #ifndef MOTION_MODEL__STATIONARY_MOTION_MODEL_HPP_
18 #define MOTION_MODEL__STATIONARY_MOTION_MODEL_HPP_
19 
24 
25 namespace autoware
26 {
27 namespace common
28 {
29 namespace motion_model
30 {
31 
38 template<typename StateT>
39 class MOTION_MODEL_PUBLIC StationaryMotionModel
40  : public MotionModelInterface<StationaryMotionModel<StateT>>
41 {
42 public:
43  using State = StateT;
44 
45 protected:
46  // Allow the CRTP interface to call private functions.
48 
56  inline const State & crtp_predict(
57  const State & state,
58  const std::chrono::nanoseconds &) const
59  {
60  return state;
61  }
62 
68  typename State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
69  {
70  return Eigen::Matrix<typename State::Scalar, State::size(), State::size()>::Identity();
71  }
72 };
73 
74 } // namespace motion_model
75 } // namespace common
76 } // namespace autoware
77 
78 #endif // MOTION_MODEL__STATIONARY_MOTION_MODEL_HPP_
motion_model_interface.hpp
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::motion_model::StationaryMotionModel::crtp_jacobian
State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const
A crtp-called function that computes a Jacobian for the stationary motion model.
Definition: stationary_motion_model.hpp:68
autoware::common::motion_model::StationaryMotionModel
This class describes a stationary motion model, i.e., the model that does not change the state.
Definition: stationary_motion_model.hpp:39
autoware::common::motion_model::MotionModelInterface
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:39
visibility_control.hpp
autoware::common::motion_model::StationaryMotionModel::State
StateT State
Definition: stationary_motion_model.hpp:43
autoware::common::motion_model::StationaryMotionModel::crtp_predict
const State & crtp_predict(const State &state, const std::chrono::nanoseconds &) const
A crtp-called function that predicts the state forward.
Definition: stationary_motion_model.hpp:56
common_states.hpp
This file holds a collection of states that are commonly used in this package.