Unverified Commit e548a1d3 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Fixes the indices used for arm quantities in the mobile manipulator class (#36)

* fixes the indices used for arm quantities in mobile manipulator class
* updates changelog
parent d75e7ff6
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.2.4" version = "0.2.5"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.2.5 (2023-03-08)
~~~~~~~~~~~~~~~~~~
Fixed
^^^^^
* Fixed the indices used for the Jacobian and dynamics quantities in the :class:`MobileManipulator` class.
0.2.4 (2023-03-04) 0.2.4 (2023-03-04)
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
......
...@@ -94,26 +94,26 @@ class MobileManipulator(SingleArmManipulator): ...@@ -94,26 +94,26 @@ class MobileManipulator(SingleArmManipulator):
# Note: we implement this function here to allow inherited classes decide whether these # Note: we implement this function here to allow inherited classes decide whether these
# quantities need to be updated similarly or not. # quantities need to be updated similarly or not.
# -- dynamic state (note: base and tools don't contribute towards these quantities) # -- dynamic state (note: base and tools don't contribute towards these quantities)
start_index = self.base_num_dof
end_index = start_index + self.arm_num_dof
# jacobian # jacobian
if self.cfg.data_info.enable_jacobian: if self.cfg.data_info.enable_jacobian:
jacobians = self.articulations.get_jacobians(indices=self._ALL_INDICES, clone=False) jacobians = self.articulations.get_jacobians(indices=self._ALL_INDICES, clone=False)
# Returned jacobian: [batch, body, 6, dof] does not include the base body (i.e. the first link). # Returned jacobian: [batch, body, 6, dof] does not include the base body (i.e. the first link).
# So we need to subtract 1 from the body index to get the correct jacobian. # So we need to subtract 1 from the body index to get the correct jacobian.
self._data.ee_jacobian[:] = jacobians[:, self.ee_body_index - 1, :, self.base_num_dof : self.arm_num_dof] self._data.ee_jacobian[:] = jacobians[:, self.ee_body_index - 1, :, start_index:end_index]
# mass matrix # mass matrix
if self.cfg.data_info.enable_mass_matrix: if self.cfg.data_info.enable_mass_matrix:
mass_matrices = self.articulations.get_mass_matrices(indices=self._ALL_INDICES, clone=False) mass_matrices = self.articulations.get_mass_matrices(indices=self._ALL_INDICES, clone=False)
self._data.mass_matrix[:] = mass_matrices[ self._data.mass_matrix[:] = mass_matrices[:, start_index:end_index, start_index:end_index]
:, self.base_num_dof : self.arm_num_dof, self.base_num_dof : self.arm_num_dof
]
# coriolis # coriolis
if self.cfg.data_info.enable_coriolis: if self.cfg.data_info.enable_coriolis:
forces = self.articulations.get_coriolis_and_centrifugal_forces(indices=self._ALL_INDICES, clone=False) forces = self.articulations.get_coriolis_and_centrifugal_forces(indices=self._ALL_INDICES, clone=False)
self._data.coriolis[:] = forces[:, self.base_num_dof : self.arm_num_dof] self._data.coriolis[:] = forces[:, start_index:end_index]
# gravity # gravity
if self.cfg.data_info.enable_gravity: if self.cfg.data_info.enable_gravity:
gravity = self.articulations.get_generalized_gravity_forces(indices=self._ALL_INDICES, clone=False) gravity = self.articulations.get_generalized_gravity_forces(indices=self._ALL_INDICES, clone=False)
self._data.gravity[:] = gravity[:, self.base_num_dof : self.arm_num_dof] self._data.gravity[:] = gravity[:, start_index:end_index]
class LeggedMobileManipulator(MobileManipulator, LeggedRobot): class LeggedMobileManipulator(MobileManipulator, LeggedRobot):
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment