Autoware.Auto
control/motion_common/include/motion_common/config.hpp
Go to the documentation of this file.
1 // Copyright 2019 Christopher Ho
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 #ifndef MOTION_COMMON__CONFIG_HPP_
15 #define MOTION_COMMON__CONFIG_HPP_
16 
19 
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; \
25  ~Class() = default;
26 
27 namespace motion
28 {
29 namespace motion_common
30 {
38 
40 class MOTION_COMMON_PUBLIC LimitsConfig
41 {
42 public:
44  class Extremum
45  {
46 public:
47  Extremum(Real min, Real max);
49 
50  Real min() const noexcept;
51  Real max() const noexcept;
52 
53 private:
54  Real m_min;
55  Real m_max;
56  }; // class Extremum
57 
59  Extremum longitudinal_velocity_mps,
60  Extremum lateral_velocity_mps,
61  Extremum acceleration_mps2,
62  Extremum yaw_rate_rps,
63  Extremum jerk_mps3,
64  Extremum steer_angle_rad,
65  Extremum steer_angle_rate_rps);
67 
68  Extremum longitudinal_velocity() const noexcept;
69  Extremum lateral_velocity() const noexcept;
70  Extremum acceleration() const noexcept;
71  Extremum jerk() const noexcept;
72  Extremum yaw_rate() const noexcept;
73  Extremum steer_angle() const noexcept;
74  Extremum steer_angle_rate() const noexcept;
75 
76 private:
77  Extremum m_longitudinal_velocity_limits_mps;
78  Extremum m_lateral_velocity_limits_mps;
79  Extremum m_acceleration_limits_mps2;
80  Extremum m_yaw_rate_limits_rps;
81  Extremum m_jerk_limits_mps3;
82  Extremum m_steer_angle_limits_rad;
83  Extremum m_steer_angle_rate_limits_rps;
84 }; // class LimitsConfig
85 
87 class MOTION_COMMON_PUBLIC VehicleConfig
88 {
89 public:
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,
95  Real mass_kg,
96  Real inertia_kgm2,
97  Real width_m,
98  Real front_overhang_m,
99  Real rear_overhang_m);
101 
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;
111 
112 private:
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;
117  Real m_mass_kg;
118  Real m_inertia_kgm2;
119  Real m_width_m;
120  Real m_front_overhang_m;
121  Real m_rear_overhang_m;
122 }; // class VehicleConfig
123 
126 class MOTION_COMMON_PUBLIC StateWeight
127 {
128 public:
129  StateWeight(
130  Real pose,
131  Real heading,
132  Real longitudinal_velocity,
133  Real lateral_velocity,
134  Real yaw_rate,
135  Real acceleration,
136  Real jerk,
137  Real steer_angle,
138  Real steer_angle_rate);
140 
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;
150 
151 private:
152  Real m_pose_weight;
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;
158  Real m_jerk_weight;
159  Real m_steer_angle_weight;
160  Real m_steer_angle_rate_weight;
161 }; // class StateWeight
162 
165 class MOTION_COMMON_PUBLIC OptimizationConfig
166 {
167 public:
169  StateWeight nominal_weights,
170  StateWeight terminal_weights);
172 
173  StateWeight nominal() const noexcept;
174  StateWeight terminal() const noexcept;
175 
176 private:
177  StateWeight m_nominal_weights;
178  StateWeight m_terminal_weights;
179 }; // class OptimizationConfig
180 } // namespace motion_common
181 } // namespace motion
182 #endif // MOTION_COMMON__CONFIG_HPP_
decltype(autoware_auto_msgs::msg::TrajectoryPoint::x) Real
Definition: motion_common.hpp:33
decltype(Trajectory::points)::value_type Point
Definition: motion_common.hpp:40
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:37
Class representing min and max values for a variable.
Definition: control/motion_common/include/motion_common/config.hpp:44
decltype(Trajectory::points)::size_type Index
Definition: motion_common.hpp:39
Extreme values for state/control variables.
Definition: control/motion_common/include/motion_common/config.hpp:40
Definition: controller_base.hpp:30
autoware_auto_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:36
Vehicle parameters specifying vehicle's handling performance.
Definition: control/motion_common/include/motion_common/config.hpp:87
autoware_auto_msgs::msg::VehicleControlCommand Command
Definition: motion_common.hpp:34
decltype(decltype(State::state)::heading) Heading
Definition: motion_common.hpp:38
Specifies the weights used for particular state weights in the least-squares objective function of th...
Definition: control/motion_common/include/motion_common/config.hpp:126
#define MOTION_COMMON_COPY_MOVE_ASSIGNABLE(Class)
Definition: control/motion_common/include/motion_common/config.hpp:20
Specifies various parameters specific to the optimization problem and it's behaviors Depending on pro...
Definition: control/motion_common/include/motion_common/config.hpp:165