|
Autoware.Auto
|
|
#include <controller_base.hpp>

Public Member Functions | |
| ControllerBase (const BehaviorConfig &config) | |
| Constructors. More... | |
| ControllerBase (const ControllerBase &)=default | |
| ControllerBase (ControllerBase &&)=default | |
| ControllerBase & | operator= (const ControllerBase &)=default |
| ControllerBase & | operator= (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 BehaviorConfig & | get_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... | |
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
|
explicit |
Constructors.
|
default |
|
default |
|
virtualdefaultnoexcept |
|
protectedvirtual |
Given a new trajectory, do some input validation: If the trajectory is fine for the algorithm, return true; otherwise return false.
| 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
| std::domain_error | If state is not in the same frame as reference trajectory |
|
protectedpure virtual |
Actually compute the control command.
|
noexcept |
Computes stopping control command.
|
noexcept |
|
virtual |
Get name of algorithm, for debugging or diagnostic purposes.
Reimplemented in motion::control::mpc_controller::MpcController.
| 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.
| std::runtime_error | if an empty tajectory or no trajectory is provided |
| 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.
| std::runtime_error | if an empty tajectory or no trajectory is provided |
|
noexcept |
Getter for reference 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
|
virtual |
Get name of algorithm, for debugging or diagnostic purposes.
Reimplemented in motion::control::mpc_controller::MpcController.
|
default |
|
default |
|
protectednoexcept |
Get a predicted state based on given state.
|
protectednoexcept |
Config getters and setters.
| 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)