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 {
37 
39 class MOTION_COMMON_PUBLIC LimitsConfig
40 {
41 public:
43  class Extremum
44  {
45 public:
46  Extremum(Real min, Real max);
48 
49  Real min() const noexcept;
50  Real max() const noexcept;
51 
52 private:
53  Real m_min;
54  Real m_max;
55  }; // class Extremum
56 
58  Extremum longitudinal_velocity_mps,
59  Extremum lateral_velocity_mps,
60  Extremum acceleration_mps2,
61  Extremum yaw_rate_rps,
62  Extremum jerk_mps3,
63  Extremum steer_angle_rad,
64  Extremum steer_angle_rate_rps);
66 
67  Extremum longitudinal_velocity() const noexcept;
68  Extremum lateral_velocity() const noexcept;
69  Extremum acceleration() const noexcept;
70  Extremum jerk() const noexcept;
71  Extremum yaw_rate() const noexcept;
72  Extremum steer_angle() const noexcept;
73  Extremum steer_angle_rate() const noexcept;
74 
75 private:
76  Extremum m_longitudinal_velocity_limits_mps;
77  Extremum m_lateral_velocity_limits_mps;
78  Extremum m_acceleration_limits_mps2;
79  Extremum m_yaw_rate_limits_rps;
80  Extremum m_jerk_limits_mps3;
81  Extremum m_steer_angle_limits_rad;
82  Extremum m_steer_angle_rate_limits_rps;
83 }; // class LimitsConfig
84 
86 class MOTION_COMMON_PUBLIC VehicleConfig
87 {
88 public:
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,
94  Real mass_kg,
95  Real inertia_kgm2,
96  Real width_m,
97  Real front_overhang_m,
98  Real rear_overhang_m);
100 
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;
110 
111 private:
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;
116  Real m_mass_kg;
117  Real m_inertia_kgm2;
118  Real m_width_m;
119  Real m_front_overhang_m;
120  Real m_rear_overhang_m;
121 }; // class VehicleConfig
122 
125 class MOTION_COMMON_PUBLIC StateWeight
126 {
127 public:
128  StateWeight(
129  Real pose,
130  Real heading,
131  Real longitudinal_velocity,
132  Real lateral_velocity,
133  Real yaw_rate,
134  Real acceleration,
135  Real jerk,
136  Real steer_angle,
137  Real steer_angle_rate);
139 
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;
149 
150 private:
151  Real m_pose_weight;
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;
157  Real m_jerk_weight;
158  Real m_steer_angle_weight;
159  Real m_steer_angle_rate_weight;
160 }; // class StateWeight
161 
164 class MOTION_COMMON_PUBLIC OptimizationConfig
165 {
166 public:
168  StateWeight nominal_weights,
169  StateWeight terminal_weights);
171 
172  StateWeight nominal() const noexcept;
173  StateWeight terminal() const noexcept;
174 
175 private:
176  StateWeight m_nominal_weights;
177  StateWeight m_terminal_weights;
178 }; // class OptimizationConfig
179 } // namespace motion_common
180 } // namespace motion
181 #endif // MOTION_COMMON__CONFIG_HPP_
motion::motion_common::VehicleConfig
Vehicle parameters specifying vehicle's handling performance.
Definition: control/motion_common/include/motion_common/config.hpp:86
motion::motion_common::Real
decltype(autoware_auto_planning_msgs::msg::TrajectoryPoint::longitudinal_velocity_mps) Real
Definition: motion_common.hpp:37
visibility_control.hpp
autoware::motion::motion_common
Definition: trajectory_common.hpp:37
motion::motion_common::Command
autoware_auto_vehicle_msgs::msg::VehicleControlCommand Command
Definition: motion_common.hpp:38
motion::motion_common::LimitsConfig::Extremum
Class representing min and max values for a variable.
Definition: control/motion_common/include/motion_common/config.hpp:43
motion::motion_common::LimitsConfig
Extreme values for state/control variables.
Definition: control/motion_common/include/motion_common/config.hpp:39
motion::motion_common::State
autoware_auto_vehicle_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:40
MOTION_COMMON_COPY_MOVE_ASSIGNABLE
#define MOTION_COMMON_COPY_MOVE_ASSIGNABLE(Class)
Definition: control/motion_common/include/motion_common/config.hpp:20
motion::motion_common::Point
decltype(Trajectory::points)::value_type Point
Definition: motion_common.hpp:45
motion_common.hpp
motion::motion_common::Index
decltype(Trajectory::points)::size_type Index
Definition: motion_common.hpp:44
motion::motion_common::StateWeight
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:125
motion
Definition: controller_base.hpp:31
motion::motion_common::Trajectory
autoware_auto_planning_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:41
motion::motion_common::OptimizationConfig
Specifies various parameters specific to the optimization problem and it's behaviors Depending on pro...
Definition: control/motion_common/include/motion_common/config.hpp:164