jaxsim.rbda.aba#
- jaxsim.rbda.aba(model, *, base_position, base_quaternion, joint_positions, base_linear_velocity, base_angular_velocity, joint_velocities, joint_forces=None, link_forces=None, standard_gravity=9.81)[source]#
Compute forward dynamics using the Articulated Body Algorithm (ABA).
- Parameters:
model (
JaxSimModel
) – The model to consider.base_position (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The position of the base link.base_quaternion (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The quaternion of the base link.joint_positions (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The positions of the joints.base_linear_velocity (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The linear velocity of the base link in inertial-fixed representation.base_angular_velocity (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The angular velocity of the base link in inertial-fixed representation.joint_velocities (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The velocities of the joints.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The forces applied to the joints.link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The forces applied to the links expressed in the world frame.standard_gravity (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The standard gravity constant.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the base acceleration in inertial-fixed representation and the joint accelerations that result from the applications of the given joint and link forces.
Note
The algorithm expects a quaternion with unit norm.