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 {
40 
42 using motion_common::StateWeight;
43 using motion_common::LimitsConfig;
44 using motion_common::VehicleConfig;
45 using motion_common::OptimizationConfig;
46 using motion_common::LimitsConfig;
47 
48 enum class Interpolation : uint8_t
49 {
50  YES = 0U,
51  NO = 1U
52 };
53 
55 class MPC_CONTROLLER_PUBLIC Config
56 {
57 public:
58  Config(
59  const LimitsConfig & limits,
60  const VehicleConfig & vehicle_param,
61  const BehaviorConfig & behavior,
62  const OptimizationConfig & optimization_param,
63  std::chrono::nanoseconds sample_period_tolerance,
64  std::chrono::nanoseconds control_lookahead_duration,
65  Interpolation interpolation_option);
67 
68  const LimitsConfig & limits() const noexcept;
69  const VehicleConfig & vehicle_param() const noexcept;
70  const BehaviorConfig & behavior() const noexcept;
71  const OptimizationConfig & optimization_param() const noexcept;
72  std::chrono::nanoseconds sample_period_tolerance() const noexcept;
73  std::chrono::nanoseconds control_lookahead_duration() const noexcept;
74  bool do_interpolate() const noexcept;
75 
76 private:
77  LimitsConfig m_limits;
78  VehicleConfig m_vehicle_param;
79  BehaviorConfig m_behavior_param;
80  OptimizationConfig m_optimization_param;
81  std::chrono::nanoseconds m_sample_period_tolerance;
82  std::chrono::nanoseconds m_control_lookahead_duration;
83  bool m_do_interpolate;
84 }; // class Config
85 
86 struct MPC_CONTROLLER_PUBLIC ControlDerivatives
87 {
90 }; // struct ControlDerivatives
91 } // namespace mpc_controller
92 } // namespace control
93 } // namespace motion
94 #endif // MPC_CONTROLLER__CONFIG_HPP_
motion::motion_common::Real
decltype(autoware_auto_planning_msgs::msg::TrajectoryPoint::longitudinal_velocity_mps) Real
Definition: motion_common.hpp:37
motion::control::mpc_controller::ControlDerivatives::steer_angle_rate_rps
Real steer_angle_rate_rps
Definition: control/mpc_controller/include/mpc_controller/config.hpp:89
motion::control::mpc_controller::ControlDerivatives
Definition: control/mpc_controller/include/mpc_controller/config.hpp:86
motion::motion_common::Command
autoware_auto_vehicle_msgs::msg::VehicleControlCommand Command
Definition: motion_common.hpp:38
motion::motion_common::State
autoware_auto_vehicle_msgs::msg::VehicleKinematicState State
Definition: motion_common.hpp:40
controller_base.hpp
motion::control::mpc_controller::ControlDerivatives::jerk_mps3
Real jerk_mps3
Definition: control/mpc_controller/include/mpc_controller/config.hpp:88
motion::control::mpc_controller::Config
A configuration class for the MpcController.
Definition: control/mpc_controller/include/mpc_controller/config.hpp:55
config.hpp
motion::control::mpc_controller::Interpolation::YES
@ YES
motion::motion_common::Point
decltype(Trajectory::points)::value_type Point
Definition: motion_common.hpp:45
motion::motion_common::Index
decltype(Trajectory::points)::size_type Index
Definition: motion_common.hpp:44
visibility_control.hpp
motion
Definition: controller_base.hpp:31
motion::control::mpc_controller::Interpolation::NO
@ NO
motion::control::controller_common::BehaviorConfig
Specifies the behavior of the controller.
Definition: controller_base.hpp:53
motion::motion_common::Trajectory
autoware_auto_planning_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:41
motion::control::mpc_controller::Interpolation
Interpolation
Definition: control/mpc_controller/include/mpc_controller/config.hpp:48
MPC_CONTROLLER_COPY_MOVE_ASSIGNABLE
#define MPC_CONTROLLER_COPY_MOVE_ASSIGNABLE(Class)
Definition: control/mpc_controller/include/mpc_controller/config.hpp:21