#include <pendulum_dynamics_solver.h>

Public Member Functions | |
| void | AssignScene (ScenePtr scene_in) override |
| 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... | |
| PendulumDynamicsSolver () | |
Public Member Functions inherited from exotica::AbstractDynamicsSolver< class, NX, NU > | |
| 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) |
| virtual Eigen::Tensor< T, 3 > | fxu (const StateVector &x, const ControlVector &u) |
| virtual Eigen::Tensor< T, 3 > | fxx (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 () |
Public Member Functions inherited from exotica::Object | |
| 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 () |
Public Member Functions inherited from exotica::InstantiableBase | |
| InstantiableBase ()=default | |
| virtual | ~InstantiableBase ()=default |
Public Member Functions inherited from exotica::Instantiable< PendulumDynamicsSolverInitializer > | |
| std::vector< Initializer > | GetAllTemplates () const override |
| Initializer | GetInitializerTemplate () override |
| const PendulumDynamicsSolverInitializer & | GetParameters () const |
| virtual void | Instantiate (const PendulumDynamicsSolverInitializer &init) |
| void | InstantiateInternal (const Initializer &init) override |
Private Attributes | |
| double | b_ = 0.0 |
| !< Length of the arm More... | |
| double | g_ = 9.81 |
| double | l_ = 1.0 |
| !< Mass at the end of the pendulum More... | |
| double | m_ = 1.0 |
| !< Gravity (m/s^2) More... | |
Additional Inherited Members | |
Public Types inherited from exotica::AbstractDynamicsSolver< class, NX, NU > | |
| typedef Eigen::Matrix< T, NX, NU > | ControlDerivative |
| typedef Eigen::Matrix< T, NU, 1 > | ControlVector |
| typedef Eigen::Matrix< T, NX, NX > | StateDerivative |
| typedef Eigen::Matrix< T, NX, 1 > | StateVector |
Public Attributes inherited from exotica::Object | |
| bool | debug_ |
| std::string | ns_ |
| std::string | object_name_ |
Protected Member Functions inherited from exotica::AbstractDynamicsSolver< class, NX, NU > | |
| void | InitializeSecondOrderDerivatives () |
| virtual StateVector | SimulateOneStep (const StateVector &x, const ControlVector &u) |
Protected Attributes inherited from exotica::AbstractDynamicsSolver< class, NX, NU > | |
| Eigen::MatrixXd | control_limits_ |
| T | dt_ |
| Eigen::MatrixXd | Fu_ |
| Eigen::MatrixXd | fu_ |
| Eigen::Tensor< T, 3 > | fuu_default_ |
| Eigen::MatrixXd | fx_ |
| Eigen::MatrixXd | Fx_ |
| Eigen::Tensor< T, 3 > | fxu_default_ |
| Eigen::Tensor< T, 3 > | fxx_default_ |
| bool | has_second_order_derivatives_ |
| bool | has_state_limits_ |
| Integrator | integrator_ |
| int | num_controls_ |
| int | num_positions_ |
| int | num_state_ |
| int | num_state_derivative_ |
| int | num_velocities_ |
| bool | second_order_derivatives_initialized_ |
| Eigen::VectorXd | state_limits_lower_ |
| Eigen::VectorXd | state_limits_upper_ |
Protected Attributes inherited from exotica::Instantiable< PendulumDynamicsSolverInitializer > | |
| PendulumDynamicsSolverInitializer | parameters_ |
Refer to http://underactuated.mit.edu/underactuated.html?chapter=pend for a derivation of the pendulum dynamics.
Definition at line 42 of file pendulum_dynamics_solver.h.
| exotica::PendulumDynamicsSolver::PendulumDynamicsSolver | ( | ) |
Definition at line 36 of file pendulum_dynamics_solver.cpp.
|
override |
Definition at line 43 of file pendulum_dynamics_solver.cpp.
|
overridevirtual |
Computes the forward dynamics of the system.
| x | The state vector. |
| u | The control input. |
Implements exotica::AbstractDynamicsSolver< class, NX, NU >.
Definition at line 57 of file pendulum_dynamics_solver.cpp.
|
overridevirtual |
Computes the dynamics derivative w.r.t .the control input u.
| x | The state vector. |
| u | The control input |
Reimplemented from exotica::AbstractDynamicsSolver< class, NX, NU >.
Definition at line 82 of file pendulum_dynamics_solver.cpp.
|
overridevirtual |
Computes the dynamics derivative w.r.t .the state x.
| x | The state vector. |
| u | The control input. |
Reimplemented from exotica::AbstractDynamicsSolver< class, NX, NU >.
Definition at line 70 of file pendulum_dynamics_solver.cpp.
|
private |
!< Length of the arm
Definition at line 69 of file pendulum_dynamics_solver.h.
|
private |
Definition at line 66 of file pendulum_dynamics_solver.h.
|
private |
!< Mass at the end of the pendulum
Definition at line 68 of file pendulum_dynamics_solver.h.
|
private |
!< Gravity (m/s^2)
Definition at line 67 of file pendulum_dynamics_solver.h.