21 #ifndef MOTION_MODEL__CATR_MODEL_HPP_ 22 #define MOTION_MODEL__CATR_MODEL_HPP_ 36 namespace motion_model
57 Eigen::Matrix<float32_t, 6U, 1U> &
x,
58 const std::chrono::nanoseconds & dt)
const override;
66 void predict(
const std::chrono::nanoseconds & dt)
override;
71 void compute_jacobian(
72 Eigen::Matrix<float32_t, 6U, 6U> & F,
73 const std::chrono::nanoseconds & dt)
override;
81 void compute_jacobian_and_predict(
82 Eigen::Matrix<float32_t, 6U, 6U> & F,
83 const std::chrono::nanoseconds & dt)
override;
92 void reset(
const Eigen::Matrix<float32_t, 6U, 1U> & x)
override;
96 const Eigen::Matrix<float32_t, 6U, 1U> & get_state()
const override;
100 Eigen::Matrix<float32_t, 6U, 1U> m_state{Eigen::Matrix<float32_t, 6U, 1U>::Zero()};
108 #endif // MOTION_MODEL__CATR_MODEL_HPP_ This struct holds some common worker variables for CATR model's jacobian and prediction computation...
Definition: catr_core.hpp:40
float float32_t
Definition: types.hpp:36
This struct holds some common worker variables for CATR model's jacobian and prediction computation...
Definition: catr_core.hpp:54
This file defines the constant velocity motion model.
This file includes common type definition.
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
Definition: controller_base.hpp:30
This file defines the motion model interface used by kalman filters.
Eigen::Index index_t
indexing matches what matrices use
Definition: motion_model.hpp:41
Virtual interface for all motion models for use with prediction.
Definition: motion_model.hpp:46
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
This is a constant acceleration, constant turn-rate motion model. This model produces clothoidal traj...
Definition: catr_model.hpp:41