Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
45 commits
Select commit Hold shift + click to select a range
2340edc
Add backend-agnostic task-space accessors for IK/OSC on Newton
hujc7 Apr 25, 2026
19a3a34
Address Codex / Greptile / Isaac Lab bot review
hujc7 Apr 27, 2026
9ee21ac
Address Codex round 2 review (P2)
hujc7 Apr 27, 2026
0c5aafa
Add shape-contract regression tests for the new accessors
hujc7 Apr 27, 2026
982da9a
Address Codex round 3: backwards-compat + floating-base note
hujc7 Apr 27, 2026
8dda563
Revert: let Pink IK gravity-comp crash loudly on Newton
hujc7 Apr 28, 2026
b6c036d
Merge remote-tracking branch 'origin/develop' into jichuanh/ik-newton…
hujc7 Apr 28, 2026
150c2e0
[Newton] Apply COM->origin shift to get_jacobians; add accuracy tests
hujc7 May 1, 2026
cd0fb72
[Newton] Add J·q_dot link-origin contract test on Newton
hujc7 May 1, 2026
498205f
[Newton] Add IK and OSC tracking accuracy regression sentinels
hujc7 May 1, 2026
134efbb
[Newton] Tighten IK and OSC accuracy thresholds based on stress data
hujc7 May 1, 2026
5077e4a
[docs] Note Newton task-space tracking floor as known issue
hujc7 May 1, 2026
0c8d4aa
[Newton] Tighten IK/OSC accuracy tests by fixing setup artifacts
hujc7 May 1, 2026
b14585b
[PhysX] Add IK/OSC tracking accuracy tests for backend parity
hujc7 May 1, 2026
c21963d
[Test] Modularize Franka tracking-test setup with shared helpers
hujc7 May 1, 2026
f5eaf90
[Test] Feed real ee_vel to OSC; assert on tail mean not min
hujc7 May 2, 2026
44a2209
[Docs] Tighten BaseArticulation docstrings to interface contract
hujc7 May 2, 2026
a51e563
[Actions] Add num_jacobi_joints property to handle Jacobian dimension…
aravindskumar-nvidia May 2, 2026
d1d038d
[Newton] Deep-copy SIM_CFGs in sim fixture
aravindskumar-nvidia May 2, 2026
f1ec832
Merge pull request #2 from aravindskumar-nvidia/aravikumar/ik-qol
hujc7 May 2, 2026
47cab0f
Merge develop into jichuanh/ik-newton-compat-mvp
hujc7 May 2, 2026
a2a07ed
Make BaseArticulation.num_jacobi_joints abstract, add Newton override
hujc7 May 2, 2026
d25773a
Rename num_jacobi_joints to joint_to_jacobi_offset
hujc7 May 2, 2026
d6cfcff
Drop redundant offset comments in task-space action terms
hujc7 May 2, 2026
c0f3ba1
Address codex review: Newton floating-base gather + ovphysx changelog
hujc7 May 2, 2026
1d620d4
Move task-space dynamics accessors to BaseArticulationData properties
hujc7 May 4, 2026
8aa4bf6
Update changelog fragments for the data-layer migration
hujc7 May 4, 2026
2d62552
Strip floating-base DoF prefix on PhysX; remove joint_to_jacobi_offset
hujc7 May 4, 2026
77ae8a0
Align J/M/g DoF axis with industry standard; add num_base_dofs
hujc7 May 5, 2026
707ed8b
Update stale references to removed BaseArticulation.get_* methods
hujc7 May 5, 2026
b0d179f
Migrate tutorials and demos to data-layer task-space accessors
hujc7 May 5, 2026
2a814c1
Tighten task-space-accessor docstrings to focus on the contract
hujc7 May 5, 2026
25fc4c7
Merge remote-tracking branch 'origin/develop' into jichuanh/ik-newton…
hujc7 May 6, 2026
11f62c5
Collapse jacobi-axis indexing into one block per action term
hujc7 May 6, 2026
cb484c2
Add OSC + gravity-compensation behavioral tests
hujc7 May 6, 2026
10d2305
Merge remote-tracking branch 'origin/develop' into jichuanh/ik-newton…
hujc7 May 8, 2026
1e7fdc9
Merge remote-tracking branch 'origin/develop' into jichuanh/ik-newton…
hujc7 May 10, 2026
a70e2ef
Copy panda cfg before unfixing root in fixed-to-floating test
hujc7 May 11, 2026
9522603
Keep fixed-base velocity binding stable across resets
hujc7 May 11, 2026
2a34f85
Refine task-space accessor wiring and buffer naming
hujc7 May 12, 2026
3bbe3da
Drop repeated axis-convention comments in task-space action terms
hujc7 May 12, 2026
f35e091
Merge remote-tracking branch 'origin/develop' into jichuanh/ik-newton…
hujc7 May 12, 2026
1f5b5c9
Refresh PhysX task-space accessors on each timestamp advance
hujc7 May 13, 2026
44280a9
Merge branch 'develop' into jichuanh/ik-newton-compat-mvp
hujc7 May 13, 2026
7471978
Merge branch 'develop' into jichuanh/ik-newton-compat-mvp
kellyguo11 May 13, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 8 additions & 2 deletions scripts/demos/haply_teleoperation.py
Original file line number Diff line number Diff line change
Expand Up @@ -191,6 +191,9 @@ def run_simulator(

ee_body_name = "panda_hand"
ee_body_idx = robot.body_names.index(ee_body_name)
# ``body_link_jacobian_w`` drops the fixed-root body row for fixed-base assets,
# so the Jacobian-axis body index is ``body_idx - 1`` in that case.
ee_jacobi_body_idx = ee_body_idx - 1 if robot.is_fixed_base else ee_body_idx

joint_pos = robot.data.default_joint_pos.torch.clone()
joint_pos[0, :7] = torch.tensor([0.0, -0.569, 0.0, -2.81, 0.0, 3.037, 0.741], device=robot.device)
Expand Down Expand Up @@ -307,8 +310,11 @@ def run_simulator(
ee_pos_w = robot.data.body_pos_w.torch[:, ee_body_idx]
ee_quat_w = robot.data.body_quat_w.torch[:, ee_body_idx]

# get jacobian to IK controller
jacobian = robot.root_view.get_jacobians()[:, ee_body_idx, :, arm_joint_indices]
# get jacobian to IK controller. The DoF axis prepends ``num_base_dofs``
# floating-base columns (0 for fixed-base, 6 for floating-base); shift the
# actuated-joint ids by ``num_base_dofs`` to address the actuated columns.
jacobi_joint_ids = [j + robot.num_base_dofs for j in arm_joint_indices]
jacobian = robot.data.body_link_jacobian_w.torch[:, ee_jacobi_body_idx, :, jacobi_joint_ids]
ik_controller.set_command(command=target_pos_tensor, ee_quat=ee_quat_w)
joint_pos_des = ik_controller.compute(ee_pos_w, ee_quat_w, jacobian, current_joint_pos)

Expand Down
7 changes: 5 additions & 2 deletions scripts/tutorials/05_controllers/run_diff_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -159,8 +159,11 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
# change goal
current_goal_idx = (current_goal_idx + 1) % len(ee_goals)
else:
# obtain quantities from simulation
jacobian = robot.root_view.get_jacobians()[:, ee_jacobi_idx, :, robot_entity_cfg.joint_ids]
# obtain quantities from simulation. The Jacobian DoF axis prepends
# ``num_base_dofs`` floating-base columns (0 for fixed-base, 6 for
# floating-base); shift the actuated-joint ids accordingly.
jacobi_joint_ids = [j + robot.num_base_dofs for j in robot_entity_cfg.joint_ids]
jacobian = robot.data.body_link_jacobian_w.torch[:, ee_jacobi_idx, :, jacobi_joint_ids]
ee_pose_w = robot.data.body_pose_w.torch[:, robot_entity_cfg.body_ids[0]]
root_pose_w = robot.data.root_pose_w.torch
joint_pos = robot.data.joint_pos.torch[:, robot_entity_cfg.joint_ids]
Expand Down
10 changes: 7 additions & 3 deletions scripts/tutorials/05_controllers/run_osc.py
Original file line number Diff line number Diff line change
Expand Up @@ -314,9 +314,13 @@ def update_states(
"""
# obtain dynamics related quantities from simulation
ee_jacobi_idx = ee_frame_idx - 1
jacobian_w = robot.root_view.get_jacobians()[:, ee_jacobi_idx, :, arm_joint_ids]
mass_matrix = robot.root_view.get_generalized_mass_matrices()[:, arm_joint_ids, :][:, :, arm_joint_ids]
gravity = robot.root_view.get_gravity_compensation_forces()[:, arm_joint_ids]
# The J / M / g DoF axis prepends ``num_base_dofs`` floating-base columns
# (0 for fixed-base, 6 for floating-base); shift the actuated-joint ids by
# ``num_base_dofs`` to address the actuated-joint columns directly.
jacobi_joint_ids = [j + robot.num_base_dofs for j in arm_joint_ids]
jacobian_w = robot.data.body_link_jacobian_w.torch[:, ee_jacobi_idx, :, jacobi_joint_ids]
mass_matrix = robot.data.mass_matrix.torch[:, jacobi_joint_ids, :][:, :, jacobi_joint_ids]
gravity = robot.data.gravity_compensation_forces.torch[:, jacobi_joint_ids]
# Convert the Jacobian from world to root frame
jacobian_b = jacobian_w.clone()
root_rot_matrix = matrix_from_quat(quat_inv(robot.data.root_quat_w.torch))
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
Added
^^^^^

* Added :attr:`~isaaclab.assets.BaseArticulationData.body_link_jacobian_w` and
:attr:`~isaaclab.assets.BaseArticulationData.body_com_jacobian_w` properties,
exposing the per-body geometric Jacobian referenced at the link origin and
body center of mass respectively. The pair mirrors the existing
:attr:`~isaaclab.assets.BaseArticulationData.body_link_pose_w` /
:attr:`~isaaclab.assets.BaseArticulationData.body_com_pose_w` and
:attr:`~isaaclab.assets.BaseArticulationData.body_link_vel_w` /
:attr:`~isaaclab.assets.BaseArticulationData.body_com_vel_w` exposure pattern.
Backends without a native primitive raise :class:`NotImplementedError`.
* Added :attr:`~isaaclab.assets.BaseArticulationData.mass_matrix` property,
exposing the joint-space generalized mass matrix ``M(q)``.
* Added :attr:`~isaaclab.assets.BaseArticulationData.gravity_compensation_forces`
property, exposing the joint-space gravity-loading torque vector ``g(q)``.
* Added :attr:`~isaaclab.assets.BaseArticulation.num_base_dofs` — number of
free DoFs of the floating base (``0`` for fixed-base, ``6`` for floating-
base). Use it to map an actuated-joint index ``j`` to its column in the
Jacobian / mass matrix / gravity vector via ``j + num_base_dofs``.

The Jacobian / mass-matrix / gravity-comp DoF axis includes the floating-
base DoFs at the front: shape ``(N, num_jacobi_bodies, 6, num_joints +
num_base_dofs)`` for the Jacobian and ``(N, num_joints + num_base_dofs,
num_joints + num_base_dofs)`` for the mass matrix. This matches the
cross-library industry convention (Pinocchio's ``nv = 6 + n_actuated``,
Drake's ephemeral floating joint, MuJoCo's ``<freejoint/>``, RBDL's
``JointTypeFloatingBase``, OCS2's ``generalizedCoordinatesNum =
6 + actuatedJointsNum``, iDynTree's ``getFreeFloatingMassMatrix``
returning ``(6 + dofs, 6 + dofs)``).

Changed
^^^^^^^

* Migrated :class:`~isaaclab.envs.mdp.actions.task_space_actions.DifferentialInverseKinematicsAction`,
:class:`~isaaclab.envs.mdp.actions.task_space_actions.OperationalSpaceControllerAction`,
and :class:`~isaaclab.envs.mdp.actions.rmpflow_task_space_actions.RMPFlowAction`
to fetch dynamic quantities through the new
:class:`~isaaclab.assets.BaseArticulationData` properties instead of the
PhysX-only ``root_view``. The OSC action term now also gates the
per-step mass-matrix and gravity-compensation fetches behind the
controller cfg's :attr:`inertial_dynamics_decoupling`,
:attr:`nullspace_control`, and :attr:`gravity_compensation` flags
so backends without a native primitive are not invoked when the
controller does not consume the result.
* Action terms (DiffIK / OSC / RMPFlow / Pink) compute their Jacobian
joint-axis indices via
``[j + asset.num_base_dofs for j in joint_ids]``, which is ``0`` for
fixed-base and ``+6`` for floating-base. Pink IK previously hardcoded
a private ``_physx_floating_joint_indices_offset = 6``; that was
removed in favor of the cross-backend property.
* PhysX backend's :attr:`body_link_jacobian_w` applies the COM→origin shift to
PhysX's natively COM-referenced Jacobian. The previously-exposed
``Articulation.get_jacobians()`` was a passthrough that returned the raw
COM-referenced Jacobian, while IK / OSC consumers also read
:attr:`body_link_pose_w` as the EE pose setpoint — a frame mismatch that
produced a ``ω × r_com_w`` per-body bias in tracking. The new property
reads the same engine buffer and applies the shift so ``J · q_dot`` matches
``body_link_lin_vel_w``. Consumers that intentionally want the raw
COM-referenced form can read :attr:`body_com_jacobian_w`.
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,19 @@ def root_view(self):
"""
raise NotImplementedError()

@property
def num_base_dofs(self) -> int:
"""Number of free DoFs of the floating base.

A floating-base articulation can translate and rotate freely in space, so
its base contributes 6 DoFs (3 linear, 3 angular). A fixed-base articulation
is bolted to the world and contributes 0.

Use this to map an actuated-joint index ``j`` to its column in the Jacobian
/ mass matrix / gravity vector: ``column = j + num_base_dofs``.
"""
return 0 if self.is_fixed_base else 6

@property
@abstractmethod
def instantaneous_wrench_composer(self) -> WrenchComposer:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -669,6 +669,83 @@ def body_com_pose_b(self) -> ProxyArray:
"""
raise NotImplementedError

##
# Dynamics quantities (task-space controllers).
##

@property
def body_link_jacobian_w(self) -> ProxyArray:
"""Per-body geometric Jacobian referenced at each body's link origin in world frame.

Shape: ``(num_instances, num_jacobi_bodies, 6, num_joints + num_base_dofs)``,
dtype ``wp.float32``. Linear rows ``[0:3]`` [m/s per unit DoF velocity];
angular rows ``[3:6]`` [rad/s per unit DoF velocity].

Contract: for any generalized velocity ``v`` of length
``num_joints + num_base_dofs``,

.. code-block:: text

J[:, jacobi_body_idx, 0:3, :] @ v == body_link_lin_vel_w[:, body_idx]
J[:, jacobi_body_idx, 3:6, :] @ v == body_link_ang_vel_w[:, body_idx]

Conventions:
* Body axis: ``jacobi_body_idx == body_idx - 1`` for fixed-base (fixed-root
row excluded); ``jacobi_body_idx == body_idx`` for floating-base.
* DoF axis: leading
:attr:`~isaaclab.assets.BaseArticulation.num_base_dofs` floating-base
columns (world-frame ``[lin_x, lin_y, lin_z, ang_x, ang_y, ang_z]``),
then actuated-joint columns in :attr:`joint_names` order.
"""
raise NotImplementedError(f"{type(self).__name__} does not implement body_link_jacobian_w.")

@property
def body_com_jacobian_w(self) -> ProxyArray:
"""Per-body geometric Jacobian referenced at each body's center of mass in world frame.

Same shape and indexing conventions as :attr:`body_link_jacobian_w`. Linear
rows ``[0:3]`` give the velocity at the body's center of mass; angular rows
``[3:6]`` are reference-point invariant (identical to
:attr:`body_link_jacobian_w`).

Contract: for any generalized velocity ``v``,

.. code-block:: text

J[:, jacobi_body_idx, 0:3, :] @ v == body_com_lin_vel_w[:, body_idx]
J[:, jacobi_body_idx, 3:6, :] @ v == body_com_ang_vel_w[:, body_idx]
"""
raise NotImplementedError(f"{type(self).__name__} does not implement body_com_jacobian_w.")

@property
def mass_matrix(self) -> ProxyArray:
"""Per-env generalized mass matrix ``M(q)`` in joint space.

Shape: ``(num_instances, num_joints + num_base_dofs, num_joints + num_base_dofs)``,
dtype ``wp.float32`` [kg·m² or kg, per DoF type]. DoF-axis convention matches
:attr:`body_link_jacobian_w`.

``M(q)`` is symmetric positive-definite. ``M[i, j]`` is the coefficient
relating DoF ``j``'s acceleration to the inertial torque on DoF ``i`` in
``M(q) q_ddot + C(q, q_dot) q_dot + g(q) = tau``.
"""
raise NotImplementedError(f"{type(self).__name__} does not implement mass_matrix.")

@property
def gravity_compensation_forces(self) -> ProxyArray:
"""Per-env gravity compensation torques ``g(q)`` in joint space.

Shape: ``(num_instances, num_joints + num_base_dofs)``, dtype ``wp.float32``
[N·m or N, per DoF type]. DoF-axis convention matches
:attr:`body_link_jacobian_w`.

``g(q)`` is the gravity-loading term in
``M(q) q_ddot + C(q, q_dot) q_dot + g(q) = tau``. Applying ``tau = g(q)`` at
``q_dot = 0`` with no external load yields ``q_ddot = 0`` (static equilibrium
under gravity).
"""
raise NotImplementedError(f"{type(self).__name__} does not implement gravity_compensation_forces.")

##
# Joint state properties.
##
Expand Down
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why is the gravity comp mixed into this PR?

Copy link
Copy Markdown
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just to unify the API to provide it in a backend agnostic way if newton side has plan to provide it in the physx way. Can be removed if there's no such plan

Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
from typing import TYPE_CHECKING

import torch
import warp as wp
from pink.tasks import FrameTask

import isaaclab.utils.math as math_utils
Expand Down Expand Up @@ -60,9 +59,6 @@ def __init__(self, cfg: pink_actions_cfg.PinkInverseKinematicsActionCfg, env: Ma
self._raw_actions = torch.zeros(self.num_envs, self.action_dim, device=self.device)
self._processed_actions = torch.zeros_like(self._raw_actions)

# PhysX Articulation Floating joint indices offset from IsaacLab Articulation joint indices
self._physx_floating_joint_indices_offset = 6

# Pre-allocate tensors for runtime use
self._initialize_helper_tensors()

Expand Down Expand Up @@ -324,20 +320,24 @@ def apply_actions(self) -> None:
)

def _apply_gravity_compensation(self) -> None:
"""Apply gravity compensation to arm joints if not disabled in props."""
"""Apply gravity compensation to arm joints if not disabled in props.

Reads :attr:`~isaaclab.assets.BaseArticulationData.gravity_compensation_forces`,
which raises :class:`NotImplementedError` on the Newton backend (no upstream
primitive). That is intentional — if a user opts into gravity compensation on
Newton via ``enable_gravity_compensation=True``, they should see a loud failure
rather than silently receive zeros. To use Pink IK on Newton, keep
``enable_gravity_compensation=False``.
"""
if not self._asset.cfg.spawn.rigid_props.disable_gravity:
# Get gravity compensation forces using cached tensor
# ``gravity_compensation_forces`` shape is ``(N, num_joints + num_base_dofs)``.
# Shift actuated-joint ids by ``num_base_dofs`` to skip the leading floating-
# base columns (0 for fixed-base, 6 for floating-base).
jacobi_ids = self._controlled_joint_ids_tensor + self._asset.num_base_dofs
if self._asset.is_fixed_base:
gravity = torch.zeros_like(
wp.to_torch(self._asset.root_view.get_gravity_compensation_forces())[
:, self._controlled_joint_ids_tensor
]
)
gravity = torch.zeros_like(self._asset.data.gravity_compensation_forces.torch[:, jacobi_ids])
else:
# If floating base, then need to skip the first 6 joints (base)
gravity = wp.to_torch(self._asset.root_view.get_gravity_compensation_forces())[
:, self._controlled_joint_ids_tensor + self._physx_floating_joint_indices_offset
]
gravity = self._asset.data.gravity_compensation_forces.torch[:, jacobi_ids]

# Apply gravity compensation to arm joints
self._asset.set_joint_effort_target_index(target=gravity, joint_ids=self._controlled_joint_ids)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
from typing import TYPE_CHECKING

import torch
import warp as wp

import isaaclab.utils.math as math_utils
import isaaclab.utils.string as string_utils
Expand Down Expand Up @@ -56,15 +55,8 @@ def __init__(self, cfg: rmpflow_actions_cfg.RMPFlowActionCfg, env: ManagerBasedE
self._body_idx = body_ids[0]
self._body_name = body_names[0]

# check if articulation is fixed-base
# if fixed-base then the jacobian for the base is not computed
# this means that number of bodies is one less than the articulation's number of bodies
if self._asset.is_fixed_base:
self._jacobi_body_idx = self._body_idx - 1
self._jacobi_joint_ids = self._joint_ids
else:
self._jacobi_body_idx = self._body_idx
self._jacobi_joint_ids = [i + 6 for i in self._joint_ids]
self._jacobi_body_idx = self._body_idx - 1 if self._asset.is_fixed_base else self._body_idx
self._jacobi_joint_ids = [j + self._asset.num_base_dofs for j in self._joint_ids]

# log info for debugging
logger.info(
Expand Down Expand Up @@ -128,7 +120,7 @@ def processed_actions(self) -> torch.Tensor:

@property
def jacobian_w(self) -> torch.Tensor:
return wp.to_torch(self._asset.root_view.get_jacobians())[:, self._jacobi_body_idx, :, self._jacobi_joint_ids]
return self._asset.data.body_link_jacobian_w.torch[:, self._jacobi_body_idx, :, self._jacobi_joint_ids]

@property
def jacobian_b(self) -> torch.Tensor:
Expand Down
Loading
Loading