Drake
Drake C++ Documentation
FiniteHorizonLinearQuadraticRegulatorResult Struct Reference

Detailed Description

A structure that contains the basic FiniteHorizonLinearQuadraticRegulator results.

The finite-horizon cost-to-go is given by (x-x0(t))'S(t)(x-x0(t)) + 2*(x-x₀(t))'sₓ(t) + s₀(t) and the optimal controller is given by u-u0(t) = -K(t)*(x-x₀(t)) - k₀(t). Please don't overlook the factor of 2 in front of the sₓ(t) term.

#include <drake/systems/controllers/finite_horizon_linear_quadratic_regulator.h>

Public Attributes

copyable_unique_ptr< trajectories::Trajectory< double > > x0
 
copyable_unique_ptr< trajectories::Trajectory< double > > u0
 
copyable_unique_ptr< trajectories::Trajectory< double > > K
 Note: This K is the K_x term in the derivation notes. More...
 
copyable_unique_ptr< trajectories::Trajectory< double > > S
 
copyable_unique_ptr< trajectories::Trajectory< double > > k0
 
copyable_unique_ptr< trajectories::Trajectory< double > > sx
 
copyable_unique_ptr< trajectories::Trajectory< double > > s0
 

Member Data Documentation

◆ K

Note: This K is the K_x term in the derivation notes.

◆ k0

◆ S

◆ s0

◆ sx

◆ u0

◆ x0


The documentation for this struct was generated from the following file: