Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_DYNAMICS_SOLVER_H_
31 #define EXOTICA_CORE_DYNAMICS_SOLVER_H_
38 #include <exotica_core/dynamics_solver_initializer.h>
40 #define REGISTER_DYNAMICS_SOLVER_TYPE(TYPE, DERIV) EXOTICA_CORE_REGISTER(exotica::DynamicsSolver, TYPE, DERIV)
54 template <
typename T,
int NX,
int NU>
72 virtual void AssignScene(std::shared_ptr<Scene> scene_in);
75 virtual void SetDt(
double dt_in);
138 assert(x_1.size() == x_2.size());
151 assert(x_1.size() == x_2.size());
166 assert(x_1.size() == x_2.size());
272 #endif // EXOTICA_CORE_DYNAMICS_SOLVER_H_
const ControlDerivative & get_fu() const
Returns derivative fu computed by ComputeDerivatives.
void StateDelta(const StateVector &x_1, const StateVector &x_2, Eigen::VectorXdRef xout)
Definition: dynamics_solver.h:142
int num_state_
Size of state space (num_positions + num_velocities)
Definition: dynamics_solver.h:238
virtual StateDerivative fx(const StateVector &x, const ControlVector &u)
Derivative of the forward dynamics w.r.t. the state.
@ ARG1
Definition: tools.h:126
virtual void Integrate(const StateVector &x, const StateVector &dx, const double dt, StateVector &xout)
Integrates without performing dynamics.
Definition: dynamics_solver.h:55
Definition: uncopyable.h:35
virtual Eigen::Tensor< T, 3 > fxu(const StateVector &x, const ControlVector &u)
Eigen::Matrix< T, NX, 1 > StateVector
Convenience definition for a StateVector containing both position and velocity (dimension NX x 1)
Definition: dynamics_solver.h:58
virtual Eigen::Tensor< T, 3 > fxx(const StateVector &x, const ControlVector &u)
bool has_state_limits_
Whether the solver specifies state limits.
Definition: dynamics_solver.h:244
virtual Hessian ddStateDelta(const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
Definition: dynamics_solver.h:162
virtual StateVector F(const StateVector &x, const ControlVector &u)
State transition function. This internally computes the differential dynamics and applies the chosen ...
int get_num_controls() const
Returns number of controls.
const bool & get_has_second_order_derivatives() const
Returns whether second-order derivatives are available.
Definition: dynamics_solver.h:111
@ SymplecticEuler
Semi-Implicit Euler.
Definition: dynamics_solver.h:49
Integrator
Definition: dynamics_solver.h:46
void InitializeSecondOrderDerivatives()
Hessian ddStateDelta_
Definition: dynamics_solver.h:232
Eigen::Tensor< T, 3 > fxx_default_
Definition: dynamics_solver.h:259
bool second_order_derivatives_initialized_
Whether fxx, fxu and fuu have been initialized to 0.
Definition: dynamics_solver.h:242
Eigen::VectorXd state_limits_upper_
Upper state limits (configuration and velocity)
Definition: dynamics_solver.h:246
virtual Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > dStateDelta(const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second)
Return the difference of the StateDelta operation between two state vectors. The ArgumentPosition arg...
Definition: dynamics_solver.h:149
virtual void ComputeDerivatives(const StateVector &x, const ControlVector &u)
Computes derivatives fx, fu, Fx, Fu [single call for efficiency, derivatives can be retrieved with ge...
int num_positions_
Number of positions in the dynamic system.
Definition: dynamics_solver.h:236
Eigen::VectorXd raw_control_limits_low_
Definition: dynamics_solver.h:230
Eigen::Tensor< T, 3 > fxu_default_
Definition: dynamics_solver.h:259
Eigen::MatrixXd fu_
Internal storage of differential dynamics partial derivative fu computed by ComputeDerivatives.
Definition: dynamics_solver.h:262
ControlDerivative fu_fd(const StateVector &x, const ControlVector &u)
Derivative of the forward dynamics w.r.t. the control [finite differencing].
Eigen::VectorXd raw_control_limits_high_
Definition: dynamics_solver.h:230
Definition: property.h:98
std::shared_ptr< exotica::DynamicsSolver > DynamicsSolverPtr
Definition: dynamics_solver.h:269
Eigen::Matrix< T, NX, NX > StateDerivative
Convenience definition for a StateDerivative.
Definition: dynamics_solver.h:60
bool control_limits_initialized_
Definition: dynamics_solver.h:229
Definition: cartpole_dynamics_solver.h:38
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
Definition: conversions.h:154
void ClampToStateLimits(Eigen::Ref< Eigen::VectorXd > state_in)
Clamps the passed in state to the state limits.
Eigen::MatrixXd dStateDelta_
Definition: dynamics_solver.h:231
int num_state_derivative_
Size of the tangent vector to the state space (2 * num_velocities)
Definition: dynamics_solver.h:239
const Eigen::MatrixXd & get_control_limits()
Returns the control limits vector.
virtual void AssignScene(std::shared_ptr< Scene > scene_in)
Passes the Scene of the PlanningProblem to the DynamicsSolver.
bool has_second_order_derivatives_
Whether this solver provides second order derivatives. If false (default), assumed to be all zeros.
Definition: dynamics_solver.h:241
int get_num_velocities() const
Returns number of velocities.
int get_num_state() const
Returns size of state space (nx)
int get_num_state_derivative() const
Returns size of derivative vector of state space (ndx)
Eigen::VectorXd state_limits_lower_
Lower state limits (configuration and velocity)
Definition: dynamics_solver.h:245
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Definition: conversions.h:54
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
T get_dt() const
Returns integration timestep dt.
T dt_
Internal timestep used for integration. Defaults to 10ms.
Definition: dynamics_solver.h:248
StateVector Simulate(const StateVector &x, const ControlVector &u, T t)
Simulates the dynamic system from starting state x using control u for t seconds.
Eigen::Matrix< T, NX, NU > ControlDerivative
Convenience definition for a ControlDerivative.
Definition: dynamics_solver.h:61
ArgumentPosition
Argument position. Used as parameter to refer to an argument.
Definition: tools.h:123
@ ARG0
Definition: tools.h:125
const ControlDerivative & get_Fu() const
Returns derivative Fu computed by ComputeDerivatives.
virtual ~AbstractDynamicsSolver()
virtual ControlDerivative fu(const StateVector &x, const ControlVector &u)
Derivative of the forward dynamics w.r.t. the control.
Definition: property.h:70
Eigen::MatrixXd fx_
Internal storage of differential dynamics partial derivative fx computed by ComputeDerivatives.
Definition: dynamics_solver.h:261
@ RK4
Runge-Kutta 4.
Definition: dynamics_solver.h:51
Eigen::MatrixXd Fx_
Internal storage of state transition partial derivative Fx computed by ComputeDerivatives.
Definition: dynamics_solver.h:263
virtual StateVector SimulateOneStep(const StateVector &x, const ControlVector &u)
Integrates the dynamic system from state x with controls u applied for one timestep dt using the sele...
virtual ControlVector InverseDynamics(const StateVector &state)
Returns a control vector corresponding to the state vector assuming zero acceleration.
Integrator integrator_
Chosen integrator. Defaults to Euler (RK1).
Definition: dynamics_solver.h:249
void set_control_limits(Eigen::VectorXdRefConst control_limits_low, Eigen::VectorXdRefConst control_limits_high)
Sets the control limits.
Eigen::Matrix< T, NU, 1 > ControlVector
Convenience definition for a ControlVector (dimension NU x 1)
Definition: dynamics_solver.h:59
virtual void SetDt(double dt_in)
Sets the timestep dt to be used for integration.
Eigen::MatrixXd control_limits_
ControlLimits. Default is empty vector.
Definition: dynamics_solver.h:252
@ RK1
Forward Euler (explicit)
Definition: dynamics_solver.h:48
const StateDerivative & get_Fx() const
Returns derivative Fx computed by ComputeDerivatives.
Eigen::Tensor< T, 3 > fuu_default_
Definition: dynamics_solver.h:259
void SetIntegrator(const std::string &integrator_in)
Sets integrator type based on request string.
StateDerivative fx_fd(const StateVector &x, const ControlVector &u)
Derivative of the forward dynamics w.r.t. the state [finite differencing].
int get_num_positions() const
Returns number of positions.
virtual Eigen::Matrix< T, Eigen::Dynamic, 1 > GetPosition(Eigen::VectorXdRefConst x_in)
Returns the position-part of the state vector to update the scene. For types including SE(3) and rota...
virtual StateVector f(const StateVector &x, const ControlVector &u)=0
Forward dynamics. This computes the differential dynamics.
Eigen::MatrixXd Fu_
Internal storage of state transition partial derivative Fu computed by ComputeDerivatives.
Definition: dynamics_solver.h:264
Integrator get_integrator() const
Returns used integration scheme.
const bool & get_has_state_limits() const
Returns whether state limits are available.
Definition: dynamics_solver.h:214
virtual Eigen::Tensor< T, 3 > fuu(const StateVector &x, const ControlVector &u)
int num_controls_
Number of controls in the dynamic system.
Definition: dynamics_solver.h:235
virtual void InstantiateBase(const Initializer &init)
Instantiates the base properties of the DynamicsSolver.
virtual StateVector StateDelta(const StateVector &x_1, const StateVector &x_2)
Return the difference of two state vectors. Used when e.g. angle differences need to be wrapped from ...
Definition: dynamics_solver.h:136
const StateDerivative & get_fx() const
Returns derivative fx computed by ComputeDerivatives.
AbstractDynamicsSolver< double, Eigen::Dynamic, Eigen::Dynamic > DynamicsSolver
Definition: dynamics_solver.h:267
void set_integrator(Integrator integrator_in)
Sets integrator type.
int num_velocities_
Number of velocities in the dynamic system.
Definition: dynamics_solver.h:237
@ RK2
Explicit trapezoid rule.
Definition: dynamics_solver.h:50