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; \
29 namespace motion_common
50 Real min()
const noexcept;
51 Real max()
const noexcept;
68 Extremum longitudinal_velocity() const noexcept;
69 Extremum lateral_velocity() const noexcept;
70 Extremum acceleration() const noexcept;
73 Extremum steer_angle() const noexcept;
74 Extremum steer_angle_rate() const noexcept;
77 Extremum m_longitudinal_velocity_limits_mps;
78 Extremum m_lateral_velocity_limits_mps;
83 Extremum m_steer_angle_rate_limits_rps;
91 Real length_cg_front_axel_m,
92 Real length_cg_rear_axel_m,
93 Real front_cornering_stiffness_N,
94 Real rear_cornering_stiffness_N,
98 Real front_overhang_m,
99 Real rear_overhang_m);
102 Real length_cg_front_axel()
const noexcept;
103 Real length_cg_rear_axel()
const noexcept;
104 Real front_cornering_stiffness()
const noexcept;
105 Real rear_cornering_stiffness()
const noexcept;
106 Real mass()
const noexcept;
107 Real inertia()
const noexcept;
108 Real width()
const noexcept;
109 Real front_overhang()
const noexcept;
110 Real rear_overhang()
const noexcept;
113 Real m_length_cg_to_front_axel_m;
114 Real m_length_cg_to_rear_axel_m;
115 Real m_front_cornering_stiffness_N;
116 Real m_rear_cornering_stiffness_N;
120 Real m_front_overhang_m;
121 Real m_rear_overhang_m;
132 Real longitudinal_velocity,
133 Real lateral_velocity,
138 Real steer_angle_rate);
141 Real pose()
const noexcept;
142 Real heading()
const noexcept;
143 Real longitudinal_velocity()
const noexcept;
144 Real lateral_velocity()
const noexcept;
145 Real yaw_rate()
const noexcept;
146 Real acceleration()
const noexcept;
147 Real jerk()
const noexcept;
148 Real steer_angle()
const noexcept;
149 Real steer_angle_rate()
const noexcept;
153 Real m_heading_weight;
154 Real m_longitudinal_velocity_weight;
155 Real m_lateral_velocity_weight;
156 Real m_yaw_rate_weight;
157 Real m_acceleration_weight;
159 Real m_steer_angle_weight;
160 Real m_steer_angle_rate_weight;
182 #endif // MOTION_COMMON__CONFIG_HPP_