-
Notifications
You must be signed in to change notification settings - Fork 2.6k
Adds automatic transform discovery for imu sensors to a viable parent body. #3864
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: main
Are you sure you want to change the base?
Changes from 2 commits
d17f69d
f6d97ce
e260d86
dca38bf
4239681
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,6 +1,14 @@ | ||
| Changelog | ||
| --------- | ||
|
|
||
| 0.48.2 (2025-10-22) | ||
| ~~~~~~~~~~~~~~~~~~~ | ||
|
|
||
| Changed | ||
| ^^^^^^^ | ||
|
|
||
| * Implement ability to attach an imu sensor to xform primitives in a usd file. This PR is based on work by @GiulioRomualdi here: #3094 Addressing issue #3088. | ||
|
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. style: consider using the |
||
|
|
||
| 0.47.2 (2025-10-22) | ||
| ~~~~~~~~~~~~~~~~~~~ | ||
|
|
||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -11,11 +11,11 @@ | |
|
|
||
| import isaacsim.core.utils.stage as stage_utils | ||
| from isaacsim.core.simulation_manager import SimulationManager | ||
| from pxr import UsdPhysics | ||
|
|
||
| import isaaclab.sim as sim_utils | ||
| import isaaclab.utils.math as math_utils | ||
| from isaaclab.markers import VisualizationMarkers | ||
| from isaaclab.sim.utils import resolve_pose_relative_to_physx_parent | ||
|
|
||
| from ..sensor_base import SensorBase | ||
| from .imu_data import ImuData | ||
|
|
@@ -27,10 +27,12 @@ | |
| class Imu(SensorBase): | ||
| """The Inertia Measurement Unit (IMU) sensor. | ||
|
|
||
| The sensor can be attached to any :class:`RigidObject` or :class:`Articulation` in the scene. The sensor provides complete state information. | ||
| The sensor is primarily used to provide the linear acceleration and angular velocity of the object in the body frame. The sensor also provides | ||
| the position and orientation of the object in the world frame and the angular acceleration and linear velocity in the body frame. The extra | ||
| data outputs are useful for simulating with or comparing against "perfect" state estimation. | ||
| The sensor can be attached to any prim path and produces body-frame linear acceleration and angular velocity, | ||
| along with world-frame pose and body-frame linear and angular accelerations/velocities. | ||
|
|
||
| If the provided path is not a rigid body, the closest rigid-body ancestor is used for simulation queries. | ||
| The fixed transform from that ancestor to the target prim is computed once during initialization and | ||
| composed with the configured sensor offset. | ||
|
|
||
| .. note:: | ||
|
|
||
|
|
@@ -40,10 +42,13 @@ class Imu(SensorBase): | |
|
|
||
| .. note:: | ||
|
|
||
| It is suggested to use the OffsetCfg to define an IMU frame relative to a rigid body prim defined at the root of | ||
| a :class:`RigidObject` or a prim that is defined by a non-fixed joint in an :class:`Articulation` (except for the | ||
| root of a fixed based articulation). The use frames with fixed joints and small mass/inertia to emulate a transform | ||
| relative to a body frame can result in lower performance and accuracy. | ||
| The user can configure the sensor offset in the configuration file. The offset is applied relative to the rigid source prim. | ||
| If the target prim is not a rigid body, the offset is composed with the fixed transform | ||
| from the rigid ancestor to the target prim. The offset is applied in the body frame of the rigid source prim. | ||
| The offset is defined as a position vector and a quaternion rotation, which | ||
| are applied in the order: position, then rotation. The position is applied as a translation | ||
| in the body frame of the rigid source prim, and the rotation is applied as a rotation | ||
| in the body frame of the rigid source prim. | ||
|
|
||
| """ | ||
|
|
||
|
|
@@ -61,6 +66,9 @@ def __init__(self, cfg: ImuCfg): | |
| # Create empty variables for storing output data | ||
| self._data = ImuData() | ||
|
|
||
| # Internal: expression used to build the rigid body view (may be different from cfg.prim_path) | ||
| self._rigid_parent_expr: str | None = None | ||
|
|
||
| def __str__(self) -> str: | ||
| """Returns: A string containing information about the instance.""" | ||
| return ( | ||
|
|
@@ -119,11 +127,9 @@ def update(self, dt: float, force_recompute: bool = False): | |
| def _initialize_impl(self): | ||
| """Initializes the sensor handles and internal buffers. | ||
|
|
||
| This function creates handles and registers the provided data types with the replicator registry to | ||
| be able to access the data from the sensor. It also initializes the internal buffers to store the data. | ||
|
|
||
| Raises: | ||
| RuntimeError: If the imu prim is not a RigidBodyPrim | ||
| - If the target prim path is a rigid body, build the view directly on it. | ||
| - Otherwise find the closest rigid-body ancestor, cache the fixed transform from that ancestor | ||
| to the target prim, and build the view on the ancestor expression. | ||
| """ | ||
| # Initialize parent class | ||
| super()._initialize_impl() | ||
|
|
@@ -133,11 +139,12 @@ def _initialize_impl(self): | |
| prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) | ||
| if prim is None: | ||
| raise RuntimeError(f"Failed to find a prim at path expression: {self.cfg.prim_path}") | ||
| # check if it is a RigidBody Prim | ||
| if prim.HasAPI(UsdPhysics.RigidBodyAPI): | ||
| self._view = self._physics_sim_view.create_rigid_body_view(self.cfg.prim_path.replace(".*", "*")) | ||
| else: | ||
| raise RuntimeError(f"Failed to find a RigidBodyAPI for the prim paths: {self.cfg.prim_path}") | ||
|
|
||
| # Determine rigid source prim and (if needed) the fixed transform from that rigid prim to target prim | ||
| self._rigid_parent_expr, fixed_pos_b, fixed_quat_b = resolve_pose_relative_to_physx_parent(self.cfg.prim_path) | ||
|
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. logic: if |
||
|
|
||
| # Create the rigid body view on the ancestor | ||
| self._view = self._physics_sim_view.create_rigid_body_view(self._rigid_parent_expr) | ||
|
|
||
| # Get world gravity | ||
| gravity = self._physics_sim_view.get_gravity() | ||
|
|
@@ -148,35 +155,53 @@ def _initialize_impl(self): | |
| # Create internal buffers | ||
| self._initialize_buffers_impl() | ||
|
|
||
| # Compose the configured offset with the fixed ancestor->target transform (done once) | ||
| # new_offset = fixed * cfg.offset | ||
| # where composition is: p = p_fixed + R_fixed * p_cfg, q = q_fixed * q_cfg | ||
| if fixed_pos_b is not None and fixed_quat_b is not None: | ||
| # Broadcast fixed transform across instances | ||
| fixed_p = torch.tensor(fixed_pos_b, device=self._device).repeat(self._view.count, 1) | ||
| fixed_q = torch.tensor(fixed_quat_b, device=self._device).repeat(self._view.count, 1) | ||
|
|
||
| cfg_p = self._offset_pos_b.clone() | ||
| cfg_q = self._offset_quat_b.clone() | ||
|
|
||
| composed_p = fixed_p + math_utils.quat_apply(fixed_q, cfg_p) | ||
| composed_q = math_utils.quat_mul(fixed_q, cfg_q) | ||
|
|
||
| self._offset_pos_b = composed_p | ||
| self._offset_quat_b = composed_q | ||
|
Comment on lines
+161
to
+173
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. style: offset composition assumes both fixed transforms are always present together, but the logic doesn't validate that |
||
|
|
||
| def _update_buffers_impl(self, env_ids: Sequence[int]): | ||
| """Fills the buffers of the sensor data.""" | ||
|
|
||
| # default to all sensors | ||
| if len(env_ids) == self._num_envs: | ||
| env_ids = slice(None) | ||
| # obtain the poses of the sensors | ||
| # world pose of the rigid source (ancestor) from the PhysX view | ||
| pos_w, quat_w = self._view.get_transforms()[env_ids].split([3, 4], dim=-1) | ||
| quat_w = quat_w.roll(1, dims=-1) | ||
|
|
||
| # store the poses | ||
| # sensor pose in world: apply composed offset | ||
| self._data.pos_w[env_ids] = pos_w + math_utils.quat_apply(quat_w, self._offset_pos_b[env_ids]) | ||
| self._data.quat_w[env_ids] = math_utils.quat_mul(quat_w, self._offset_quat_b[env_ids]) | ||
|
|
||
| # get the offset from COM to link origin | ||
| # COM of rigid source (body frame) | ||
| com_pos_b = self._view.get_coms().to(self.device).split([3, 4], dim=-1)[0] | ||
|
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. logic: when |
||
|
|
||
| # obtain the velocities of the link COM | ||
| # Velocities at rigid source COM | ||
| lin_vel_w, ang_vel_w = self._view.get_velocities()[env_ids].split([3, 3], dim=-1) | ||
| # if an offset is present or the COM does not agree with the link origin, the linear velocity has to be | ||
| # transformed taking the angular velocity into account | ||
|
|
||
| # If sensor offset or COM != link origin, account for angular velocity contribution | ||
| lin_vel_w += torch.linalg.cross( | ||
| ang_vel_w, math_utils.quat_apply(quat_w, self._offset_pos_b[env_ids] - com_pos_b[env_ids]), dim=-1 | ||
| ) | ||
|
|
||
| # numerical derivative | ||
| # numerical derivative (world frame) | ||
| lin_acc_w = (lin_vel_w - self._prev_lin_vel_w[env_ids]) / self._dt + self._gravity_bias_w[env_ids] | ||
| ang_acc_w = (ang_vel_w - self._prev_ang_vel_w[env_ids]) / self._dt | ||
| # stack data in world frame and batch rotate | ||
|
|
||
| # batch rotate world->body using current sensor orientation | ||
| dynamics_data = torch.stack((lin_vel_w, ang_vel_w, lin_acc_w, ang_acc_w, self.GRAVITY_VEC_W[env_ids]), dim=0) | ||
| dynamics_data_rot = math_utils.quat_apply_inverse(self._data.quat_w[env_ids].repeat(5, 1), dynamics_data).chunk( | ||
| 5, dim=0 | ||
|
|
@@ -207,7 +232,7 @@ def _initialize_buffers_impl(self): | |
| self._prev_lin_vel_w = torch.zeros_like(self._data.pos_w) | ||
| self._prev_ang_vel_w = torch.zeros_like(self._data.pos_w) | ||
|
|
||
| # store sensor offset transformation | ||
| # store sensor offset (applied relative to rigid source). This may be composed later with a fixed ancestor->target transform. | ||
| self._offset_pos_b = torch.tensor(list(self.cfg.offset.pos), device=self._device).repeat(self._view.count, 1) | ||
| self._offset_quat_b = torch.tensor(list(self.cfg.offset.rot), device=self._device).repeat(self._view.count, 1) | ||
| # set gravity bias | ||
|
|
||
| Original file line number | Diff line number | Diff line change | ||||
|---|---|---|---|---|---|---|
|
|
@@ -895,6 +895,87 @@ def find_matching_prim_paths(prim_path_regex: str, stage: Usd.Stage | None = Non | |||||
| return output_prim_paths | ||||||
|
|
||||||
|
|
||||||
| def check_prim_implements_apis( | ||||||
| prim: Usd.Prim, apis: list[Usd.APISchemaBase] | Usd.APISchemaBase = UsdPhysics.RigidBodyAPI | ||||||
| ) -> bool: | ||||||
| """Return true if prim implements all apis, False otherwise.""" | ||||||
|
|
||||||
| if type(apis) is not list: | ||||||
| return prim.HasAPI(apis) | ||||||
| else: | ||||||
| return all(prim.HasAPI(api) for api in apis) | ||||||
|
Comment on lines
+898
to
+906
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. style: using |
||||||
|
|
||||||
|
|
||||||
| def resolve_pose_relative_to_physx_parent( | ||||||
| prim_path_regex: str, | ||||||
| implements_apis: list[Usd.APISchemaBase] | Usd.APISchemaBase = UsdPhysics.RigidBodyAPI, | ||||||
| *, | ||||||
| stage: Usd.Stage() | None = None, | ||||||
|
||||||
| stage: Usd.Stage() | None = None, | |
| stage: Usd.Stage | None = None, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
logic: missing null check: find_first_matching_prim can return None, but code assumes valid prim on line 933
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
logic: when target prim directly implements required APIs, returning None for transforms may break callers expecting valid tuples - should document this behavior or return identity transform ((0, 0, 0), (1, 0, 0, 0)). Should this return identity transform instead of None when no offset is needed, to maintain consistent return type handling?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
syntax: GetPrimPath() returns Sdf.Path, not string. Call .pathString if string is needed, or handle Sdf.Path directly
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
logic: string manipulation assumes prim_path_regex format matches child_path suffix structure - if regex contains complex patterns (e.g., character classes, quantifiers beyond .*), this substring logic may produce incorrect results. What regex patterns are expected in prim_path_regex beyond simple wildcards? Complex patterns like [0-9]+ or (a|b) could break the string trimming logic.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
syntax: typo: 'Implement' should be 'Implemented' to match past tense convention used throughout the CHANGELOG