Drake
Drake C++ Documentation
drake::systems::controllers Namespace Reference

Classes

struct  DynamicProgrammingOptions
 Consolidates the many possible options to be passed to the dynamic programming algorithms. More...
 
struct  FiniteHorizonLinearQuadraticRegulatorOptions
 A structure to facilitate passing the myriad of optional arguments to the FiniteHorizonLinearQuadraticRegulator algorithms. More...
 
struct  FiniteHorizonLinearQuadraticRegulatorResult
 A structure that contains the basic FiniteHorizonLinearQuadraticRegulator results. More...
 
class  InverseDynamics
 Solves inverse dynamics with no consideration for joint actuator force limits. More...
 
class  InverseDynamicsController
 A state feedback controller that uses a PidController to generate desired accelerations, which are then converted into torques using InverseDynamics. More...
 
class  JointImpedanceController
 Drake does not yet offer a joint impedance controller, which would use feedback to shape the stiffness, damping, and inertia of the closed-loop system. More...
 
class  JointStiffnessController
 Implements a joint-space stiffness controller of the form. More...
 
class  LinearModelPredictiveController
 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...
 
struct  LinearQuadraticRegulatorResult
 
class  PidControlledSystem
 A system that encapsulates a PidController and a controlled System (a.k.a the "plant"). More...
 
class  PidController
 Implements the PID controller. More...
 
class  StateFeedbackControllerInterface
 Interface for state feedback controllers. More...
 

Functions

std::pair< std::unique_ptr< BarycentricMeshSystem< double > >, Eigen::RowVectorXd > FittedValueIteration (Simulator< double > *simulator, const std::function< double(const Context< double > &context)> &cost_function, const math::BarycentricMesh< double >::MeshGrid &state_grid, const math::BarycentricMesh< double >::MeshGrid &input_grid, double time_step, const DynamicProgrammingOptions &options=DynamicProgrammingOptions())
 Implements Fitted Value Iteration on a (triangulated) Barycentric Mesh, which designs a state-feedback policy to minimize the infinite-horizon cost ∑ γⁿ g(x[n],u[n]), where γ is the discount factor in options. More...
 
Eigen::VectorXd LinearProgrammingApproximateDynamicProgramming (Simulator< double > *simulator, const std::function< double(const Context< double > &context)> &cost_function, const std::function< symbolic::Expression(const Eigen::Ref< const Eigen::VectorXd > &state, const VectorX< symbolic::Variable > &parameters)> &linearly_parameterized_cost_to_go_function, int num_parameters, const Eigen::Ref< const Eigen::MatrixXd > &state_samples, const Eigen::Ref< const Eigen::MatrixXd > &input_samples, double time_step, const DynamicProgrammingOptions &options=DynamicProgrammingOptions())
 Implements the Linear Programming approach to approximate dynamic programming. More...
 
FiniteHorizonLinearQuadraticRegulatorResult FiniteHorizonLinearQuadraticRegulator (const System< double > &system, const Context< double > &context, double t0, double tf, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, const FiniteHorizonLinearQuadraticRegulatorOptions &options=FiniteHorizonLinearQuadraticRegulatorOptions())
 Solves the differential Riccati equation to compute the optimal controller and optimal cost-to-go for the finite-horizon linear quadratic regulator: More...
 
std::unique_ptr< System< double > > MakeFiniteHorizonLinearQuadraticRegulator (const System< double > &system, const Context< double > &context, double t0, double tf, const Eigen::Ref< const Eigen::MatrixXd > &Q, const Eigen::Ref< const Eigen::MatrixXd > &R, const FiniteHorizonLinearQuadraticRegulatorOptions &options=FiniteHorizonLinearQuadraticRegulatorOptions())
 Variant of FiniteHorizonLinearQuadraticRegulator that returns a System implementing the regulator (controller) as a System, with a single "plant_state" input for the estimated plant state, and a single "control" output for the regulator control output. More...
 
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(), const Eigen::Ref< const Eigen::MatrixXd > &F=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< 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< 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(), int input_port_index=0)
 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...