Exotica
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
Collaboration diagram for exotica::AbstractDynamicsSolver< T, NX, NU >:
Collaboration graph

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 StateDerivativeget_Fx () const
 Returns derivative Fx 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 ControlDerivativeget_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...
 
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< InitializerGetAllTemplates () 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...
 
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
 

Member Typedef Documentation

◆ ControlDerivative

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

Convenience definition for a ControlDerivative.

◆ ControlVector

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)

◆ StateDerivative

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

Convenience definition for a StateDerivative.

◆ StateVector

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)

Constructor & Destructor Documentation

◆ AbstractDynamicsSolver()

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

◆ ~AbstractDynamicsSolver()

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

Member Function Documentation

◆ AssignScene()

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

◆ ClampToStateLimits()

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.

◆ ComputeDerivatives()

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

Reimplemented in exotica::PinocchioDynamicsSolver, exotica::PinocchioDynamicsSolverWithGravityCompensation, and exotica::DoubleIntegratorDynamicsSolver.

◆ ddStateDelta()

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

◆ dStateDelta()

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.

Reimplemented in exotica::PinocchioDynamicsSolver, and exotica::PinocchioDynamicsSolverWithGravityCompensation.

◆ F()

template<typename T , int NX, int NU>
virtual StateVector 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.

◆ f()

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

◆ fu()

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

◆ fu_fd()

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

◆ fuu()

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

◆ fx()

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

◆ fx_fd()

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

◆ fxu()

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

◆ fxx()

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

◆ get_control_limits()

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

Returns the control limits vector.

◆ get_dt()

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

Returns integration timestep dt.

◆ get_Fu()

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

Returns derivative Fu computed by ComputeDerivatives.

◆ get_fu()

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

Returns derivative fu computed by ComputeDerivatives.

◆ get_Fx()

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

Returns derivative Fx computed by ComputeDerivatives.

◆ get_fx()

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

Returns derivative fx computed by ComputeDerivatives.

◆ get_has_second_order_derivatives()

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.

◆ get_has_state_limits()

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.

◆ get_integrator()

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

Returns used integration scheme.

◆ get_num_controls()

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

Returns number of controls.

◆ get_num_positions()

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

Returns number of positions.

◆ get_num_state()

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

Returns size of state space (nx)

◆ get_num_state_derivative()

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)

◆ get_num_velocities()

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

Returns number of velocities.

◆ GetPosition()

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

◆ InitializeSecondOrderDerivatives()

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

◆ InstantiateBase()

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

Instantiates the base properties of the DynamicsSolver.

Reimplemented from exotica::InstantiableBase.

◆ Integrate()

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

Integrates without performing dynamics.

Reimplemented in exotica::PinocchioDynamicsSolver, and exotica::PinocchioDynamicsSolverWithGravityCompensation.

◆ InverseDynamics()

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

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

Reimplemented in exotica::PinocchioDynamicsSolver.

◆ set_control_limits()

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.

◆ set_integrator()

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

Sets integrator type.

◆ SetDt()

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

Sets the timestep dt to be used for integration.

◆ SetIntegrator()

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.

◆ Simulate()

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

◆ SimulateOneStep()

template<typename T , int NX, int NU>
virtual StateVector 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.

◆ StateDelta() [1/2]

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.

Reimplemented in exotica::PinocchioDynamicsSolver, and exotica::PinocchioDynamicsSolverWithGravityCompensation.

◆ StateDelta() [2/2]

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

Member Data Documentation

◆ control_limits_

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

ControlLimits. Default is empty vector.

◆ control_limits_initialized_

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

◆ ddStateDelta_

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

◆ dStateDelta_

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

◆ dt_

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.

◆ fu_

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.

◆ Fu_

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.

◆ fuu_default_

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

◆ fx_

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.

◆ Fx_

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.

◆ fxu_default_

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

◆ fxx_default_

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

◆ has_second_order_derivatives_

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.

◆ has_state_limits_

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

Whether the solver specifies state limits.

◆ integrator_

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

Chosen integrator. Defaults to Euler (RK1).

◆ num_controls_

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

Number of controls in the dynamic system.

◆ num_positions_

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

Number of positions in the dynamic system.

◆ num_state_

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)

◆ num_state_derivative_

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)

◆ num_velocities_

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

Number of velocities in the dynamic system.

◆ raw_control_limits_high_

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

◆ raw_control_limits_low_

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

◆ second_order_derivatives_initialized_

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.

◆ state_limits_lower_

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

Lower state limits (configuration and velocity)

◆ state_limits_upper_

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

Upper state limits (configuration and velocity)


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