Autoware.Auto
control/mpc_controller/include/mpc_controller/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 MPC_CONTROLLER__CONFIG_HPP_
15 #define MPC_CONTROLLER__CONFIG_HPP_
16 
19 #include <motion_common/config.hpp>
20 
21 #define MPC_CONTROLLER_COPY_MOVE_ASSIGNABLE(Class) \
22  Class(const Class &) = default; \
23  Class(Class &&) = default; \
24  Class & operator=(const Class &) = default; \
25  Class & operator=(Class &&) = default; \
26  ~Class() = default;
27 
28 namespace motion
29 {
30 namespace control
31 {
32 namespace mpc_controller
33 {
41 
48 
49 enum class Interpolation : uint8_t
50 {
51  YES = 0U,
52  NO = 1U
53 };
54 
56 class MPC_CONTROLLER_PUBLIC Config
57 {
58 public:
59  Config(
60  const LimitsConfig & limits,
61  const VehicleConfig & vehicle_param,
62  const BehaviorConfig & behavior,
63  const OptimizationConfig & optimization_param,
64  std::chrono::nanoseconds sample_period_tolerance,
65  std::chrono::nanoseconds control_lookahead_duration,
66  Interpolation interpolation_option);
68 
69  const LimitsConfig & limits() const noexcept;
70  const VehicleConfig & vehicle_param() const noexcept;
71  const BehaviorConfig & behavior() const noexcept;
72  const OptimizationConfig & optimization_param() const noexcept;
73  std::chrono::nanoseconds sample_period_tolerance() const noexcept;
74  std::chrono::nanoseconds control_lookahead_duration() const noexcept;
75  bool do_interpolate() const noexcept;
76 
77 private:
78  LimitsConfig m_limits;
79  VehicleConfig m_vehicle_param;
80  BehaviorConfig m_behavior_param;
81  OptimizationConfig m_optimization_param;
82  std::chrono::nanoseconds m_sample_period_tolerance;
83  std::chrono::nanoseconds m_control_lookahead_duration;
84  bool m_do_interpolate;
85 }; // class Config
86 
87 struct MPC_CONTROLLER_PUBLIC ControlDerivatives
88 {
91 }; // struct ControlDerivatives
92 } // namespace mpc_controller
93 } // namespace control
94 } // namespace motion
95 #endif // MPC_CONTROLLER__CONFIG_HPP_
decltype(autoware_auto_msgs::msg::TrajectoryPoint::x) Real
Definition: motion_common.hpp:33
Interpolation
Definition: control/mpc_controller/include/mpc_controller/config.hpp:49
decltype(Trajectory::points)::value_type Point
Definition: motion_common.hpp:40
autoware_auto_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:37
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
#define MPC_CONTROLLER_COPY_MOVE_ASSIGNABLE(Class)
Definition: control/mpc_controller/include/mpc_controller/config.hpp:21
Definition: control/mpc_controller/include/mpc_controller/config.hpp:87
Real steer_angle_rate_rps
Definition: control/mpc_controller/include/mpc_controller/config.hpp:90
Real jerk_mps3
Definition: control/mpc_controller/include/mpc_controller/config.hpp:89
Specifies the behavior of the controller.
Definition: controller_base.hpp:53
Definition: controller_base.hpp:30
A configuration class for the MpcController.
Definition: control/mpc_controller/include/mpc_controller/config.hpp:56
autoware_auto_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:36
Vehicle parameters specifying vehicle&#39;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
Specifies various parameters specific to the optimization problem and it&#39;s behaviors Depending on pro...
Definition: control/motion_common/include/motion_common/config.hpp:165