14 #ifndef MPC_CONTROLLER__CONFIG_HPP_ 15 #define MPC_CONTROLLER__CONFIG_HPP_ 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; \ 32 namespace mpc_controller
64 std::chrono::nanoseconds sample_period_tolerance,
65 std::chrono::nanoseconds control_lookahead_duration,
73 std::chrono::nanoseconds sample_period_tolerance()
const noexcept;
74 std::chrono::nanoseconds control_lookahead_duration()
const noexcept;
75 bool do_interpolate()
const noexcept;
82 std::chrono::nanoseconds m_sample_period_tolerance;
83 std::chrono::nanoseconds m_control_lookahead_duration;
84 bool m_do_interpolate;
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'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's behaviors Depending on pro...
Definition: control/motion_common/include/motion_common/config.hpp:165