Autoware.Auto
motion::control::controller_common::ControllerBase Class Referenceabstract

#include <controller_base.hpp>

Inheritance diagram for motion::control::controller_common::ControllerBase:

Public Member Functions

 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
 
virtual std::string name () const
 Get name of algorithm, for debugging or diagnostic purposes. More...
 
virtual Index get_compute_iterations () const
 Get name of algorithm, for debugging or diagnostic purposes. More...
 
const BehaviorConfigget_base_config () const noexcept
 

Protected Member Functions

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 base class which exposes the basic API and implements the basic behaviors of a controller in the absence of a trajectory, and other basic bookkeeping

Constructor & Destructor Documentation

◆ ControllerBase() [1/3]

motion::control::controller_common::ControllerBase::ControllerBase ( const BehaviorConfig config)
explicit

Constructors.

◆ ControllerBase() [2/3]

motion::control::controller_common::ControllerBase::ControllerBase ( const ControllerBase )
default

◆ ControllerBase() [3/3]

motion::control::controller_common::ControllerBase::ControllerBase ( ControllerBase &&  )
default

◆ ~ControllerBase()

virtual motion::control::controller_common::ControllerBase::~ControllerBase ( )
virtualdefaultnoexcept

Member Function Documentation

◆ check_new_trajectory()

bool motion::control::controller_common::ControllerBase::check_new_trajectory ( const Trajectory &  trajectory) const
protectedvirtual

Given a new trajectory, do some input validation: If the trajectory is fine for the algorithm, return true; otherwise return false.

◆ compute_command()

Command motion::control::controller_common::ControllerBase::compute_command ( const State &  state)

Main API: Given current state (and reference trajectory), compute next command. Updates the current reference point of the trajectory

Exceptions
std::domain_errorIf state is not in the same frame as reference trajectory

◆ compute_command_impl()

virtual Command motion::control::controller_common::ControllerBase::compute_command_impl ( const State &  state)
protectedpure virtual

Actually compute the control command.

◆ compute_stop_command()

Command motion::control::controller_common::ControllerBase::compute_stop_command ( const State &  state) const
noexcept

Computes stopping control command.

◆ get_base_config()

const BehaviorConfig & motion::control::controller_common::ControllerBase::get_base_config ( ) const
noexcept

◆ get_compute_iterations()

Index motion::control::controller_common::ControllerBase::get_compute_iterations ( ) const
virtual

Get name of algorithm, for debugging or diagnostic purposes.

Reimplemented in motion::control::mpc_controller::MpcController.

◆ get_current_state_spatial_index()

Index motion::control::controller_common::ControllerBase::get_current_state_spatial_index ( ) const

Returns the index of the current reference point in the trajectory, i.e. the first point on the trajectory just after the current point spatially. If a point exactly matches, return that index.

Exceptions
std::runtime_errorif an empty trajectory or no trajectory is provided

◆ get_current_state_temporal_index()

Index motion::control::controller_common::ControllerBase::get_current_state_temporal_index ( ) const

Returns the index of the current reference point in the trajectory, i.e. the first point on the trajectory just after the current point in time. If a point exactly matches, return that index.

Exceptions
std::runtime_errorif an empty trajectory or no trajectory is provided

◆ get_reference_trajectory()

const Trajectory & motion::control::controller_common::ControllerBase::get_reference_trajectory ( ) const
noexcept

Getter for reference trajectory.

◆ handle_new_trajectory()

const Trajectory & motion::control::controller_common::ControllerBase::handle_new_trajectory ( const Trajectory &  trajectory)
protectedvirtual

Update internal bookkeeping or the algorithm-specific representation of the trajectory associated with updating to a new trajectory, return preferred form of trajectory

◆ name()

std::string motion::control::controller_common::ControllerBase::name ( ) const
virtual

Get name of algorithm, for debugging or diagnostic purposes.

Reimplemented in motion::control::mpc_controller::MpcController.

◆ operator=() [1/2]

ControllerBase& motion::control::controller_common::ControllerBase::operator= ( const ControllerBase )
default

◆ operator=() [2/2]

ControllerBase& motion::control::controller_common::ControllerBase::operator= ( ControllerBase &&  )
default

◆ predict()

Point motion::control::controller_common::ControllerBase::predict ( const Point point,
std::chrono::nanoseconds  dt 
)
protectednoexcept

Get a predicted state based on given state.

◆ set_base_config()

void motion::control::controller_common::ControllerBase::set_base_config ( const BehaviorConfig config)
protectednoexcept

Config getters and setters.

◆ set_trajectory()

void motion::control::controller_common::ControllerBase::set_trajectory ( const Trajectory &  trajectory)

Setter for reference trajectory, throws if trajectory is inappropriate without mutating state (assuming handle_new_trajectory also does not)


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