@@ -50,7 +50,7 @@ def set_frame_velocity_representation(
50
50
self .rbdalgos .set_frame_velocity_representation (representation )
51
51
52
52
def mass_matrix (
53
- self , base_transform : torch .Tensor , joint_position : torch .Tensor
53
+ self , base_transform : torch .Tensor , joint_positions : torch .Tensor
54
54
) -> torch .Tensor :
55
55
"""Returns the Mass Matrix functions computed the CRBA
56
56
@@ -61,11 +61,11 @@ def mass_matrix(
61
61
Returns:
62
62
M (torch.tensor): Mass Matrix
63
63
"""
64
- [M , _ ] = self .rbdalgos .crba (base_transform , joint_position )
64
+ [M , _ ] = self .rbdalgos .crba (base_transform , joint_positions )
65
65
return M .array
66
66
67
67
def centroidal_momentum_matrix (
68
- self , base_transform : torch .Tensor , joint_position : torch .Tensor
68
+ self , base_transform : torch .Tensor , joint_positions : torch .Tensor
69
69
) -> torch .Tensor :
70
70
"""Returns the Centroidal Momentum Matrix functions computed the CRBA
71
71
@@ -76,11 +76,11 @@ def centroidal_momentum_matrix(
76
76
Returns:
77
77
Jcc (torch.tensor): Centroidal Momentum matrix
78
78
"""
79
- [_ , Jcm ] = self .rbdalgos .crba (base_transform , joint_position )
79
+ [_ , Jcm ] = self .rbdalgos .crba (base_transform , joint_positions )
80
80
return Jcm .array
81
81
82
82
def forward_kinematics (
83
- self , frame , base_transform : torch .Tensor , joint_position : torch .Tensor
83
+ self , frame , base_transform : torch .Tensor , joint_positions : torch .Tensor
84
84
) -> torch .Tensor :
85
85
"""Computes the forward kinematics relative to the specified frame
86
86
@@ -96,7 +96,7 @@ def forward_kinematics(
96
96
self .rbdalgos .forward_kinematics (
97
97
frame ,
98
98
base_transform ,
99
- joint_position ,
99
+ joint_positions ,
100
100
)
101
101
).array
102
102
@@ -177,7 +177,7 @@ def bias_force(
177
177
base_velocity : torch .Tensor ,
178
178
joint_velocities : torch .Tensor ,
179
179
) -> torch .Tensor :
180
- """Returns the bias force of the floating-base dynamics ejoint_positionsuation ,
180
+ """Returns the bias force of the floating-base dynamics equation ,
181
181
using a reduced RNEA (no acceleration and external forces)
182
182
183
183
Args:
@@ -204,7 +204,7 @@ def coriolis_term(
204
204
base_velocity : torch .Tensor ,
205
205
joint_velocities : torch .Tensor ,
206
206
) -> torch .Tensor :
207
- """Returns the coriolis term of the floating-base dynamics ejoint_positionsuation ,
207
+ """Returns the coriolis term of the floating-base dynamics equation ,
208
208
using a reduced RNEA (no acceleration and external forces)
209
209
210
210
Args:
@@ -228,7 +228,7 @@ def coriolis_term(
228
228
def gravity_term (
229
229
self , base_transform : torch .Tensor , joint_positions : torch .Tensor
230
230
) -> torch .Tensor :
231
- """Returns the gravity term of the floating-base dynamics ejoint_positionsuation ,
231
+ """Returns the gravity term of the floating-base dynamics equation ,
232
232
using a reduced RNEA (no acceleration and external forces)
233
233
234
234
Args:
0 commit comments