Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
exotica::AbstractDynamicsSolver< T, NX, NU > Class Template Referenceabstract

#include <dynamics_solver.h>

Inheritance diagram for exotica::AbstractDynamicsSolver< T, NX, NU >:
Inheritance graph
[legend]

Public Types

typedef Eigen::Matrix< T, NX, NU > ControlDerivative
 Convenience definition for a ControlDerivative. 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, 1 > StateVector
 Convenience definition for a StateVector containing both position and velocity (dimension NX x 1) More...
 

Public Member Functions

 AbstractDynamicsSolver ()
 
virtual void AssignScene (std::shared_ptr< Scene > scene_in)
 Passes the Scene of the PlanningProblem to the DynamicsSolver. More...
 
void ClampToStateLimits (Eigen::Ref< Eigen::VectorXd > state_in)
 Clamps the passed in state to the state limits. 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...
 
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)
 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 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 ControlDerivative fu (const StateVector &x, const ControlVector &u)
 Derivative of the forward dynamics w.r.t. the control. More...
 
ControlDerivative fu_fd (const StateVector &x, const ControlVector &u)
 Derivative of the forward dynamics w.r.t. the control [finite differencing]. More...
 
virtual Eigen::Tensor< T, 3 > fuu (const StateVector &x, const ControlVector &u)
 
virtual StateDerivative fx (const StateVector &x, const ControlVector &u)
 Derivative of the forward dynamics w.r.t. the state. More...
 
StateDerivative fx_fd (const StateVector &x, const ControlVector &u)
 Derivative of the forward dynamics w.r.t. the state [finite differencing]. More...
 
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 ()
 Returns the control limits vector. More...
 
get_dt () const
 Returns integration timestep dt. More...
 
const ControlDerivativeget_Fu () const
 Returns derivative Fu computed by ComputeDerivatives. More...
 
const ControlDerivativeget_fu () const
 Returns derivative fu computed by ComputeDerivatives. More...
 
const StateDerivativeget_Fx () const
 Returns derivative Fx computed by ComputeDerivatives. More...
 
const StateDerivativeget_fx () const
 Returns derivative fx computed by ComputeDerivatives. More...
 
const bool & get_has_second_order_derivatives () const
 Returns whether second-order derivatives are available. More...
 
const bool & get_has_state_limits () const
 Returns whether state limits are available. More...
 
Integrator get_integrator () const
 Returns used integration scheme. More...
 
int get_num_controls () const
 Returns number of controls. More...
 
int get_num_positions () const
 Returns number of positions. 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...
 
int get_num_velocities () const
 Returns number of velocities. More...
 
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...
 
virtual void InstantiateBase (const Initializer &init)
 Instantiates the base properties of the DynamicsSolver. More...
 
virtual void Integrate (const StateVector &x, const StateVector &dx, const double dt, StateVector &xout)
 Integrates without performing dynamics. More...
 
virtual ControlVector InverseDynamics (const StateVector &state)
 Returns a control vector corresponding to the state vector assuming zero acceleration. More...
 
void set_control_limits (Eigen::VectorXdRefConst control_limits_low, Eigen::VectorXdRefConst control_limits_high)
 Sets the control limits. More...
 
void set_integrator (Integrator integrator_in)
 Sets integrator type. More...
 
virtual void SetDt (double dt_in)
 Sets the timestep dt to be used for integration. More...
 
void SetIntegrator (const std::string &integrator_in)
 Sets integrator type based on request string. More...
 
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 ~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
 Type Information wrapper: must be virtual so that it is polymorphic... More...
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::InstantiableBase
virtual std::vector< InitializerGetAllTemplates () const =0
 
virtual Initializer GetInitializerTemplate ()=0
 
 InstantiableBase ()=default
 
virtual void InstantiateInternal (const Initializer &init)=0
 
virtual ~InstantiableBase ()=default
 

Protected Member Functions

void InitializeSecondOrderDerivatives ()
 
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...
 

Protected Attributes

Eigen::MatrixXd control_limits_
 ControlLimits. Default is empty vector. More...
 
dt_ = 0.01
 Internal timestep used for integration. Defaults to 10ms. More...
 
Eigen::MatrixXd fu_
 Internal storage of differential dynamics partial derivative fu computed by ComputeDerivatives. More...
 
Eigen::MatrixXd Fu_
 Internal storage of state transition partial derivative Fu computed by ComputeDerivatives. More...
 
Eigen::Tensor< T, 3 > fuu_default_
 
Eigen::MatrixXd fx_
 Internal storage of differential dynamics partial derivative fx computed by ComputeDerivatives. More...
 
Eigen::MatrixXd Fx_
 Internal storage of state transition partial derivative Fx computed by ComputeDerivatives. More...
 
Eigen::Tensor< T, 3 > fxu_default_
 
Eigen::Tensor< T, 3 > fxx_default_
 
bool has_second_order_derivatives_ = false
 Whether this solver provides second order derivatives. If false (default), assumed to be all zeros. More...
 
bool has_state_limits_ = false
 Whether the solver specifies state limits. More...
 
Integrator integrator_ = Integrator::RK1
 Chosen integrator. Defaults to Euler (RK1). More...
 
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_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...
 
int num_velocities_ = -1
 Number of velocities in the dynamic system. More...
 
bool second_order_derivatives_initialized_ = false
 Whether fxx, fxu and fuu have been initialized to 0. 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...
 

Private Attributes

bool control_limits_initialized_ = false
 
Hessian ddStateDelta_
 
Eigen::MatrixXd dStateDelta_
 
Eigen::VectorXd raw_control_limits_high_
 
Eigen::VectorXd raw_control_limits_low_
 

Additional Inherited Members

- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Private Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 

Detailed Description

template<typename T, int NX, int NU>
class exotica::AbstractDynamicsSolver< T, NX, NU >

Definition at line 55 of file dynamics_solver.h.

Member Typedef Documentation

template<typename T , int NX, int NU>
typedef Eigen::Matrix<T, NX, NU> exotica::AbstractDynamicsSolver< T, NX, NU >::ControlDerivative

Convenience definition for a ControlDerivative.

Definition at line 61 of file dynamics_solver.h.

template<typename T , int NX, int NU>
typedef Eigen::Matrix<T, NU, 1> exotica::AbstractDynamicsSolver< T, NX, NU >::ControlVector

Convenience definition for a ControlVector (dimension NU x 1)

Definition at line 59 of file dynamics_solver.h.

template<typename T , int NX, int NU>
typedef Eigen::Matrix<T, NX, NX> exotica::AbstractDynamicsSolver< T, NX, NU >::StateDerivative

Convenience definition for a StateDerivative.

Definition at line 60 of file dynamics_solver.h.

template<typename T , int NX, int NU>
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)

Definition at line 58 of file dynamics_solver.h.

Constructor & Destructor Documentation

template<typename T , int NX, int NU>
exotica::AbstractDynamicsSolver< T, NX, NU >::AbstractDynamicsSolver ( )
default
template<typename T , int NX, int NU>
exotica::AbstractDynamicsSolver< T, NX, NU >::~AbstractDynamicsSolver ( )
virtualdefault

Member Function Documentation

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::AssignScene ( std::shared_ptr< Scene scene_in)
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.

Definition at line 58 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::ClampToStateLimits ( Eigen::Ref< Eigen::VectorXd >  state_in)

Clamps the passed in state to the state limits.

Definition at line 279 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::ComputeDerivatives ( const StateVector x,
const ControlVector u 
)
virtual

Computes derivatives fx, fu, Fx, Fu [single call for efficiency, derivatives can be retrieved with get_fx, get_fu, get_Fx, get_Fu].

Definition at line 407 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
virtual Hessian exotica::AbstractDynamicsSolver< T, NX, NU >::ddStateDelta ( const StateVector x_1,
const StateVector x_2,
const ArgumentPosition  first_or_second 
)
inlinevirtual

Definition at line 162 of file dynamics_solver.h.

template<typename T , int NX, int NU>
virtual Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> exotica::AbstractDynamicsSolver< T, NX, NU >::dStateDelta ( const StateVector x_1,
const StateVector x_2,
const ArgumentPosition  first_or_second 
)
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.

Definition at line 149 of file dynamics_solver.h.

template<typename T , int NX, int NU>
virtual StateVector exotica::AbstractDynamicsSolver< T, NX, NU >::f ( const StateVector x,
const ControlVector u 
)
pure virtual

Forward dynamics. This computes the differential dynamics.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NX, 1 > exotica::AbstractDynamicsSolver< T, NX, NU >::F ( const StateVector x,
const ControlVector u 
)
virtual

State transition function. This internally computes the differential dynamics and applies the chosen integration scheme.

Definition at line 63 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NX, NU > exotica::AbstractDynamicsSolver< T, NX, NU >::fu ( const StateVector x,
const ControlVector u 
)
virtual

Derivative of the forward dynamics w.r.t. the control.

Definition at line 401 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NX, NU > 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].

Definition at line 379 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Tensor< T, 3 > exotica::AbstractDynamicsSolver< T, NX, NU >::fuu ( const StateVector x,
const ControlVector u 
)
virtual

Definition at line 320 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NX, NX > exotica::AbstractDynamicsSolver< T, NX, NU >::fx ( const StateVector x,
const ControlVector u 
)
virtual

Derivative of the forward dynamics w.r.t. the state.

Definition at line 373 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NX, NX > 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].

Definition at line 340 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Tensor< T, 3 > exotica::AbstractDynamicsSolver< T, NX, NU >::fxu ( const StateVector x,
const ControlVector u 
)
virtual

Definition at line 327 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Tensor< T, 3 > exotica::AbstractDynamicsSolver< T, NX, NU >::fxx ( const StateVector x,
const ControlVector u 
)
virtual

Definition at line 313 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
const Eigen::MatrixXd & exotica::AbstractDynamicsSolver< T, NX, NU >::get_control_limits ( )

Returns the control limits vector.

Definition at line 247 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
T exotica::AbstractDynamicsSolver< T, NX, NU >::get_dt ( ) const

Returns integration timestep dt.

Definition at line 214 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
const Eigen::Matrix< T, NX, NU > & exotica::AbstractDynamicsSolver< T, NX, NU >::get_Fu ( ) const

Returns derivative Fu computed by ComputeDerivatives.

Definition at line 470 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
const Eigen::Matrix< T, NX, NU > & exotica::AbstractDynamicsSolver< T, NX, NU >::get_fu ( ) const

Returns derivative fu computed by ComputeDerivatives.

Definition at line 458 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
const Eigen::Matrix< T, NX, NX > & exotica::AbstractDynamicsSolver< T, NX, NU >::get_Fx ( ) const

Returns derivative Fx computed by ComputeDerivatives.

Definition at line 464 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
const Eigen::Matrix< T, NX, NX > & exotica::AbstractDynamicsSolver< T, NX, NU >::get_fx ( ) const

Returns derivative fx computed by ComputeDerivatives.

Definition at line 452 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
const bool& exotica::AbstractDynamicsSolver< T, NX, NU >::get_has_second_order_derivatives ( ) const
inline

Returns whether second-order derivatives are available.

Definition at line 111 of file dynamics_solver.h.

template<typename T , int NX, int NU>
const bool& exotica::AbstractDynamicsSolver< T, NX, NU >::get_has_state_limits ( ) const
inline

Returns whether state limits are available.

Definition at line 214 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Integrator exotica::AbstractDynamicsSolver< T, NX, NU >::get_integrator ( ) const

Returns used integration scheme.

Definition at line 220 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_controls ( ) const

Returns number of controls.

Definition at line 178 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_positions ( ) const

Returns number of positions.

Definition at line 184 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_state ( ) const

Returns size of state space (nx)

Definition at line 196 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_state_derivative ( ) const

Returns size of derivative vector of state space (ndx)

Definition at line 205 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::get_num_velocities ( ) const

Returns number of velocities.

Definition at line 190 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, Eigen::Dynamic, 1 > exotica::AbstractDynamicsSolver< T, NX, NU >::GetPosition ( Eigen::VectorXdRefConst  x_in)
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.

Definition at line 171 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::InitializeSecondOrderDerivatives ( )
protected

Definition at line 290 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::InstantiateBase ( const Initializer init)
virtual

Instantiates the base properties of the DynamicsSolver.

Reimplemented from exotica::InstantiableBase.

Definition at line 42 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::Integrate ( const StateVector x,
const StateVector dx,
const double  dt,
StateVector xout 
)
virtual

Integrates without performing dynamics.

Definition at line 122 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NU, 1 > exotica::AbstractDynamicsSolver< T, NX, NU >::InverseDynamics ( const StateVector state)
virtual

Returns a control vector corresponding to the state vector assuming zero acceleration.

Definition at line 334 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::set_control_limits ( Eigen::VectorXdRefConst  control_limits_low,
Eigen::VectorXdRefConst  control_limits_high 
)

Sets the control limits.

Definition at line 255 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::set_integrator ( Integrator  integrator_in)

Sets integrator type.

Definition at line 226 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::SetDt ( double  dt_in)
virtual

Sets the timestep dt to be used for integration.

Definition at line 70 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::SetIntegrator ( const std::string &  integrator_in)

Sets integrator type based on request string.

Definition at line 232 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NX, 1 > exotica::AbstractDynamicsSolver< T, NX, NU >::Simulate ( const StateVector x,
const ControlVector u,
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.

Definition at line 159 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
Eigen::Matrix< T, NX, 1 > exotica::AbstractDynamicsSolver< T, NX, NU >::SimulateOneStep ( const StateVector x,
const ControlVector u 
)
protectedvirtual

Integrates the dynamic system from state x with controls u applied for one timestep dt using the selected integrator.

Definition at line 77 of file dynamics_solver.cpp.

template<typename T , int NX, int NU>
virtual StateVector exotica::AbstractDynamicsSolver< T, NX, NU >::StateDelta ( const StateVector x_1,
const StateVector x_2 
)
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.

Definition at line 136 of file dynamics_solver.h.

template<typename T , int NX, int NU>
void exotica::AbstractDynamicsSolver< T, NX, NU >::StateDelta ( const StateVector x_1,
const StateVector x_2,
Eigen::VectorXdRef  xout 
)
inline

Definition at line 142 of file dynamics_solver.h.

Member Data Documentation

template<typename T , int NX, int NU>
Eigen::MatrixXd exotica::AbstractDynamicsSolver< T, NX, NU >::control_limits_
protected

ControlLimits. Default is empty vector.

Definition at line 252 of file dynamics_solver.h.

template<typename T , int NX, int NU>
bool exotica::AbstractDynamicsSolver< T, NX, NU >::control_limits_initialized_ = false
private

Definition at line 229 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Hessian exotica::AbstractDynamicsSolver< T, NX, NU >::ddStateDelta_
private

Definition at line 232 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::MatrixXd exotica::AbstractDynamicsSolver< T, NX, NU >::dStateDelta_
private

Definition at line 231 of file dynamics_solver.h.

template<typename T , int NX, int NU>
T exotica::AbstractDynamicsSolver< T, NX, NU >::dt_ = 0.01
protected

Internal timestep used for integration. Defaults to 10ms.

Definition at line 248 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::MatrixXd exotica::AbstractDynamicsSolver< T, NX, NU >::fu_
protected

Internal storage of differential dynamics partial derivative fu computed by ComputeDerivatives.

Definition at line 262 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::MatrixXd exotica::AbstractDynamicsSolver< T, NX, NU >::Fu_
protected

Internal storage of state transition partial derivative Fu computed by ComputeDerivatives.

Definition at line 264 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::Tensor<T, 3> exotica::AbstractDynamicsSolver< T, NX, NU >::fuu_default_
protected

Definition at line 259 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::MatrixXd exotica::AbstractDynamicsSolver< T, NX, NU >::fx_
protected

Internal storage of differential dynamics partial derivative fx computed by ComputeDerivatives.

Definition at line 261 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::MatrixXd exotica::AbstractDynamicsSolver< T, NX, NU >::Fx_
protected

Internal storage of state transition partial derivative Fx computed by ComputeDerivatives.

Definition at line 263 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::Tensor<T, 3> exotica::AbstractDynamicsSolver< T, NX, NU >::fxu_default_
protected

Definition at line 259 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::Tensor<T, 3> exotica::AbstractDynamicsSolver< T, NX, NU >::fxx_default_
protected

Definition at line 259 of file dynamics_solver.h.

template<typename T , int NX, int NU>
bool exotica::AbstractDynamicsSolver< T, NX, NU >::has_second_order_derivatives_ = false
protected

Whether this solver provides second order derivatives. If false (default), assumed to be all zeros.

Definition at line 241 of file dynamics_solver.h.

template<typename T , int NX, int NU>
bool exotica::AbstractDynamicsSolver< T, NX, NU >::has_state_limits_ = false
protected

Whether the solver specifies state limits.

Definition at line 244 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Integrator exotica::AbstractDynamicsSolver< T, NX, NU >::integrator_ = Integrator::RK1
protected

Chosen integrator. Defaults to Euler (RK1).

Definition at line 249 of file dynamics_solver.h.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::num_controls_ = -1
protected

Number of controls in the dynamic system.

Definition at line 235 of file dynamics_solver.h.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::num_positions_ = -1
protected

Number of positions in the dynamic system.

Definition at line 236 of file dynamics_solver.h.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::num_state_ = -1
protected

Size of state space (num_positions + num_velocities)

Definition at line 238 of file dynamics_solver.h.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::num_state_derivative_ = -1
protected

Size of the tangent vector to the state space (2 * num_velocities)

Definition at line 239 of file dynamics_solver.h.

template<typename T , int NX, int NU>
int exotica::AbstractDynamicsSolver< T, NX, NU >::num_velocities_ = -1
protected

Number of velocities in the dynamic system.

Definition at line 237 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::VectorXd exotica::AbstractDynamicsSolver< T, NX, NU >::raw_control_limits_high_
private

Definition at line 230 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::VectorXd exotica::AbstractDynamicsSolver< T, NX, NU >::raw_control_limits_low_
private

Definition at line 230 of file dynamics_solver.h.

template<typename T , int NX, int NU>
bool exotica::AbstractDynamicsSolver< T, NX, NU >::second_order_derivatives_initialized_ = false
protected

Whether fxx, fxu and fuu have been initialized to 0.

Definition at line 242 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::VectorXd exotica::AbstractDynamicsSolver< T, NX, NU >::state_limits_lower_
protected

Lower state limits (configuration and velocity)

Definition at line 245 of file dynamics_solver.h.

template<typename T , int NX, int NU>
Eigen::VectorXd exotica::AbstractDynamicsSolver< T, NX, NU >::state_limits_upper_
protected

Upper state limits (configuration and velocity)

Definition at line 246 of file dynamics_solver.h.


The documentation for this class was generated from the following files:


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:49