14 #ifndef MOTION_COMMON__CONFIG_HPP_
15 #define MOTION_COMMON__CONFIG_HPP_
20 #define MOTION_COMMON_COPY_MOVE_ASSIGNABLE(Class) \
21 Class(const Class &) = default; \
22 Class(Class &&) = default; \
23 Class & operator=(const Class &) = default; \
24 Class & operator=(Class &&) = default; \
49 Real min()
const noexcept;
50 Real max()
const noexcept;
67 Extremum longitudinal_velocity() const noexcept;
68 Extremum lateral_velocity() const noexcept;
69 Extremum acceleration() const noexcept;
72 Extremum steer_angle() const noexcept;
73 Extremum steer_angle_rate() const noexcept;
76 Extremum m_longitudinal_velocity_limits_mps;
77 Extremum m_lateral_velocity_limits_mps;
82 Extremum m_steer_angle_rate_limits_rps;
90 Real length_cg_front_axel_m,
91 Real length_cg_rear_axel_m,
92 Real front_cornering_stiffness_N,
93 Real rear_cornering_stiffness_N,
97 Real front_overhang_m,
98 Real rear_overhang_m);
101 Real length_cg_front_axel()
const noexcept;
102 Real length_cg_rear_axel()
const noexcept;
103 Real front_cornering_stiffness()
const noexcept;
104 Real rear_cornering_stiffness()
const noexcept;
105 Real mass()
const noexcept;
106 Real inertia()
const noexcept;
107 Real width()
const noexcept;
108 Real front_overhang()
const noexcept;
109 Real rear_overhang()
const noexcept;
112 Real m_length_cg_to_front_axel_m;
113 Real m_length_cg_to_rear_axel_m;
114 Real m_front_cornering_stiffness_N;
115 Real m_rear_cornering_stiffness_N;
119 Real m_front_overhang_m;
120 Real m_rear_overhang_m;
131 Real longitudinal_velocity,
132 Real lateral_velocity,
137 Real steer_angle_rate);
140 Real pose()
const noexcept;
141 Real heading()
const noexcept;
142 Real longitudinal_velocity()
const noexcept;
143 Real lateral_velocity()
const noexcept;
144 Real yaw_rate()
const noexcept;
145 Real acceleration()
const noexcept;
146 Real jerk()
const noexcept;
147 Real steer_angle()
const noexcept;
148 Real steer_angle_rate()
const noexcept;
152 Real m_heading_weight;
153 Real m_longitudinal_velocity_weight;
154 Real m_lateral_velocity_weight;
155 Real m_yaw_rate_weight;
156 Real m_acceleration_weight;
158 Real m_steer_angle_weight;
159 Real m_steer_angle_rate_weight;
181 #endif // MOTION_COMMON__CONFIG_HPP_