Autoware.Auto
linear_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__LINEAR_MOTION_MODEL_HPP_
18 #define MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
19 
24 
25 namespace autoware
26 {
27 namespace common
28 {
29 namespace motion_model
30 {
31 
41 template<typename StateT>
42 class MOTION_MODEL_PUBLIC LinearMotionModel
43  : public MotionModelInterface<LinearMotionModel<StateT>>
44 {
45 public:
46  using State = StateT;
47 
48 protected:
49  // Allow the CRTP interface to call private functions.
51 
61  const State & state,
62  const std::chrono::nanoseconds & dt) const
63  {
64  return State{crtp_jacobian(state, dt) * state.vector()};
65  }
66 
76  typename State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds & dt) const;
77 };
78 
79 } // namespace motion_model
80 } // namespace common
81 } // namespace autoware
82 
83 #endif // MOTION_MODEL__LINEAR_MOTION_MODEL_HPP_
motion_model_interface.hpp
motion::motion_common::State
autoware_auto_vehicle_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:40
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::LinearMotionModel::crtp_predict
State crtp_predict(const State &state, const std::chrono::nanoseconds &dt) const
A crtp-called function that predicts the state forward.
Definition: linear_motion_model.hpp:60
autoware::common::motion_model::LinearMotionModel::State
StateT State
Definition: linear_motion_model.hpp:46
autoware::common::motion_model::LinearMotionModel
A generic linear motion model class.
Definition: linear_motion_model.hpp:42
autoware::common::motion_model::MotionModelInterface
A CRTP interface for any motion model.
Definition: motion_model_interface.hpp:39
visibility_control.hpp
common_states.hpp
This file holds a collection of states that are commonly used in this package.