Skip to content

Commit ca9ec26

Browse files
authored
Fix joint_position -> joint_positions in pytorch KinDynComputations
1 parent daf88ff commit ca9ec26

File tree

1 file changed

+9
-9
lines changed

1 file changed

+9
-9
lines changed

src/adam/pytorch/computations.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ def set_frame_velocity_representation(
5050
self.rbdalgos.set_frame_velocity_representation(representation)
5151

5252
def mass_matrix(
53-
self, base_transform: torch.Tensor, joint_position: torch.Tensor
53+
self, base_transform: torch.Tensor, joint_positions: torch.Tensor
5454
) -> torch.Tensor:
5555
"""Returns the Mass Matrix functions computed the CRBA
5656
@@ -61,11 +61,11 @@ def mass_matrix(
6161
Returns:
6262
M (torch.tensor): Mass Matrix
6363
"""
64-
[M, _] = self.rbdalgos.crba(base_transform, joint_position)
64+
[M, _] = self.rbdalgos.crba(base_transform, joint_positions)
6565
return M.array
6666

6767
def centroidal_momentum_matrix(
68-
self, base_transform: torch.Tensor, joint_position: torch.Tensor
68+
self, base_transform: torch.Tensor, joint_positions: torch.Tensor
6969
) -> torch.Tensor:
7070
"""Returns the Centroidal Momentum Matrix functions computed the CRBA
7171
@@ -76,11 +76,11 @@ def centroidal_momentum_matrix(
7676
Returns:
7777
Jcc (torch.tensor): Centroidal Momentum matrix
7878
"""
79-
[_, Jcm] = self.rbdalgos.crba(base_transform, joint_position)
79+
[_, Jcm] = self.rbdalgos.crba(base_transform, joint_positions)
8080
return Jcm.array
8181

8282
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
8484
) -> torch.Tensor:
8585
"""Computes the forward kinematics relative to the specified frame
8686
@@ -96,7 +96,7 @@ def forward_kinematics(
9696
self.rbdalgos.forward_kinematics(
9797
frame,
9898
base_transform,
99-
joint_position,
99+
joint_positions,
100100
)
101101
).array
102102

@@ -177,7 +177,7 @@ def bias_force(
177177
base_velocity: torch.Tensor,
178178
joint_velocities: torch.Tensor,
179179
) -> 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,
181181
using a reduced RNEA (no acceleration and external forces)
182182
183183
Args:
@@ -204,7 +204,7 @@ def coriolis_term(
204204
base_velocity: torch.Tensor,
205205
joint_velocities: torch.Tensor,
206206
) -> 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,
208208
using a reduced RNEA (no acceleration and external forces)
209209
210210
Args:
@@ -228,7 +228,7 @@ def coriolis_term(
228228
def gravity_term(
229229
self, base_transform: torch.Tensor, joint_positions: torch.Tensor
230230
) -> 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,
232232
using a reduced RNEA (no acceleration and external forces)
233233
234234
Args:

0 commit comments

Comments
 (0)