Drake

Classes

class  InverseDynamicsController< T >
 A state feedback controller that uses a PidController to generate desired accelerations, which are then converted into torques using InverseDynamics. More...
 
class  InverseDynamicsController< T >
 A state feedback controller that uses a PidController to generate desired accelerations, which are then converted into torques using InverseDynamics. More...
 
class  LinearModelPredictiveController< T >
 Implements a basic Model Predictive Controller that linearizes the system about an equilibrium condition and regulates to the same point by solving an optimal control problem over a finite time horizon. More...
 
class  PidControlledSystem< T >
 A system that encapsulates a PidController and a controlled System (a.k.a the "plant"). More...
 
class  PidController< T >
 Implements the PID controller. More...
 

Functions

LinearQuadraticRegulatorResult LinearQuadraticRegulator (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, const Eigen::Ref< const Eigen::MatrixXd > &N=Eigen::Matrix< double, 0, 0 >::Zero())
 Computes the optimal feedback controller, u=-Kx, and the optimal cost-to-go J = x'Sx for the problem: More...
 
LinearQuadraticRegulatorResult DiscreteTimeLinearQuadraticRegulator (const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R)
 Computes the optimal feedback controller, u=-Kx, and the optimal cost-to-go J = x'Sx for the problem: More...
 
std::unique_ptr< systems::LinearSystem< double > > LinearQuadraticRegulator (const LinearSystem< double > &system, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, const Eigen::Ref< const Eigen::MatrixXd > &N=Eigen::Matrix< double, 0, 0 >::Zero())
 Creates a system that implements the optimal time-invariant linear quadratic regulator (LQR). More...
 
std::unique_ptr< systems::AffineSystem< double > > LinearQuadraticRegulator (const System< double > &system, const Context< double > &context, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, const Eigen::Ref< const Eigen::MatrixXd > &N=Eigen::Matrix< double, 0, 0 >::Zero())
 Linearizes the System around the specified Context, computes the optimal time-invariant linear quadratic regulator (LQR), and returns a System which implements that regulator in the original System's coordinates. More...
 
Eigen::MatrixXd ControllabilityMatrix (const LinearSystem< double > &sys)
 Returns the controllability matrix: R = [B, AB, ..., A^{n-1}B]. More...
 
bool IsControllable (const LinearSystem< double > &sys, optional< double > threshold)
 Returns true iff the controllability matrix is full row rank. More...
 

Detailed Description

Implementations of controllers that operate as Systems in a block diagram.

Algorithms that synthesize controllers are located in Feedback Control Design.

Function Documentation

◆ ControllabilityMatrix()

Eigen::MatrixXd ControllabilityMatrix ( const LinearSystem< double > &  sys)

Returns the controllability matrix: R = [B, AB, ..., A^{n-1}B].

◆ DiscreteTimeLinearQuadraticRegulator()

LinearQuadraticRegulatorResult DiscreteTimeLinearQuadraticRegulator ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::MatrixXd > &  B,
const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::MatrixXd > &  R 
)

Computes the optimal feedback controller, u=-Kx, and the optimal cost-to-go J = x'Sx for the problem:

\[ x[n+1] = Ax[n] + Bu[n] \]

\[ \min_u \sum_0^\infty x'Qx + u'Ru \]

Parameters
AThe state-space dynamics matrix of size num_states x num_states.
BThe state-space input matrix of size num_states x num_inputs.
QA symmetric positive semi-definite cost matrix of size num_states x num_states.
RA symmetric positive definite cost matrix of size num_inputs x num_inputs.
Returns
A structure that contains the optimal feedback gain K and the quadratic cost term S. The optimal feedback control is u = -Kx;
Exceptions
std::runtime_errorif R is not positive definite.

◆ IsControllable()

bool IsControllable ( const LinearSystem< double > &  sys,
optional< double threshold 
)

Returns true iff the controllability matrix is full row rank.

◆ LinearQuadraticRegulator() [1/3]

LinearQuadraticRegulatorResult LinearQuadraticRegulator ( const Eigen::Ref< const Eigen::MatrixXd > &  A,
const Eigen::Ref< const Eigen::MatrixXd > &  B,
const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::MatrixXd > &  R,
const Eigen::Ref< const Eigen::MatrixXd > &  N = Eigen::Matrix< double, 0, 0 >::Zero() 
)

Computes the optimal feedback controller, u=-Kx, and the optimal cost-to-go J = x'Sx for the problem:

\[ \dot{x} = Ax + Bu \]

\[ \min_u \int_0^\infty x'Qx + u'Ru + 2x'Nu dt \]

Parameters
AThe state-space dynamics matrix of size num_states x num_states.
BThe state-space input matrix of size num_states x num_inputs.
QA symmetric positive semi-definite cost matrix of size num_states x num_states.
RA symmetric positive definite cost matrix of size num_inputs x num_inputs.
NA cost matrix of size num_states x num_inputs.
Returns
A structure that contains the optimal feedback gain K and the quadratic cost term S. The optimal feedback control is u = -Kx;
Exceptions
std::runtime_errorif R is not positive definite.

◆ LinearQuadraticRegulator() [2/3]

std::unique_ptr< LinearSystem< double > > LinearQuadraticRegulator ( const LinearSystem< double > &  system,
const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::MatrixXd > &  R,
const Eigen::Ref< const Eigen::MatrixXd > &  N = Eigen::Matrix< double, 0, 0 >::Zero() 
)

Creates a system that implements the optimal time-invariant linear quadratic regulator (LQR).

If system is a continuous-time system, then solves the continuous-time LQR problem:

\[ \min_u \int_0^\infty x^T(t)Qx(t) + u^T(t)Ru(t) dt. \]

If system is a discrete-time system, then solves the discrete-time LQR problem:

\[ \min_u \sum_0^\infty x^T[n]Qx[n] + u^T[n]Ru[n]. \]

Parameters
systemThe System to be controlled.
QA symmetric positive semi-definite cost matrix of size num_states x num_states.
RA symmetric positive definite cost matrix of size num_inputs x num_inputs.
NA cost matrix of size num_states x num_inputs.
Returns
A system implementing the optimal controller in the original system coordinates.
Exceptions
std::runtime_errorif R is not positive definite.

◆ LinearQuadraticRegulator() [3/3]

std::unique_ptr< AffineSystem< double > > LinearQuadraticRegulator ( const System< double > &  system,
const Context< double > &  context,
const Eigen::Ref< const Eigen::MatrixXd > &  Q,
const Eigen::Ref< const Eigen::MatrixXd > &  R,
const Eigen::Ref< const Eigen::MatrixXd > &  N = Eigen::Matrix< double, 0, 0 >::Zero() 
)

Linearizes the System around the specified Context, computes the optimal time-invariant linear quadratic regulator (LQR), and returns a System which implements that regulator in the original System's coordinates.

If system is a continuous-time system, then solves the continuous-time LQR problem:

\[ \min_u \int_0^\infty (x-x_0)^TQ(x-x_0) + (u-u_0)^TR(u-u_0) dt. \]

If system is a discrete-time system, then solves the discrete-time LQR problem:

\[ \min_u \sum_0^\infty (x-x_0)^TQ(x-x_0) + (u-u_0)^TR(u-u_0), \]

where \( x_0 \) is the nominal state and \( u_0 \) is the nominal input. The system is considered discrete if it has a single discrete state vector and a single unique periodic update event declared.

Parameters
systemThe System to be controlled.
contextDefines the desired state and control input to regulate the system to. Note that this state/input must be an equilibrium point of the system. See drake::systems::Linearize for more details.
QA symmetric positive semi-definite cost matrix of size num_states x num_states.
RA symmetric positive definite cost matrix of size num_inputs x num_inputs.
NA cost matrix of size num_states x num_inputs.
Returns
A system implementing the optimal controller in the original system coordinates.
Exceptions
std::runtime_errorif R is not positive definite.