Autoware.Auto
motion::control::mpc_controller::MpcController Class Reference

A wrapper around an autogenerated mpc solver for vehicle dynamics control. More...

#include <mpc_controller.hpp>

Inheritance diagram for motion::control::mpc_controller::MpcController:
Collaboration diagram for motion::control::mpc_controller::MpcController:

Public Types

using Command = autoware_auto_vehicle_msgs::msg::VehicleControlCommand
 
using State = autoware_auto_vehicle_msgs::msg::VehicleKinematicState
 
using Trajectory = autoware_auto_planning_msgs::msg::Trajectory
 

Public Member Functions

 MpcController (const MpcController &)=delete
 
 MpcController (MpcController &&) noexcept=delete
 
MpcControlleroperator= (const MpcController &)=delete
 
MpcControlleroperator= (MpcController &&) noexcept=delete
 
 MpcController (const Config &config)
 Constructor. More...
 
 ~MpcController () override=default
 
const Configget_config () const
 Getter for config class. More...
 
void set_config (const Config &config)
 Setter for config class. More...
 
const Trajectoryget_computed_trajectory () const noexcept
 
ControlDerivatives get_computed_control_derivatives () const noexcept
 Get derivatives computed from the control problem. More...
 
void debug_print (std::ostream &out) const
 Debug printing. More...
 
std::string name () const override
 Get name of algorithm, for debugging or diagnostic purposes. More...
 
Index get_compute_iterations () const override
 Get name of algorithm, for debugging or diagnostic purposes. More...
 
- Public Member Functions inherited from motion::control::controller_common::ControllerBase
 ControllerBase (const BehaviorConfig &config)
 Constructors. More...
 
 ControllerBase (const ControllerBase &)=default
 
 ControllerBase (ControllerBase &&)=default
 
ControllerBaseoperator= (const ControllerBase &)=default
 
ControllerBaseoperator= (ControllerBase &&)=default
 
virtual ~ControllerBase () noexcept=default
 
void set_trajectory (const Trajectory &trajectory)
 
const Trajectory & get_reference_trajectory () const noexcept
 Getter for reference trajectory. More...
 
Command compute_command (const State &state)
 
Command compute_stop_command (const State &state) const noexcept
 Computes stopping control command. More...
 
Index get_current_state_spatial_index () const
 
Index get_current_state_temporal_index () const
 
const BehaviorConfigget_base_config () const noexcept
 

Static Public Attributes

constexpr static std::chrono::nanoseconds solver_time_step {std::chrono::milliseconds{100LL}}
 

Protected Member Functions

bool check_new_trajectory (const Trajectory &trajectory) const override
 Checks trajectory. More...
 
const Trajectoryhandle_new_trajectory (const Trajectory &trajectory) override
 Sets reference trajectory. More...
 
Command compute_command_impl (const State &state) override
 Actually compute the control command. More...
 
- Protected Member Functions inherited from motion::control::controller_common::ControllerBase
virtual bool check_new_trajectory (const Trajectory &trajectory) const
 
virtual const Trajectory & handle_new_trajectory (const Trajectory &trajectory)
 
virtual Command compute_command_impl (const State &state)=0
 Actually compute the control command. More...
 
Point predict (const Point &point, std::chrono::nanoseconds dt) noexcept
 Get a predicted state based on given state. More...
 
void set_base_config (const BehaviorConfig &config) noexcept
 Config getters and setters. More...
 

Detailed Description

A wrapper around an autogenerated mpc solver for vehicle dynamics control.

Member Typedef Documentation

◆ Command

using motion::control::mpc_controller::MpcController::Command = autoware_auto_vehicle_msgs::msg::VehicleControlCommand

◆ State

using motion::control::mpc_controller::MpcController::State = autoware_auto_vehicle_msgs::msg::VehicleKinematicState

◆ Trajectory

using motion::control::mpc_controller::MpcController::Trajectory = autoware_auto_planning_msgs::msg::Trajectory

Constructor & Destructor Documentation

◆ MpcController() [1/3]

motion::control::mpc_controller::MpcController::MpcController ( const MpcController )
delete

◆ MpcController() [2/3]

motion::control::mpc_controller::MpcController::MpcController ( MpcController &&  )
deletenoexcept

◆ MpcController() [3/3]

motion::control::mpc_controller::MpcController::MpcController ( const Config config)
explicit

Constructor.

◆ ~MpcController()

motion::control::mpc_controller::MpcController::~MpcController ( )
overridedefault

Member Function Documentation

◆ check_new_trajectory()

bool motion::control::mpc_controller::MpcController::check_new_trajectory ( const Trajectory trajectory) const
overrideprotected

Checks trajectory.

◆ compute_command_impl()

Command motion::control::mpc_controller::MpcController::compute_command_impl ( const State state)
overrideprotected

Actually compute the control command.

◆ debug_print()

void motion::control::mpc_controller::MpcController::debug_print ( std::ostream &  out) const

Debug printing.

◆ get_compute_iterations()

Index motion::control::mpc_controller::MpcController::get_compute_iterations ( ) const
overridevirtual

Get name of algorithm, for debugging or diagnostic purposes.

Reimplemented from motion::control::controller_common::ControllerBase.

◆ get_computed_control_derivatives()

ControlDerivatives motion::control::mpc_controller::MpcController::get_computed_control_derivatives ( ) const
noexcept

Get derivatives computed from the control problem.

◆ get_computed_trajectory()

const MpcController::Trajectory & motion::control::mpc_controller::MpcController::get_computed_trajectory ( ) const
noexcept

Get trajectory plan computed as a result of solving the optimization problem. This method triggers the rather expensive copy from the solved vector to the trajectory representation

◆ get_config()

const Config & motion::control::mpc_controller::MpcController::get_config ( ) const

Getter for config class.

◆ handle_new_trajectory()

const Trajectory & motion::control::mpc_controller::MpcController::handle_new_trajectory ( const Trajectory trajectory)
overrideprotected

Sets reference trajectory.

◆ name()

std::string motion::control::mpc_controller::MpcController::name ( ) const
overridevirtual

Get name of algorithm, for debugging or diagnostic purposes.

Reimplemented from motion::control::controller_common::ControllerBase.

◆ operator=() [1/2]

MpcController& motion::control::mpc_controller::MpcController::operator= ( const MpcController )
delete

◆ operator=() [2/2]

MpcController& motion::control::mpc_controller::MpcController::operator= ( MpcController &&  )
deletenoexcept

◆ set_config()

void motion::control::mpc_controller::MpcController::set_config ( const Config config)

Setter for config class.

Member Data Documentation

◆ solver_time_step

constexpr std::chrono::nanoseconds motion::control::mpc_controller::MpcController::solver_time_step {std::chrono::milliseconds{100LL}}
staticconstexpr

The documentation for this class was generated from the following files: