|
void | AssignScene (ScenePtr scene_in) override |
|
| CartpoleDynamicsSolver () |
|
StateVector | f (const StateVector &x, const ControlVector &u) override |
| Computes the forward dynamics of the system. More...
|
|
Eigen::MatrixXd | fu (const StateVector &x, const ControlVector &u) override |
| Computes the dynamics derivative w.r.t .the control input u. More...
|
|
Eigen::MatrixXd | fx (const StateVector &x, const ControlVector &u) override |
| Computes the dynamics derivative w.r.t .the state x. More...
|
|
Eigen::Tensor< double, 3 > | fxu (const StateVector &x, const ControlVector &u) override |
|
Eigen::Tensor< double, 3 > | fxx (const StateVector &x, const ControlVector &u) override |
|
| AbstractDynamicsSolver () |
|
virtual void | AssignScene (std::shared_ptr< Scene > scene_in) |
|
void | ClampToStateLimits (Eigen::Ref< Eigen::VectorXd > state_in) |
|
virtual void | ComputeDerivatives (const StateVector &x, const ControlVector &u) |
|
virtual Hessian | ddStateDelta (const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second) |
|
virtual Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > | dStateDelta (const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second) |
|
virtual StateVector | F (const StateVector &x, const ControlVector &u) |
|
ControlDerivative | fu_fd (const StateVector &x, const ControlVector &u) |
|
virtual Eigen::Tensor< T, 3 > | fuu (const StateVector &x, const ControlVector &u) |
|
StateDerivative | fx_fd (const StateVector &x, const ControlVector &u) |
|
const Eigen::MatrixXd & | get_control_limits () |
|
T | get_dt () const |
|
const ControlDerivative & | get_Fu () const |
|
const ControlDerivative & | get_fu () const |
|
const StateDerivative & | get_Fx () const |
|
const StateDerivative & | get_fx () const |
|
const bool & | get_has_second_order_derivatives () const |
|
const bool & | get_has_state_limits () const |
|
Integrator | get_integrator () const |
|
int | get_num_controls () const |
|
int | get_num_positions () const |
|
int | get_num_state () const |
|
int | get_num_state_derivative () const |
|
int | get_num_velocities () const |
|
virtual Eigen::Matrix< T, Eigen::Dynamic, 1 > | GetPosition (Eigen::VectorXdRefConst x_in) |
|
virtual void | InstantiateBase (const Initializer &init) |
|
virtual void | Integrate (const StateVector &x, const StateVector &dx, const double dt, StateVector &xout) |
|
virtual ControlVector | InverseDynamics (const StateVector &state) |
|
void | set_control_limits (Eigen::VectorXdRefConst control_limits_low, Eigen::VectorXdRefConst control_limits_high) |
|
void | set_integrator (Integrator integrator_in) |
|
virtual void | SetDt (double dt_in) |
|
void | SetIntegrator (const std::string &integrator_in) |
|
StateVector | Simulate (const StateVector &x, const ControlVector &u, T t) |
|
void | StateDelta (const StateVector &x_1, const StateVector &x_2, Eigen::VectorXdRef xout) |
|
virtual StateVector | StateDelta (const StateVector &x_1, const StateVector &x_2) |
|
virtual | ~AbstractDynamicsSolver () |
|
std::string | GetObjectName () |
|
void | InstantiateObject (const Initializer &init) |
|
| Object () |
|
virtual std::string | Print (const std::string &prepend) const |
|
virtual std::string | type () const |
|
virtual | ~Object () |
|
| InstantiableBase ()=default |
|
virtual | ~InstantiableBase ()=default |
|
std::vector< Initializer > | GetAllTemplates () const override |
|
Initializer | GetInitializerTemplate () override |
|
const CartpoleDynamicsSolverInitializer & | GetParameters () const |
|
virtual void | Instantiate (const CartpoleDynamicsSolverInitializer &init) |
|
void | InstantiateInternal (const Initializer &init) override |
|
StateVector X ∈ R^4 = [x, theta, x_dot, theta_dot] Refer to http://underactuated.mit.edu/acrobot.html#cart_pole for a derivation of the cartpole dynamics.
Definition at line 43 of file cartpole_dynamics_solver.h.