14 #ifndef MPC_CONTROLLER__MPC_CONTROLLER_HPP_
15 #define MPC_CONTROLLER__MPC_CONTROLLER_HPP_
18 #include <autoware_auto_planning_msgs/msg/trajectory.hpp>
19 #include <autoware_auto_vehicle_msgs/msg/vehicle_control_command.hpp>
20 #include <autoware_auto_vehicle_msgs/msg/vehicle_kinematic_state.hpp>
32 namespace mpc_controller
38 constexpr
static std::chrono::nanoseconds solver_time_step{std::chrono::milliseconds{100LL}};
55 const
Config & get_config() const;
57 void set_config(const
Config & config);
62 const
Trajectory & get_computed_trajectory() const noexcept;
67 void debug_print(std::ostream & out) const;
70 std::
string name() const override;
73 Index get_compute_iterations() const override;
77 bool check_new_trajectory(const
Trajectory & trajectory) const override;
81 Command compute_command_impl(const
State & state) override;
85 MPC_CONTROLLER_LOCAL
void solve();
87 MPC_CONTROLLER_LOCAL
bool update_references(
Index current_idx);
89 MPC_CONTROLLER_LOCAL
void initial_conditions(const
Point & state);
91 MPC_CONTROLLER_LOCAL std::chrono::nanoseconds x0_time_offset(const
State & state,
Index idx);
93 MPC_CONTROLLER_LOCAL
Command interpolated_command(std::chrono::nanoseconds x0_time_offset);
96 MPC_CONTROLLER_LOCAL
bool ensure_reference_consistency(
Index horizon);
98 MPC_CONTROLLER_LOCAL
void apply_config(const
Config & cfg);
100 MPC_CONTROLLER_LOCAL
void apply_parameters(const VehicleConfig & cfg) noexcept;
102 MPC_CONTROLLER_LOCAL
void apply_bounds(const LimitsConfig & cfg) noexcept;
104 MPC_CONTROLLER_LOCAL
void apply_weights(const OptimizationConfig & cfg);
106 MPC_CONTROLLER_LOCAL
void apply_nominal_weights(const StateWeight & cfg,
Index start,
Index end);
108 MPC_CONTROLLER_LOCAL
void apply_terminal_weights(const
Index idx);
113 MPC_CONTROLLER_LOCAL
void zero_nominal_weights(
Index start,
Index end);
115 MPC_CONTROLLER_LOCAL
void zero_terminal_weights() noexcept;
117 MPC_CONTROLLER_LOCAL
void set_terminal_weights(const StateWeight & cfg) noexcept;
119 MPC_CONTROLLER_LOCAL
void set_terminal_reference(const
Point & pt) noexcept;
121 MPC_CONTROLLER_LOCAL
void advance_problem(
Index count);
123 MPC_CONTROLLER_LOCAL
void backfill_reference(
Index count);
126 Trajectory::UniquePtr m_interpolated_trajectory{
nullptr};
128 Index m_last_reference_index;
133 #endif // MPC_CONTROLLER__MPC_CONTROLLER_HPP_