adam.pytorch.computations#
Classes#
This is a small class that retrieves robot quantities using Pytorch for Floating Base systems. |
Module Contents#
- class adam.pytorch.computations.KinDynComputations(urdfstring: str, joints_name_list: list = None, root_link: str = None, gravity: numpy.array = torch.tensor([0, 0, -9.80665, 0, 0, 0]))[source]#
This is a small class that retrieves robot quantities using Pytorch for Floating Base systems.
- set_frame_velocity_representation(representation: adam.core.constants.Representations) None [source]#
Sets the representation of the velocity of the frames
- Parameters:
representation (Representations) – The representation of the velocity
- mass_matrix(base_transform: torch.Tensor, joint_positions: torch.Tensor) torch.Tensor [source]#
Returns the Mass Matrix functions computed the CRBA
- Parameters:
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
- Returns:
Mass Matrix
- Return type:
M (torch.tensor)
- centroidal_momentum_matrix(base_transform: torch.Tensor, joint_positions: torch.Tensor) torch.Tensor [source]#
Returns the Centroidal Momentum Matrix functions computed the CRBA
- Parameters:
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
- Returns:
Centroidal Momentum matrix
- Return type:
Jcc (torch.tensor)
- forward_kinematics(frame, base_transform: torch.Tensor, joint_positions: torch.Tensor) torch.Tensor [source]#
Computes the forward kinematics relative to the specified frame
- Parameters:
frame (str) – The frame to which the fk will be computed
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
- Returns:
The fk represented as Homogenous transformation matrix
- Return type:
H (torch.tensor)
- jacobian(frame: str, base_transform: torch.Tensor, joint_positions: torch.Tensor) torch.Tensor [source]#
Returns the Jacobian relative to the specified frame
- Parameters:
frame (str) – The frame to which the jacobian will be computed
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
- Returns:
The Jacobian relative to the frame
- Return type:
J_tot (torch.tensor)
- relative_jacobian(frame, joint_positions: torch.Tensor) torch.Tensor [source]#
Returns the Jacobian between the root link and a specified frame frames
- Parameters:
frame (str) – The tip of the chain
joint_positions (torch.tensor) – The joints position
- Returns:
The Jacobian between the root and the frame
- Return type:
J (torch.tensor)
- jacobian_dot(frame: str, base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) torch.Tensor [source]#
Returns the Jacobian derivative relative to the specified frame
- Parameters:
frame (str) – The frame to which the jacobian will be computed
base_transform (torch.Tensor) – The homogenous transform from base to world frame
joint_positions (torch.Tensor) – The joints position
base_velocity (torch.Tensor) – The base velocity
joint_velocities (torch.Tensor) – The joint velocities
- Returns:
The Jacobian derivative relative to the frame
- Return type:
Jdot (torch.Tensor)
- CoM_position(base_transform: torch.Tensor, joint_positions: torch.Tensor) torch.Tensor [source]#
Returns the CoM position
- Parameters:
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
- Returns:
The CoM position
- Return type:
CoM (torch.tensor)
- CoM_jacobian(base_transform: torch.Tensor, joint_positions: torch.Tensor) torch.Tensor [source]#
Returns the CoM Jacobian
- Parameters:
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
- Returns:
The CoM Jacobian
- Return type:
Jcom (torch.tensor)
- bias_force(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) torch.Tensor [source]#
Returns the bias force of the floating-base dynamics equation, using a reduced RNEA (no acceleration and external forces)
- Parameters:
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
base_velocity (torch.tensor) – The base velocity
joint_velocities (torch.tensor) – The joints velocity
- Returns:
the bias force
- Return type:
h (torch.tensor)
- coriolis_term(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) torch.Tensor [source]#
Returns the coriolis term of the floating-base dynamics equation, using a reduced RNEA (no acceleration and external forces)
- Parameters:
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints position
base_velocity (torch.tensor) – The base velocity
joint_velocities (torch.tensor) – The joints velocity
- Returns:
the Coriolis term
- Return type:
C (torch.tensor)
- gravity_term(base_transform: torch.Tensor, joint_positions: torch.Tensor) torch.Tensor [source]#
Returns the gravity term of the floating-base dynamics equation, using a reduced RNEA (no acceleration and external forces)
- Parameters:
base_transform (torch.tensor) – The homogenous transform from base to world frame
joint_positions (torch.tensor) – The joints positions
- Returns:
the gravity term
- Return type:
G (torch.tensor)