Exotica
|
#include <dynamics_solver.h>
Public Types | |
typedef Eigen::Matrix< T, NX, 1 > | StateVector |
Convenience definition for a StateVector containing both position and velocity (dimension NX x 1) More... | |
typedef Eigen::Matrix< T, NU, 1 > | ControlVector |
Convenience definition for a ControlVector (dimension NU x 1) More... | |
typedef Eigen::Matrix< T, NX, NX > | StateDerivative |
Convenience definition for a StateDerivative. More... | |
typedef Eigen::Matrix< T, NX, NU > | ControlDerivative |
Convenience definition for a ControlDerivative. More... | |
Public Member Functions | |
AbstractDynamicsSolver () | |
virtual | ~AbstractDynamicsSolver () |
virtual void | InstantiateBase (const Initializer &init) |
Instantiates the base properties of the DynamicsSolver. More... | |
virtual void | AssignScene (std::shared_ptr< Scene > scene_in) |
Passes the Scene of the PlanningProblem to the DynamicsSolver. More... | |
virtual void | SetDt (double dt_in) |
Sets the timestep dt to be used for integration. More... | |
virtual StateVector | f (const StateVector &x, const ControlVector &u)=0 |
Forward dynamics. This computes the differential dynamics. More... | |
virtual StateVector | F (const StateVector &x, const ControlVector &u) |
State transition function. This internally computes the differential dynamics and applies the chosen integration scheme. More... | |
virtual void | ComputeDerivatives (const StateVector &x, const ControlVector &u) |
Computes derivatives fx, fu, Fx, Fu [single call for efficiency, derivatives can be retrieved with get_fx, get_fu, get_Fx, get_Fu]. More... | |
const StateDerivative & | get_Fx () const |
Returns derivative Fx computed by ComputeDerivatives. More... | |
const ControlDerivative & | get_Fu () const |
Returns derivative Fu computed by ComputeDerivatives. More... | |
const StateDerivative & | get_fx () const |
Returns derivative fx computed by ComputeDerivatives. More... | |
const ControlDerivative & | get_fu () const |
Returns derivative fu computed by ComputeDerivatives. More... | |
virtual StateDerivative | fx (const StateVector &x, const ControlVector &u) |
Derivative of the forward dynamics w.r.t. the state. More... | |
virtual ControlDerivative | fu (const StateVector &x, const ControlVector &u) |
Derivative of the forward dynamics w.r.t. the control. More... | |
StateDerivative | fx_fd (const StateVector &x, const ControlVector &u) |
Derivative of the forward dynamics w.r.t. the state [finite differencing]. More... | |
ControlDerivative | fu_fd (const StateVector &x, const ControlVector &u) |
Derivative of the forward dynamics w.r.t. the control [finite differencing]. More... | |
const bool & | get_has_second_order_derivatives () const |
Returns whether second-order derivatives are available. More... | |
virtual Eigen::Tensor< T, 3 > | fxx (const StateVector &x, const ControlVector &u) |
virtual Eigen::Tensor< T, 3 > | fuu (const StateVector &x, const ControlVector &u) |
virtual Eigen::Tensor< T, 3 > | fxu (const StateVector &x, const ControlVector &u) |
StateVector | Simulate (const StateVector &x, const ControlVector &u, T t) |
Simulates the dynamic system from starting state x using control u for t seconds. More... | |
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 [-pi; pi] Returns x_1-x_2. More... | |
void | StateDelta (const StateVector &x_1, const StateVector &x_2, Eigen::VectorXdRef xout) |
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 argument can be used to select whether to take derivative w.r.t. x_1 or x_2. More... | |
virtual Hessian | ddStateDelta (const StateVector &x_1, const StateVector &x_2, const ArgumentPosition first_or_second) |
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 rotation, convert to the appropriate representation here by overriding this method. More... | |
int | get_num_controls () const |
Returns number of controls. More... | |
int | get_num_positions () const |
Returns number of positions. More... | |
int | get_num_velocities () const |
Returns number of velocities. More... | |
int | get_num_state () const |
Returns size of state space (nx) More... | |
int | get_num_state_derivative () const |
Returns size of derivative vector of state space (ndx) More... | |
T | get_dt () const |
Returns integration timestep dt. More... | |
Integrator | get_integrator () const |
Returns used integration scheme. More... | |
void | set_integrator (Integrator integrator_in) |
Sets integrator type. More... | |
void | SetIntegrator (const std::string &integrator_in) |
Sets integrator type based on request string. More... | |
const Eigen::MatrixXd & | get_control_limits () |
Returns the control limits vector. More... | |
void | set_control_limits (Eigen::VectorXdRefConst control_limits_low, Eigen::VectorXdRefConst control_limits_high) |
Sets the control limits. More... | |
const bool & | get_has_state_limits () const |
Returns whether state limits are available. More... | |
void | ClampToStateLimits (Eigen::Ref< Eigen::VectorXd > state_in) |
Clamps the passed in state to the state limits. More... | |
virtual ControlVector | InverseDynamics (const StateVector &state) |
Returns a control vector corresponding to the state vector assuming zero acceleration. More... | |
virtual void | Integrate (const StateVector &x, const StateVector &dx, const double dt, StateVector &xout) |
Integrates without performing dynamics. More... | |
Public Member Functions inherited from exotica::Object | |
Object () | |
virtual | ~Object () |
virtual std::string | type () const |
Type Information wrapper: must be virtual so that it is polymorphic... More... | |
std::string | GetObjectName () |
void | InstantiateObject (const Initializer &init) |
virtual std::string | Print (const std::string &prepend) const |
Public Member Functions inherited from exotica::InstantiableBase | |
InstantiableBase ()=default | |
virtual | ~InstantiableBase ()=default |
virtual Initializer | GetInitializerTemplate ()=0 |
virtual void | InstantiateInternal (const Initializer &init)=0 |
virtual std::vector< Initializer > | GetAllTemplates () const =0 |
Protected Member Functions | |
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 selected integrator. More... | |
void | InitializeSecondOrderDerivatives () |
Protected Attributes | |
int | num_controls_ = -1 |
Number of controls in the dynamic system. More... | |
int | num_positions_ = -1 |
Number of positions in the dynamic system. More... | |
int | num_velocities_ = -1 |
Number of velocities in the dynamic system. More... | |
int | num_state_ = -1 |
Size of state space (num_positions + num_velocities) More... | |
int | num_state_derivative_ = -1 |
Size of the tangent vector to the state space (2 * num_velocities) More... | |
bool | has_second_order_derivatives_ = false |
Whether this solver provides second order derivatives. If false (default), assumed to be all zeros. More... | |
bool | second_order_derivatives_initialized_ = false |
Whether fxx, fxu and fuu have been initialized to 0. More... | |
bool | has_state_limits_ = false |
Whether the solver specifies state limits. More... | |
Eigen::VectorXd | state_limits_lower_ |
Lower state limits (configuration and velocity) More... | |
Eigen::VectorXd | state_limits_upper_ |
Upper state limits (configuration and velocity) More... | |
T | dt_ = 0.01 |
Internal timestep used for integration. Defaults to 10ms. More... | |
Integrator | integrator_ = Integrator::RK1 |
Chosen integrator. Defaults to Euler (RK1). More... | |
Eigen::MatrixXd | control_limits_ |
ControlLimits. Default is empty vector. More... | |
Eigen::Tensor< T, 3 > | fxx_default_ |
Eigen::Tensor< T, 3 > | fuu_default_ |
Eigen::Tensor< T, 3 > | fxu_default_ |
Eigen::MatrixXd | fx_ |
Internal storage of differential dynamics partial derivative fx computed by ComputeDerivatives. More... | |
Eigen::MatrixXd | fu_ |
Internal storage of differential dynamics partial derivative fu computed by ComputeDerivatives. More... | |
Eigen::MatrixXd | Fx_ |
Internal storage of state transition partial derivative Fx computed by ComputeDerivatives. More... | |
Eigen::MatrixXd | Fu_ |
Internal storage of state transition partial derivative Fu computed by ComputeDerivatives. More... | |
Private Attributes | |
bool | control_limits_initialized_ = false |
Eigen::VectorXd | raw_control_limits_low_ |
Eigen::VectorXd | raw_control_limits_high_ |
Eigen::MatrixXd | dStateDelta_ |
Hessian | ddStateDelta_ |
Additional Inherited Members | |
Public Attributes inherited from exotica::Object | |
std::string | ns_ |
std::string | object_name_ |
bool | debug_ |
Private Member Functions inherited from exotica::Uncopyable | |
Uncopyable ()=default | |
~Uncopyable ()=default | |
typedef Eigen::Matrix<T, NX, NU> exotica::AbstractDynamicsSolver< T, NX, NU >::ControlDerivative |
Convenience definition for a ControlDerivative.
typedef Eigen::Matrix<T, NU, 1> exotica::AbstractDynamicsSolver< T, NX, NU >::ControlVector |
Convenience definition for a ControlVector (dimension NU x 1)
typedef Eigen::Matrix<T, NX, NX> exotica::AbstractDynamicsSolver< T, NX, NU >::StateDerivative |
Convenience definition for a StateDerivative.
typedef Eigen::Matrix<T, NX, 1> exotica::AbstractDynamicsSolver< T, NX, NU >::StateVector |
Convenience definition for a StateVector containing both position and velocity (dimension NX x 1)
exotica::AbstractDynamicsSolver< T, NX, NU >::AbstractDynamicsSolver | ( | ) |
|
virtual |
|
virtual |
Passes the Scene of the PlanningProblem to the DynamicsSolver.
Called immediately after creation of the DynamicsSolver plug-in using a pointer to the Scene of the PlanningProblem. This can be used to extract required information from the Scene, e.g., URDF, dimensionality, etc.
void exotica::AbstractDynamicsSolver< T, NX, NU >::ClampToStateLimits | ( | Eigen::Ref< Eigen::VectorXd > | state_in | ) |
Clamps the passed in state to the state limits.
|
virtual |
Computes derivatives fx, fu, Fx, Fu [single call for efficiency, derivatives can be retrieved with get_fx, get_fu, get_Fx, get_Fu].
Reimplemented in exotica::PinocchioDynamicsSolver, exotica::PinocchioDynamicsSolverWithGravityCompensation, and exotica::DoubleIntegratorDynamicsSolver.
|
inlinevirtual |
|
inlinevirtual |
Return the difference of the StateDelta operation between two state vectors. The ArgumentPosition argument can be used to select whether to take derivative w.r.t. x_1 or x_2.
Reimplemented in exotica::PinocchioDynamicsSolver, and exotica::PinocchioDynamicsSolverWithGravityCompensation.
|
virtual |
State transition function. This internally computes the differential dynamics and applies the chosen integration scheme.
|
pure virtual |
Forward dynamics. This computes the differential dynamics.
Implemented in exotica::PinocchioDynamicsSolver, exotica::PinocchioDynamicsSolverWithGravityCompensation, exotica::QuadrotorDynamicsSolver, exotica::CartpoleDynamicsSolver, exotica::PendulumDynamicsSolver, and exotica::DoubleIntegratorDynamicsSolver.
|
virtual |
Derivative of the forward dynamics w.r.t. the control.
Reimplemented in exotica::CartpoleDynamicsSolver, exotica::PendulumDynamicsSolver, exotica::PinocchioDynamicsSolver, exotica::PinocchioDynamicsSolverWithGravityCompensation, exotica::QuadrotorDynamicsSolver, and exotica::DoubleIntegratorDynamicsSolver.
ControlDerivative exotica::AbstractDynamicsSolver< T, NX, NU >::fu_fd | ( | const StateVector & | x, |
const ControlVector & | u | ||
) |
Derivative of the forward dynamics w.r.t. the control [finite differencing].
|
virtual |
|
virtual |
Derivative of the forward dynamics w.r.t. the state.
Reimplemented in exotica::PinocchioDynamicsSolver, exotica::PinocchioDynamicsSolverWithGravityCompensation, exotica::CartpoleDynamicsSolver, exotica::PendulumDynamicsSolver, exotica::QuadrotorDynamicsSolver, and exotica::DoubleIntegratorDynamicsSolver.
StateDerivative exotica::AbstractDynamicsSolver< T, NX, NU >::fx_fd | ( | const StateVector & | x, |
const ControlVector & | u | ||
) |
Derivative of the forward dynamics w.r.t. the state [finite differencing].
|
virtual |
Reimplemented in exotica::CartpoleDynamicsSolver.
|
virtual |
Reimplemented in exotica::CartpoleDynamicsSolver.
const Eigen::MatrixXd& exotica::AbstractDynamicsSolver< T, NX, NU >::get_control_limits | ( | ) |
Returns the control limits vector.
T exotica::AbstractDynamicsSolver< T, NX, NU >::get_dt | ( | ) | const |
Returns integration timestep dt.
const ControlDerivative& exotica::AbstractDynamicsSolver< T, NX, NU >::get_Fu | ( | ) | const |
Returns derivative Fu computed by ComputeDerivatives.
const ControlDerivative& exotica::AbstractDynamicsSolver< T, NX, NU >::get_fu | ( | ) | const |
Returns derivative fu computed by ComputeDerivatives.
const StateDerivative& exotica::AbstractDynamicsSolver< T, NX, NU >::get_Fx | ( | ) | const |
Returns derivative Fx computed by ComputeDerivatives.
const StateDerivative& exotica::AbstractDynamicsSolver< T, NX, NU >::get_fx | ( | ) | const |
Returns derivative fx computed by ComputeDerivatives.
|
inline |
Returns whether second-order derivatives are available.
|
inline |
Returns whether state limits are available.
Integrator exotica::AbstractDynamicsSolver< T, NX, NU >::get_integrator | ( | ) | const |
Returns used integration scheme.
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_controls | ( | ) | const |
Returns number of controls.
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_positions | ( | ) | const |
Returns number of positions.
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_state | ( | ) | const |
Returns size of state space (nx)
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_state_derivative | ( | ) | const |
Returns size of derivative vector of state space (ndx)
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_velocities | ( | ) | const |
Returns number of velocities.
|
virtual |
Returns the position-part of the state vector to update the scene. For types including SE(3) and rotation, convert to the appropriate representation here by overriding this method.
|
protected |
|
virtual |
Instantiates the base properties of the DynamicsSolver.
Reimplemented from exotica::InstantiableBase.
|
virtual |
Integrates without performing dynamics.
Reimplemented in exotica::PinocchioDynamicsSolver, and exotica::PinocchioDynamicsSolverWithGravityCompensation.
|
virtual |
Returns a control vector corresponding to the state vector assuming zero acceleration.
Reimplemented in exotica::PinocchioDynamicsSolver.
void exotica::AbstractDynamicsSolver< T, NX, NU >::set_control_limits | ( | Eigen::VectorXdRefConst | control_limits_low, |
Eigen::VectorXdRefConst | control_limits_high | ||
) |
Sets the control limits.
void exotica::AbstractDynamicsSolver< T, NX, NU >::set_integrator | ( | Integrator | integrator_in | ) |
Sets integrator type.
|
virtual |
Sets the timestep dt to be used for integration.
void exotica::AbstractDynamicsSolver< T, NX, NU >::SetIntegrator | ( | const std::string & | integrator_in | ) |
Sets integrator type based on request string.
StateVector exotica::AbstractDynamicsSolver< T, NX, NU >::Simulate | ( | const StateVector & | x, |
const ControlVector & | u, | ||
T | t | ||
) |
Simulates the dynamic system from starting state x using control u for t seconds.
Simulates the system and steps the simulation by timesteps dt for a total time of t using the specified integration scheme starting from state x and with controls u.
|
protectedvirtual |
Integrates the dynamic system from state x with controls u applied for one timestep dt using the selected integrator.
|
inlinevirtual |
Return the difference of two state vectors. Used when e.g. angle differences need to be wrapped from [-pi; pi] Returns x_1-x_2.
Reimplemented in exotica::PinocchioDynamicsSolver, and exotica::PinocchioDynamicsSolverWithGravityCompensation.
|
inline |
|
protected |
ControlLimits. Default is empty vector.
|
private |
|
private |
|
private |
|
protected |
Internal timestep used for integration. Defaults to 10ms.
|
protected |
Internal storage of differential dynamics partial derivative fu computed by ComputeDerivatives.
|
protected |
Internal storage of state transition partial derivative Fu computed by ComputeDerivatives.
|
protected |
|
protected |
Internal storage of differential dynamics partial derivative fx computed by ComputeDerivatives.
|
protected |
Internal storage of state transition partial derivative Fx computed by ComputeDerivatives.
|
protected |
|
protected |
|
protected |
Whether this solver provides second order derivatives. If false (default), assumed to be all zeros.
|
protected |
Whether the solver specifies state limits.
|
protected |
Chosen integrator. Defaults to Euler (RK1).
|
protected |
Number of controls in the dynamic system.
|
protected |
Number of positions in the dynamic system.
|
protected |
Size of state space (num_positions + num_velocities)
|
protected |
Size of the tangent vector to the state space (2 * num_velocities)
|
protected |
Number of velocities in the dynamic system.
|
private |
|
private |
|
protected |
Whether fxx, fxu and fuu have been initialized to 0.
|
protected |
Lower state limits (configuration and velocity)
|
protected |
Upper state limits (configuration and velocity)