Branch data Line data Source code
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 : : 20 : : #include <motion_model/motion_model_interface.hpp> 21 : : #include <motion_model/visibility_control.hpp> 22 : : #include <state_vector/common_states.hpp> 23 : : #include <state_vector/generic_state.hpp> 24 : : 25 : : namespace autoware 26 : : { 27 : : namespace common 28 : : { 29 : : namespace motion_model 30 : : { 31 : : 32 : : /// 33 : : /// @brief This class describes a stationary motion model, i.e., the model that does not change 34 : : /// the state. 35 : : /// 36 : : /// @tparam StateT State with which the motion model works. 37 : : /// 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. 47 : : friend MotionModelInterface<StationaryMotionModel<StateT>>; 48 : : 49 : : /// 50 : : /// @brief A crtp-called function that predicts the state forward. 51 : : /// 52 : : /// @param[in] state The current state vector 53 : : /// 54 : : /// @return A const reference to the unchanged input state. 55 : : /// 56 : 2 : inline const State & crtp_predict( 57 : : const State & state, 58 : : const std::chrono::nanoseconds &) const 59 : : { 60 : 2 : return state; 61 : : } 62 : : 63 : : /// 64 : : /// @brief A crtp-called function that computes a Jacobian for the stationary motion model. 65 : : /// 66 : : /// @return An identity matrix. 67 : : /// 68 : 1 : typename State::Matrix crtp_jacobian(const State &, const std::chrono::nanoseconds &) const 69 : : { 70 [ + - ]: 1 : 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_