[docs]classActuatorBase(ABC):"""Base class for actuator models over a collection of actuated joints in an articulation. Actuator models augment the simulated articulation joints with an external drive dynamics model.
@@ -570,7 +570,7 @@
Source code for omni.isaac.lab.actuators.actuator_base
friction:torch.Tensor"""The joint friction of the actuator joints. Shape is (num_envs, num_joints)."""
-
- def__str__(self)->str:
+ def__str__(self)->str:"""Returns: A string representation of the actuator group."""# resolve joint indices for printingjoint_indices=self.joint_indices
@@ -651,17 +651,17 @@
Source code for omni.isaac.lab.actuators.actuator_base
"""
@property
- defnum_joints(self)->int:
+ defnum_joints(self)->int:"""Number of actuators in the group."""returnlen(self._joint_names)@property
- defjoint_names(self)->list[str]:
+ defjoint_names(self)->list[str]:"""Articulation's joint names that are part of the group."""returnself._joint_names@property
- defjoint_indices(self)->slice|Sequence[int]:
+ defjoint_indices(self)->slice|Sequence[int]:"""Articulation's joint indices that are part of the group. Note:
@@ -675,7 +675,7 @@
Source code for omni.isaac.lab.actuators.actuator_base
"""
[docs]@abstractmethod
- defreset(self,env_ids:Sequence[int]):
+ defreset(self,env_ids:Sequence[int]):"""Reset the internals within the group. Args:
@@ -684,7 +684,7 @@
Source code for omni.isaac.lab.actuators.actuator_base
raise NotImplementedError
[docs]@abstractmethod
- defcompute(
+ defcompute(self,control_action:ArticulationActions,joint_pos:torch.Tensor,joint_vel:torch.Tensor)->ArticulationActions:"""Process the actuator group actions and compute the articulation actions.
@@ -706,7 +706,7 @@
Source code for omni.isaac.lab.actuators.actuator_base
Helper functions.
"""
- def_parse_joint_parameter(
+ def_parse_joint_parameter(self,cfg_value:float|dict[str,float]|None,default_value:float|torch.Tensor|None)->torch.Tensor:"""Parse the joint parameter from the configuration.
@@ -766,7 +766,7 @@
Source code for omni.isaac.lab.actuators.actuator_base
return param
- def_clip_effort(self,effort:torch.Tensor)->torch.Tensor:
+ def_clip_effort(self,effort:torch.Tensor)->torch.Tensor:"""Clip the desired torques based on the motor limits. Args:
@@ -823,7 +823,7 @@
Source code for omni.isaac.lab.actuators.actuator_base
- Last updated on Jan 03, 2025.
+ Last updated on Jan 07, 2025.
[docs]@configclass
-classActuatorBaseCfg:
+classActuatorBaseCfg:"""Configuration for default actuators in an articulation."""class_type:type[ActuatorBase]=MISSING
@@ -591,7 +591,7 @@
Source code for omni.isaac.lab.actuators.actuator_cfg
[docs]@configclass
-classImplicitActuatorCfg(ActuatorBaseCfg):
+classImplicitActuatorCfg(ActuatorBaseCfg):"""Configuration for an implicit actuator. Note:
@@ -607,14 +607,14 @@
Source code for omni.isaac.lab.actuators.actuator_cfg
[docs]@configclass
-classIdealPDActuatorCfg(ActuatorBaseCfg):
+classIdealPDActuatorCfg(ActuatorBaseCfg):"""Configuration for an ideal PD actuator."""class_type:type=actuator_pd.IdealPDActuator
[docs]@configclass
-classDCMotorCfg(IdealPDActuatorCfg):
+classDCMotorCfg(IdealPDActuatorCfg):"""Configuration for direct control (DC) motor actuator model."""class_type:type=actuator_pd.DCMotor
@@ -624,7 +624,7 @@
Source code for omni.isaac.lab.actuators.actuator_cfg
[docs]classActuatorNetLSTM(DCMotor):"""Actuator model based on recurrent neural network (LSTM). Unlike the MLP implementation :cite:t:`hwangbo2019learning`, this class implements
@@ -559,7 +559,7 @@
Source code for omni.isaac.lab.actuators.actuator_net
cfg:ActuatorNetLSTMCfg"""The configuration of the actuator model."""
-
[docs]defreset(self,env_ids:Sequence[int]):# reset the hidden and cell states for the specified environmentswithtorch.no_grad():self.sea_hidden_state_per_env[:,env_ids]=0.0self.sea_cell_state_per_env[:,env_ids]=0.0
[docs]classActuatorNetMLP(DCMotor):"""Actuator model based on multi-layer perceptron and joint history. Many times the analytical model is not sufficient to capture the actuator dynamics, the
@@ -638,7 +638,7 @@
Source code for omni.isaac.lab.actuators.actuator_net
cfg:ActuatorNetMLPCfg"""The configuration of the actuator model."""
-
[docs]defreset(self,env_ids:Sequence[int]):# reset the history for the specified environmentsself._joint_pos_error_history[env_ids]=0.0self._joint_vel_history[env_ids]=0.0
[docs]defcompute(self,control_action:ArticulationActions,joint_pos:torch.Tensor,joint_vel:torch.Tensor)->ArticulationActions:# move history queue by 1 and update top of history
@@ -750,7 +750,7 @@
Source code for omni.isaac.lab.actuators.actuator_net
- Last updated on Jan 03, 2025.
+ Last updated on Jan 07, 2025.
[docs]classImplicitActuator(ActuatorBase):"""Implicit actuator model that is handled by the simulation. This performs a similar function as the :class:`IdealPDActuator` class. However, the PD control is handled
@@ -572,11 +572,11 @@
Source code for omni.isaac.lab.actuators.actuator_pd
[docs]defcompute(self,control_action:ArticulationActions,joint_pos:torch.Tensor,joint_vel:torch.Tensor)->ArticulationActions:"""Process the actuator group actions and compute the articulation actions.
@@ -609,7 +609,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
[docs]classIdealPDActuator(ActuatorBase):r"""Ideal torque-controlled actuator model with a simple saturation model. It employs the following model for computing torques for the actuated joint :math:`j`:
@@ -642,10 +642,10 @@
Source code for omni.isaac.lab.actuators.actuator_pd
[docs]classDCMotor(IdealPDActuator):r"""Direct control (DC) motor actuator model with velocity-based saturation model. It uses the same model as the :class:`IdealActuator` for computing the torques from input commands.
@@ -706,7 +706,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
cfg:DCMotorCfg"""The configuration for the actuator model."""
-
[docs]defcompute(self,control_action:ArticulationActions,joint_pos:torch.Tensor,joint_vel:torch.Tensor)->ArticulationActions:# save current joint vel
@@ -737,7 +737,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
[docs]classDelayedPDActuator(IdealPDActuator):"""Ideal PD actuator with delayed command application. This class extends the :class:`IdealPDActuator` class by adding a delay to the actuator commands. The delay
@@ -766,7 +766,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
cfg:DelayedPDActuatorCfg"""The configuration for the actuator model."""
-
[docs]defreset(self,env_ids:Sequence[int]):super().reset(env_ids)# number of environments (since env_ids can be a slice)ifenv_idsisNoneorenv_ids==slice(None):
@@ -799,7 +799,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
[docs]defcompute(self,control_action:ArticulationActions,joint_pos:torch.Tensor,joint_vel:torch.Tensor)->ArticulationActions:# apply delay based on the delay the model for all the setpoints
@@ -810,7 +810,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
[docs]classRemotizedPDActuator(DelayedPDActuator):"""Ideal PD actuator with angle-dependent torque limits. This class extends the :class:`DelayedPDActuator` class by adding angle-dependent torque limits to the actuator.
@@ -820,7 +820,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
The torque limits are interpolated based on the current joint positions and applied to the actuator commands.
"""
-
[docs]defcompute(self,control_action:ArticulationActions,joint_pos:torch.Tensor,joint_vel:torch.Tensor)->ArticulationActions:# call the base method
@@ -925,7 +925,7 @@
Source code for omni.isaac.lab.actuators.actuator_pd
- Last updated on Jan 03, 2025.
+ Last updated on Jan 07, 2025.
[docs]classAppLauncher:"""A utility class to launch Isaac Sim application based on command-line arguments and environment variables. The class resolves the simulation app settings that appear through environments variables,
@@ -563,7 +563,7 @@
[docs]def__init__(self,launcher_args:argparse.Namespace|dict|None=None,**kwargs):"""Create a `SimulationApp`_ instance based on the input settings. Args:
@@ -647,7 +647,7 @@
[docs]@staticmethod
- defadd_app_launcher_args(parser:argparse.ArgumentParser)->None:
+ defadd_app_launcher_args(parser:argparse.ArgumentParser)->None:"""Utility function to configure AppLauncher arguments with an existing argument parser object. This function takes an ``argparse.ArgumentParser`` object and does some sanity checking on the existing
@@ -863,7 +863,7 @@
Source code for omni.isaac.lab.app.app_launcher
<
"""@staticmethod
- def_check_argparser_config_params(config:dict)->None:
+ def_check_argparser_config_params(config:dict)->None:"""Checks that input argparser object has parameters with valid settings with no name conflicts. First, we inspect the dictionary to ensure that the passed ArgParser object is not attempting to add arguments
@@ -906,7 +906,7 @@
Source code for omni.isaac.lab.app.app_launcher
<
# Print out values which will be usedprint(f"[INFO][AppLauncher]: The argument '{key}' will be used to configure the SimulationApp.")
- def_config_resolution(self,launcher_args:dict):
+ def_config_resolution(self,launcher_args:dict):"""Resolve the input arguments and environment variables. Args:
@@ -1102,7 +1102,7 @@
Source code for omni.isaac.lab.app.app_launcher
<
key:launcher_args[key]forkeyinset(AppLauncher._SIM_APP_CFG_TYPES.keys())&set(launcher_args.keys())}
- def_create_app(self):
+ def_create_app(self):"""Launch and create the SimulationApp based on the parsed simulation config."""# Initialize SimulationApp# hack sys module to make sure that the SimulationApp is initialized correctly
@@ -1135,18 +1135,18 @@
Source code for omni.isaac.lab.app.app_launcher
<
iflen(self._kit_args)>0:sys.argv=[argforarginsys.argvifargnotinself._kit_args]
- def_rendering_enabled(self)->bool:
+ def_rendering_enabled(self)->bool:"""Check if rendering is required by the app."""# Indicates whether rendering is required by the app.# Extensions required for rendering bring startup and simulation costs, so we do not enable them if not required.returnnotself._headlessorself._livestream>=1orself._enable_cameras
- def_load_extensions(self):
+ def_load_extensions(self):"""Load correct extensions based on AppLauncher's resolved config member variables."""# These have to be loaded after SimulationApp is initialized
- importcarb
- importomni.physx.bindings._physxasphysx_impl
- fromomni.isaac.core.utils.extensionsimportenable_extension
+ importcarb
+ importomni.physx.bindings._physxasphysx_impl
+ fromomni.isaac.core.utils.extensionsimportenable_extension# Retrieve carb settings for modificationcarb_settings_iface=carb.settings.get_settings()
@@ -1205,7 +1205,7 @@
Source code for omni.isaac.lab.app.app_launcher
<
# disable physics backwards compatibility checkcarb_settings_iface.set_int(physx_impl.SETTING_BACKWARD_COMPATIBILITY,0)
- def_hide_stop_button(self):
+ def_hide_stop_button(self):"""Hide the stop button in the toolbar. For standalone executions, having a stop button is confusing since it invalidates the whole simulation.
@@ -1214,7 +1214,7 @@
Source code for omni.isaac.lab.app.app_launcher
<
# when we are truly headless, then we can't import the widget toolbar# thus, we only hide the stop button when we are not headless (i.e. GUI is enabled)ifself._livestream>=1ornotself._headless:
- importomni.kit.widget.toolbar
+ importomni.kit.widget.toolbar# grey out the stop button because we don't want to stop the simulation manually in standalone modetoolbar=omni.kit.widget.toolbar.get_instance()
@@ -1224,14 +1224,14 @@
Source code for omni.isaac.lab.app.app_launcher
<
play_button_group._stop_button.enabled=False# type: ignoreplay_button_group._stop_button=None# type: ignore
- def_interrupt_signal_handle_callback(self,signal,frame):
+ def_interrupt_signal_handle_callback(self,signal,frame):"""Handle the interrupt signal from the keyboard."""# close the appself._app.close()# raise the error for keyboard interruptraiseKeyboardInterrupt
- def_abort_signal_handle_callback(self,signal,frame):
+ def_abort_signal_handle_callback(self,signal,frame):"""Handle the abort/segmentation/kill signals."""# close the appself._app.close()
[docs]classArticulation(AssetBase):"""An articulation asset class. An articulation is a collection of rigid bodies connected by joints. The joints can be either
@@ -607,7 +607,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
attribute. They are used to compute the joint commands during the :meth:`write_data_to_sim` function.
"""
-
[docs]def__init__(self,cfg:ArticulationCfg):"""Initialize the articulation. Args:
@@ -624,50 +624,50 @@
Source code for omni.isaac.lab.assets.articulation.articulation
"""
@property
- defdata(self)->ArticulationData:
+ defdata(self)->ArticulationData:returnself._data@property
- defnum_instances(self)->int:
+ defnum_instances(self)->int:returnself.root_physx_view.count@property
- defis_fixed_base(self)->bool:
+ defis_fixed_base(self)->bool:"""Whether the articulation is a fixed-base or floating-base system."""returnself.root_physx_view.shared_metatype.fixed_base@property
- defnum_joints(self)->int:
+ defnum_joints(self)->int:"""Number of joints in articulation."""returnself.root_physx_view.shared_metatype.dof_count@property
- defnum_fixed_tendons(self)->int:
+ defnum_fixed_tendons(self)->int:"""Number of fixed tendons in articulation."""returnself.root_physx_view.max_fixed_tendons@property
- defnum_bodies(self)->int:
+ defnum_bodies(self)->int:"""Number of bodies in articulation."""returnself.root_physx_view.shared_metatype.link_count@property
- defjoint_names(self)->list[str]:
+ defjoint_names(self)->list[str]:"""Ordered names of joints in articulation."""returnself.root_physx_view.shared_metatype.dof_names@property
- deffixed_tendon_names(self)->list[str]:
+ deffixed_tendon_names(self)->list[str]:"""Ordered names of fixed tendons in articulation."""returnself._fixed_tendon_names@property
- defbody_names(self)->list[str]:
+ defbody_names(self)->list[str]:"""Ordered names of bodies in articulation."""returnself.root_physx_view.shared_metatype.link_names@property
- defroot_physx_view(self)->physx.ArticulationView:
+ defroot_physx_view(self)->physx.ArticulationView:"""Articulation view for the asset (PhysX). Note:
@@ -679,7 +679,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_data_to_sim(self):"""Write external wrenches and joint commands to the simulation. If any explicit actuators are present, then the actuator models are used to compute the
@@ -719,14 +719,14 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]deffind_bodies(self,name_keys:str|Sequence[str],preserve_order:bool=False)->tuple[list[int],list[str]]:"""Find bodies in the articulation based on the name keys. Please check the :meth:`omni.isaac.lab.utils.string_utils.resolve_matching_names` function for more
@@ -741,7 +741,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]deffind_joints(self,name_keys:str|Sequence[str],joint_subset:list[str]|None=None,preserve_order:bool=False)->tuple[list[int],list[str]]:"""Find joints in the articulation based on the name keys.
@@ -763,7 +763,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]deffind_fixed_tendons(self,name_keys:str|Sequence[str],tendon_subsets:list[str]|None=None,preserve_order:bool=False)->tuple[list[int],list[str]]:"""Find fixed tendons in the articulation based on the name keys.
@@ -791,7 +791,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_root_state_to_sim(self,root_state:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root state over selected environment indices into the simulation. The root state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear
@@ -814,7 +814,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_root_com_state_to_sim(self,root_state:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root center of mass state over selected environment indices into the simulation. The root state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear
@@ -828,7 +828,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_root_link_state_to_sim(self,root_state:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root link state over selected environment indices into the simulation. The root state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear
@@ -842,7 +842,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_root_pose_to_sim(self,root_pose:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root pose over selected environment indices into the simulation. The root pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).
@@ -861,7 +861,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_root_link_pose_to_sim(self,root_pose:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root link pose over selected environment indices into the simulation. The root pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).
@@ -891,7 +891,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
# set into simulation
self.root_physx_view.set_root_transforms(root_poses_xyzw,indices=physx_env_ids)
[docs]defwrite_root_com_pose_to_sim(self,root_pose:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root center of mass pose over selected environment indices into the simulation. The root pose comprises of the cartesian position and quaternion orientation in (w, x, y, z).
@@ -918,7 +918,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_root_velocity_to_sim(self,root_velocity:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root center of mass velocity over selected environment indices into the simulation. The velocity comprises linear velocity (x, y, z) and angular velocity (x, y, z) in that order.
@@ -938,7 +938,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]defwrite_root_com_velocity_to_sim(self,root_velocity:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root center of mass velocity over selected environment indices into the simulation. The velocity comprises linear velocity (x, y, z) and angular velocity (x, y, z) in that order.
@@ -964,7 +964,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
# set into simulation
self.root_physx_view.set_root_velocities(self._data.root_com_state_w[:,7:],indices=physx_env_ids)
[docs]defwrite_root_link_velocity_to_sim(self,root_velocity:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the root link velocity over selected environment indices into the simulation. The velocity comprises linear velocity (x, y, z) and angular velocity (x, y, z) in that order.
@@ -988,7 +988,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
# write center of mass velocity to sim
self.write_root_com_velocity_to_sim(root_velocity=root_com_velocity,env_ids=env_ids)
Source code for omni.isaac.lab.assets.articulation.articulation
f" joints available: {total_act_joints} != {self.num_joints-self.num_fixed_tendons}.")
- def_process_fixed_tendons(self):
+ def_process_fixed_tendons(self):"""Process fixed tendons."""# create a list to store the fixed tendon namesself._fixed_tendon_names=list()
@@ -1906,7 +1906,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
self._data.default_fixed_tendon_rest_length=self.root_physx_view.get_fixed_tendon_rest_lengths().clone()self._data.default_fixed_tendon_offset=self.root_physx_view.get_fixed_tendon_offsets().clone()
- def_apply_actuator_model(self):
+ def_apply_actuator_model(self):"""Processes joint commands for the articulation by forwarding them to the actuators. The actions are first processed using actuator models. Depending on the robot configuration,
@@ -1949,7 +1949,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
Internal helpers -- Debugging.
"""
- def_validate_cfg(self):
+ def_validate_cfg(self):"""Validate the configuration after processing. Note:
@@ -1989,7 +1989,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
msg +=f"\t- '{joint_name}': {joint_vel:.3f} not in [{joint_limits[0]:.3f}, {joint_limits[1]:.3f}]\n"raiseValueError(msg)
- def_log_articulation_joint_info(self):
+ def_log_articulation_joint_info(self):"""Log information about the articulation's simulated joints."""# read out all joint parameters from simulation# -- gains
@@ -2116,7 +2116,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation
[docs]@configclass
-classArticulationCfg(AssetBaseCfg):
+classArticulationCfg(AssetBaseCfg):"""Configuration parameters for an articulation."""
[docs]@configclass
- classInitialStateCfg(AssetBaseCfg.InitialStateCfg):
+ classInitialStateCfg(AssetBaseCfg.InitialStateCfg):"""Initial state of the articulation."""# root velocity
@@ -614,7 +614,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_cfg
[docs]classArticulationData:"""Data container for an articulation. This class contains the data for an articulation in the simulation. The data includes the state of
@@ -548,7 +548,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
can be interpreted as the link frame.
"""
- def__init__(self,root_physx_view:physx.ArticulationView,device:str):
+ def__init__(self,root_physx_view:physx.ArticulationView,device:str):"""Initializes the articulation data. Args:
@@ -597,7 +597,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
self._body_state_dep_warn=Falseself._ignore_dep_warn=False
- defupdate(self,dt:float):
+ defupdate(self,dt:float):# update the simulation timestampself._sim_timestamp+=dt# Trigger an update of the joint acceleration buffer at a higher frequency
@@ -784,7 +784,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
##
@property
- defroot_state_w(self):
+ defroot_state_w(self):"""Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13). The position and quaternion are of the articulation root's actor frame relative to the world. Meanwhile,
@@ -809,7 +809,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._root_state_w.data@property
- defroot_link_state_w(self):
+ defroot_link_state_w(self):"""Root state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13). The position, quaternion, and linear/angular velocity are of the articulation root's actor frame relative to the
@@ -832,7 +832,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._root_link_state_w.data@property
- defroot_com_state_w(self):
+ defroot_com_state_w(self):"""Root center of mass state ``[pos, quat, lin_vel, ang_vel]`` in simulation world frame. Shape is (num_instances, 13). The position, quaternion, and linear/angular velocity are of the articulation root link's center of mass frame
@@ -856,7 +856,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._root_com_state_w.data@property
- defbody_state_w(self):
+ defbody_state_w(self):"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame. Shape is (num_instances, num_bodies, 13).
@@ -883,7 +883,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._body_state_w.data@property
- defbody_link_state_w(self):
+ defbody_link_state_w(self):"""State of all bodies' link frame`[pos, quat, lin_vel, ang_vel]` in simulation world frame. Shape is (num_instances, num_bodies, 13).
@@ -907,7 +907,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._body_link_state_w.data@property
- defbody_com_state_w(self):
+ defbody_com_state_w(self):"""State of all bodies center of mass `[pos, quat, lin_vel, ang_vel]` in simulation world frame. Shape is (num_instances, num_bodies, 13).
@@ -933,7 +933,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._body_com_state_w.data@property
- defbody_acc_w(self):
+ defbody_acc_w(self):"""Acceleration of all bodies (center of mass). Shape is (num_instances, num_bodies, 6). All values are relative to the world.
@@ -946,12 +946,12 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._body_acc_w.data@property
- defprojected_gravity_b(self):
+ defprojected_gravity_b(self):"""Projection of the gravity direction on base frame. Shape is (num_instances, 3)."""returnmath_utils.quat_rotate_inverse(self.root_link_quat_w,self.GRAVITY_VEC_W)@property
- defheading_w(self):
+ defheading_w(self):"""Yaw heading of the base frame (in radians). Shape is (num_instances,). Note:
@@ -962,7 +962,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return torch.atan2(forward_w[:,1],forward_w[:,0])@property
- defjoint_pos(self):
+ defjoint_pos(self):"""Joint positions of all joints. Shape is (num_instances, num_joints)."""ifself._joint_pos.timestamp<self._sim_timestamp:# read data from simulation and set the buffer data and timestamp
@@ -971,7 +971,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._joint_pos.data@property
- defjoint_vel(self):
+ defjoint_vel(self):"""Joint velocities of all joints. Shape is (num_instances, num_joints)."""ifself._joint_vel.timestamp<self._sim_timestamp:# read data from simulation and set the buffer data and timestamp
@@ -980,7 +980,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._joint_vel.data@property
- defjoint_acc(self):
+ defjoint_acc(self):"""Joint acceleration of all joints. Shape is (num_instances, num_joints)."""ifself._joint_acc.timestamp<self._sim_timestamp:# note: we use finite differencing to compute acceleration
@@ -996,7 +996,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
##
@property
- defroot_pos_w(self)->torch.Tensor:
+ defroot_pos_w(self)->torch.Tensor:"""Root position in simulation world frame. Shape is (num_instances, 3). This quantity is the position of the actor frame of the articulation root relative to the world.
@@ -1004,7 +1004,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_state_w[:,:3]@property
- defroot_quat_w(self)->torch.Tensor:
+ defroot_quat_w(self)->torch.Tensor:"""Root orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4). This quantity is the orientation of the actor frame of the articulation root relative to the world.
@@ -1012,7 +1012,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_state_w[:,3:7]@property
- defroot_vel_w(self)->torch.Tensor:
+ defroot_vel_w(self)->torch.Tensor:"""Root velocity in simulation world frame. Shape is (num_instances, 6). This quantity contains the linear and angular velocities of the articulation root's center of mass frame
@@ -1021,7 +1021,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_state_w[:,7:13]@property
- defroot_lin_vel_w(self)->torch.Tensor:
+ defroot_lin_vel_w(self)->torch.Tensor:"""Root linear velocity in simulation world frame. Shape is (num_instances, 3). This quantity is the linear velocity of the articulation root's center of mass frame relative to the world.
@@ -1029,7 +1029,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_state_w[:,7:10]@property
- defroot_ang_vel_w(self)->torch.Tensor:
+ defroot_ang_vel_w(self)->torch.Tensor:"""Root angular velocity in simulation world frame. Shape is (num_instances, 3). This quantity is the angular velocity of the articulation root's center of mass frame relative to the world.
@@ -1037,7 +1037,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_state_w[:,10:13]@property
- defroot_lin_vel_b(self)->torch.Tensor:
+ defroot_lin_vel_b(self)->torch.Tensor:"""Root linear velocity in base frame. Shape is (num_instances, 3). This quantity is the linear velocity of the articulation root's center of mass frame relative to the world
@@ -1046,7 +1046,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return math_utils.quat_rotate_inverse(self.root_quat_w,self.root_lin_vel_w)@property
- defroot_ang_vel_b(self)->torch.Tensor:
+ defroot_ang_vel_b(self)->torch.Tensor:"""Root angular velocity in base world frame. Shape is (num_instances, 3). This quantity is the angular velocity of the articulation root's center of mass frame relative to the world with
@@ -1059,7 +1059,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
#
@property
- defroot_link_pos_w(self)->torch.Tensor:
+ defroot_link_pos_w(self)->torch.Tensor:"""Root link position in simulation world frame. Shape is (num_instances, 3). This quantity is the position of the actor frame of the root rigid body relative to the world.
@@ -1071,7 +1071,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_link_state_w[:,:3]@property
- defroot_link_quat_w(self)->torch.Tensor:
+ defroot_link_quat_w(self)->torch.Tensor:"""Root link orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4). This quantity is the orientation of the actor frame of the root rigid body.
@@ -1084,7 +1084,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_link_state_w[:,3:7]@property
- defroot_link_vel_w(self)->torch.Tensor:
+ defroot_link_vel_w(self)->torch.Tensor:"""Root link velocity in simulation world frame. Shape is (num_instances, 6). This quantity contains the linear and angular velocities of the actor frame of the root
@@ -1093,7 +1093,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_link_state_w[:,7:13]@property
- defroot_link_lin_vel_w(self)->torch.Tensor:
+ defroot_link_lin_vel_w(self)->torch.Tensor:"""Root linear velocity in simulation world frame. Shape is (num_instances, 3). This quantity is the linear velocity of the root rigid body's actor frame relative to the world.
@@ -1101,7 +1101,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_link_state_w[:,7:10]@property
- defroot_link_ang_vel_w(self)->torch.Tensor:
+ defroot_link_ang_vel_w(self)->torch.Tensor:"""Root link angular velocity in simulation world frame. Shape is (num_instances, 3). This quantity is the angular velocity of the actor frame of the root rigid body relative to the world.
@@ -1109,7 +1109,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_link_state_w[:,10:13]@property
- defroot_link_lin_vel_b(self)->torch.Tensor:
+ defroot_link_lin_vel_b(self)->torch.Tensor:"""Root link linear velocity in base frame. Shape is (num_instances, 3). This quantity is the linear velocity of the actor frame of the root rigid body frame with respect to the
@@ -1118,7 +1118,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return math_utils.quat_rotate_inverse(self.root_link_quat_w,self.root_link_lin_vel_w)@property
- defroot_link_ang_vel_b(self)->torch.Tensor:
+ defroot_link_ang_vel_b(self)->torch.Tensor:"""Root link angular velocity in base world frame. Shape is (num_instances, 3). This quantity is the angular velocity of the actor frame of the root rigid body frame with respect to the
@@ -1131,7 +1131,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
#
@property
- defroot_com_pos_w(self)->torch.Tensor:
+ defroot_com_pos_w(self)->torch.Tensor:"""Root center of mass position in simulation world frame. Shape is (num_instances, 3). This quantity is the position of the actor frame of the root rigid body relative to the world.
@@ -1139,7 +1139,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_com_state_w[:,:3]@property
- defroot_com_quat_w(self)->torch.Tensor:
+ defroot_com_quat_w(self)->torch.Tensor:"""Root center of mass orientation (w, x, y, z) in simulation world frame. Shape is (num_instances, 4). This quantity is the orientation of the actor frame of the root rigid body relative to the world.
@@ -1147,7 +1147,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_com_state_w[:,3:7]@property
- defroot_com_vel_w(self)->torch.Tensor:
+ defroot_com_vel_w(self)->torch.Tensor:"""Root center of mass velocity in simulation world frame. Shape is (num_instances, 6). This quantity contains the linear and angular velocities of the root rigid body's center of mass frame relative to the world.
@@ -1159,7 +1159,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_com_state_w[:,7:13]@property
- defroot_com_lin_vel_w(self)->torch.Tensor:
+ defroot_com_lin_vel_w(self)->torch.Tensor:"""Root center of mass linear velocity in simulation world frame. Shape is (num_instances, 3). This quantity is the linear velocity of the root rigid body's center of mass frame relative to the world.
@@ -1171,7 +1171,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_com_state_w[:,7:10]@property
- defroot_com_ang_vel_w(self)->torch.Tensor:
+ defroot_com_ang_vel_w(self)->torch.Tensor:"""Root center of mass angular velocity in simulation world frame. Shape is (num_instances, 3). This quantity is the angular velocity of the root rigid body's center of mass frame relative to the world.
@@ -1184,7 +1184,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.root_com_state_w[:,10:13]@property
- defroot_com_lin_vel_b(self)->torch.Tensor:
+ defroot_com_lin_vel_b(self)->torch.Tensor:"""Root center of mass linear velocity in base frame. Shape is (num_instances, 3). This quantity is the linear velocity of the root rigid body's center of mass frame with respect to the
@@ -1193,7 +1193,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return math_utils.quat_rotate_inverse(self.root_link_quat_w,self.root_com_lin_vel_w)@property
- defroot_com_ang_vel_b(self)->torch.Tensor:
+ defroot_com_ang_vel_b(self)->torch.Tensor:"""Root center of mass angular velocity in base world frame. Shape is (num_instances, 3). This quantity is the angular velocity of the root rigid body's center of mass frame with respect to the
@@ -1202,7 +1202,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return math_utils.quat_rotate_inverse(self.root_link_quat_w,self.root_com_ang_vel_w)@property
- defbody_pos_w(self)->torch.Tensor:
+ defbody_pos_w(self)->torch.Tensor:"""Positions of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3). This quantity is the position of the rigid bodies' actor frame relative to the world.
@@ -1210,7 +1210,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_state_w[...,:3]@property
- defbody_quat_w(self)->torch.Tensor:
+ defbody_quat_w(self)->torch.Tensor:"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 4). This quantity is the orientation of the rigid bodies' actor frame relative to the world.
@@ -1218,7 +1218,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_state_w[...,3:7]@property
- defbody_vel_w(self)->torch.Tensor:
+ defbody_vel_w(self)->torch.Tensor:"""Velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 6). This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame relative
@@ -1227,7 +1227,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_state_w[...,7:13]@property
- defbody_lin_vel_w(self)->torch.Tensor:
+ defbody_lin_vel_w(self)->torch.Tensor:"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3). This quantity is the linear velocity of the rigid bodies' center of mass frame relative to the world.
@@ -1235,7 +1235,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_state_w[...,7:10]@property
- defbody_ang_vel_w(self)->torch.Tensor:
+ defbody_ang_vel_w(self)->torch.Tensor:"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3). This quantity is the angular velocity of the rigid bodies' center of mass frame relative to the world.
@@ -1243,7 +1243,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_state_w[...,10:13]@property
- defbody_lin_acc_w(self)->torch.Tensor:
+ defbody_lin_acc_w(self)->torch.Tensor:"""Linear acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3). This quantity is the linear acceleration of the rigid bodies' center of mass frame relative to the world.
@@ -1251,7 +1251,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_acc_w[...,0:3]@property
- defbody_ang_acc_w(self)->torch.Tensor:
+ defbody_ang_acc_w(self)->torch.Tensor:"""Angular acceleration of all bodies in simulation world frame. Shape is (num_instances, num_bodies, 3). This quantity is the angular acceleration of the rigid bodies' center of mass frame relative to the world.
@@ -1263,7 +1263,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
#
@property
- defbody_link_pos_w(self)->torch.Tensor:
+ defbody_link_pos_w(self)->torch.Tensor:"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3). This quantity is the position of the rigid bodies' actor frame relative to the world.
@@ -1276,7 +1276,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._body_link_state_w.data[...,:3]@property
- defbody_link_quat_w(self)->torch.Tensor:
+ defbody_link_quat_w(self)->torch.Tensor:"""Orientation (w, x, y, z) of all bodies in simulation world frame. Shape is (num_instances, 1, 4). This quantity is the orientation of the rigid bodies' actor frame relative to the world.
@@ -1290,7 +1290,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_link_state_w[...,3:7]@property
- defbody_link_vel_w(self)->torch.Tensor:
+ defbody_link_vel_w(self)->torch.Tensor:"""Velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 6). This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame
@@ -1299,7 +1299,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_link_state_w[...,7:13]@property
- defbody_link_lin_vel_w(self)->torch.Tensor:
+ defbody_link_lin_vel_w(self)->torch.Tensor:"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3). This quantity is the linear velocity of the rigid bodies' center of mass frame relative to the world.
@@ -1307,7 +1307,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_link_state_w[...,7:10]@property
- defbody_link_ang_vel_w(self)->torch.Tensor:
+ defbody_link_ang_vel_w(self)->torch.Tensor:"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3). This quantity is the angular velocity of the rigid bodies' center of mass frame relative to the world.
@@ -1319,7 +1319,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
#
@property
- defbody_com_pos_w(self)->torch.Tensor:
+ defbody_com_pos_w(self)->torch.Tensor:"""Positions of all bodies in simulation world frame. Shape is (num_instances, 1, 3). This quantity is the position of the rigid bodies' actor frame.
@@ -1327,7 +1327,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_com_state_w[...,:3]@property
- defbody_com_quat_w(self)->torch.Tensor:
+ defbody_com_quat_w(self)->torch.Tensor:"""Orientation (w, x, y, z) of the prinicple axies of inertia of all bodies in simulation world frame. Shape is (num_instances, 1, 4). This quantity is the orientation of the rigid bodies' actor frame.
@@ -1335,7 +1335,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_com_state_w[...,3:7]@property
- defbody_com_vel_w(self)->torch.Tensor:
+ defbody_com_vel_w(self)->torch.Tensor:"""Velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 6). This quantity contains the linear and angular velocities of the rigid bodies' center of mass frame.
@@ -1348,7 +1348,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_com_state_w[...,7:13]@property
- defbody_com_lin_vel_w(self)->torch.Tensor:
+ defbody_com_lin_vel_w(self)->torch.Tensor:"""Linear velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3). This quantity is the linear velocity of the rigid bodies' center of mass frame.
@@ -1361,7 +1361,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_com_state_w[...,7:10]@property
- defbody_com_ang_vel_w(self)->torch.Tensor:
+ defbody_com_ang_vel_w(self)->torch.Tensor:"""Angular velocity of all bodies in simulation world frame. Shape is (num_instances, 1, 3). This quantity is the angular velocity of the rigid bodies' center of mass frame.
@@ -1374,7 +1374,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self.body_com_state_w[...,10:13]@property
- defcom_pos_b(self)->torch.Tensor:
+ defcom_pos_b(self)->torch.Tensor:"""Center of mass of all of the bodies in simulation world frame. Shape is (num_instances, num_bodies, 3). This quantity is the center of mass location relative to its body frame.
@@ -1382,7 +1382,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
return self._root_physx_view.get_coms().to(self.device)[...,:3]@property
- defcom_quat_b(self)->torch.Tensor:
+ defcom_quat_b(self)->torch.Tensor:"""Orientation (w,x,y,z) of the prinicple axies of inertia of all of the bodies in simulation world frame. Shape is (num_instances, num_bodies, 4). This quantity is the orientation of the principles axes of inertia relative to its body frame.
@@ -1436,7 +1436,7 @@
Source code for omni.isaac.lab.assets.articulation.articulation_data
- Last updated on Jan 03, 2025.
+ Last updated on Jan 07, 2025.
[docs]classAssetBase(ABC):"""The base interface class for assets. An asset corresponds to any physics-enabled object that can be spawned in the simulation. These include
@@ -567,7 +567,7 @@
[docs]def__init__(self,cfg:AssetBaseCfg):"""Initialize the asset base. Args:
@@ -621,7 +621,7 @@
Source code for omni.isaac.lab.assets.asset_base
# set initial state of debug visualizationself.set_debug_vis(self.cfg.debug_vis)
- def__del__(self):
+ def__del__(self):"""Unsubscribe from the callbacks."""# clear physics events handlesifself._initialize_handle:
@@ -640,7 +640,7 @@
Source code for omni.isaac.lab.assets.asset_base
"""@property
- defis_initialized(self)->bool:
+ defis_initialized(self)->bool:"""Whether the asset is initialized. Returns True if the asset is initialized, False otherwise.
@@ -649,7 +649,7 @@
Source code for omni.isaac.lab.assets.asset_base
@property@abstractmethod
- defnum_instances(self)->int:
+ defnum_instances(self)->int:"""Number of instances of the asset. This is equal to the number of asset instances per environment multiplied by the number of environments.
@@ -657,18 +657,18 @@
Source code for omni.isaac.lab.assets.asset_base
returnNotImplementedError@property
- defdevice(self)->str:
+ defdevice(self)->str:"""Memory device for computation."""returnself._device@property@abstractmethod
- defdata(self)->Any:
+ defdata(self)->Any:"""Data related to the asset."""returnNotImplementedError@property
- defhas_debug_vis_implementation(self)->bool:
+ defhas_debug_vis_implementation(self)->bool:"""Whether the asset has a debug visualization implemented."""# check if function raises NotImplementedErrorsource_code=inspect.getsource(self._set_debug_vis_impl)
@@ -678,7 +678,7 @@
[docs]defset_debug_vis(self,debug_vis:bool)->bool:"""Sets whether to visualize the asset data. Args:
@@ -710,7 +710,7 @@
Source code for omni.isaac.lab.assets.asset_base
returnTrue
[docs]@abstractmethod
- defreset(self,env_ids:Sequence[int]|None=None):
+ defreset(self,env_ids:Sequence[int]|None=None):"""Resets all internal buffers of selected environments. Args:
@@ -719,12 +719,12 @@
Source code for omni.isaac.lab.assets.asset_base
raiseNotImplementedError
[docs]@abstractmethod
- defwrite_data_to_sim(self):
+ defwrite_data_to_sim(self):"""Writes data to the simulator."""raiseNotImplementedError
[docs]@abstractmethod
- defupdate(self,dt:float):
+ defupdate(self,dt:float):"""Update the internal buffers. The time step ``dt`` is used to compute numerical derivatives of quantities such as joint
@@ -740,11 +740,11 @@
Source code for omni.isaac.lab.assets.asset_base
"""@abstractmethod
- def_initialize_impl(self):
+ def_initialize_impl(self):"""Initializes the PhysX handles and internal buffers."""raiseNotImplementedError
- def_set_debug_vis_impl(self,debug_vis:bool):
+ def_set_debug_vis_impl(self,debug_vis:bool):"""Set debug visualization into visualization objects. This function is responsible for creating the visualization objects if they don't exist
@@ -753,7 +753,7 @@
Source code for omni.isaac.lab.assets.asset_base
"""raiseNotImplementedError(f"Debug visualization is not implemented for {self.__class__.__name__}.")
- def_debug_vis_callback(self,event):
+ def_debug_vis_callback(self,event):"""Callback for debug visualization. This function calls the visualization objects and sets the data to visualize into them.
@@ -764,7 +764,7 @@
Source code for omni.isaac.lab.assets.asset_base
Internal simulation callbacks. """
- def_initialize_callback(self,event):
+ def_initialize_callback(self,event):"""Initializes the scene elements. Note:
@@ -783,7 +783,7 @@
Source code for omni.isaac.lab.assets.asset_base
# set flagself._is_initialized=True
- def_invalidate_initialize_callback(self,event):
+ def_invalidate_initialize_callback(self,event):"""Invalidates the scene elements."""self._is_initialized=False
[docs]@configclass
-classAssetBaseCfg:
+classAssetBaseCfg:"""The base configuration class for an asset's parameters. Please see the :class:`AssetBase` class for more information on the asset class. """
[docs]@configclass
- classInitialStateCfg:
+ classInitialStateCfg:"""Initial state of the asset. This defines the default initial state of the asset when it is spawned into the simulation, as
@@ -639,7 +639,7 @@
Source code for omni.isaac.lab.assets.asset_base_cfg
- Last updated on Jan 03, 2025.
+ Last updated on Jan 07, 2025.
[docs]classDeformableObject(AssetBase):"""A deformable object asset class. Deformable objects are assets that can be deformed in the simulation. They are typically used for
@@ -572,7 +572,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_objectcfg:DeformableObjectCfg"""Configuration instance for the deformable object."""
-
[docs]def__init__(self,cfg:DeformableObjectCfg):"""Initialize the deformable object. Args:
@@ -585,15 +585,15 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object """
@property
- defdata(self)->DeformableObjectData:
+ defdata(self)->DeformableObjectData:returnself._data@property
- defnum_instances(self)->int:
+ defnum_instances(self)->int:returnself.root_physx_view.count@property
- defnum_bodies(self)->int:
+ defnum_bodies(self)->int:"""Number of bodies in the asset. This is always 1 since each object is a single deformable body.
@@ -601,7 +601,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_objectreturn 1@property
- defroot_physx_view(self)->physx.SoftBodyView:
+ defroot_physx_view(self)->physx.SoftBodyView:"""Deformable body view for the asset (PhysX). Note:
@@ -610,7 +610,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_objectreturn self._root_physx_view@property
- defmaterial_physx_view(self)->physx.SoftBodyMaterialView|None:
+ defmaterial_physx_view(self)->physx.SoftBodyMaterialView|None:"""Deformable material view for the asset (PhysX). This view is optional and may not be available if the material is not bound to the deformable body.
@@ -622,22 +622,22 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_objectreturn self._material_physx_view@property
- defmax_sim_elements_per_body(self)->int:
+ defmax_sim_elements_per_body(self)->int:"""The maximum number of simulation mesh elements per deformable body."""returnself.root_physx_view.max_sim_elements_per_body@property
- defmax_collision_elements_per_body(self)->int:
+ defmax_collision_elements_per_body(self)->int:"""The maximum number of collision mesh elements per deformable body."""returnself.root_physx_view.max_elements_per_body@property
- defmax_sim_vertices_per_body(self)->int:
+ defmax_sim_vertices_per_body(self)->int:"""The maximum number of simulation mesh vertices per deformable body."""returnself.root_physx_view.max_sim_vertices_per_body@property
- defmax_collision_vertices_per_body(self)->int:
+ defmax_collision_vertices_per_body(self)->int:"""The maximum number of collision mesh vertices per deformable body."""returnself.root_physx_view.max_vertices_per_body
@@ -645,22 +645,22 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object Operations.
"""
-
[docs]defreset(self,env_ids:Sequence[int]|None=None):# Think: Should we reset the kinematic targets when resetting the object?# This is not done in the current implementation. We assume users will reset the kinematic targets.pass
[docs]defwrite_nodal_state_to_sim(self,nodal_state:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the nodal state over selected environment indices into the simulation. The nodal state comprises of the nodal positions and velocities. Since these are nodes, the velocity only has
@@ -675,7 +675,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_objectself.write_nodal_pos_to_sim(nodal_state[...,:3],env_ids=env_ids)self.write_nodal_velocity_to_sim(nodal_state[...,3:],env_ids=env_ids)
[docs]defwrite_nodal_pos_to_sim(self,nodal_pos:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the nodal positions over selected environment indices into the simulation. The nodal position comprises of individual nodal positions of the simulation mesh for the deformable body.
@@ -697,7 +697,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object# set into simulation
self.root_physx_view.set_sim_nodal_positions(self._data.nodal_pos_w,indices=physx_env_ids)
[docs]defwrite_nodal_velocity_to_sim(self,nodal_vel:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the nodal velocity over selected environment indices into the simulation. The nodal velocity comprises of individual nodal velocities of the simulation mesh for the deformable
@@ -720,7 +720,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object# set into simulation
self.root_physx_view.set_sim_nodal_velocities(self._data.nodal_vel_w,indices=physx_env_ids)
[docs]defwrite_nodal_kinematic_target_to_sim(self,targets:torch.Tensor,env_ids:Sequence[int]|None=None):"""Set the kinematic targets of the simulation mesh for the deformable bodies indicated by the indices. The kinematic targets comprise of individual nodal positions of the simulation mesh for the deformable body
@@ -748,7 +748,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object Operations - Helper.
"""
-
[docs]deftransform_nodal_pos(self,nodal_pos:torch.tensor,pos:torch.Tensor|None=None,quat:torch.Tensor|None=None)->torch.Tensor:"""Transform the nodal positions based on the pose transformation.
@@ -777,7 +777,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object# update the deformable body data
self.update(0.0)
- def_create_buffers(self):
+ def_create_buffers(self):"""Create buffers for storing data."""# constantsself._ALL_INDICES=torch.arange(self.num_instances,dtype=torch.long,device=self.device)
@@ -896,7 +896,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object Internal simulation callbacks.
"""
- def_set_debug_vis_impl(self,debug_vis:bool):
+ def_set_debug_vis_impl(self,debug_vis:bool):# set visibility of markers# note: parent only deals with callbacks. not their visibilityifdebug_vis:
@@ -908,7 +908,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_objectif hasattr(self,"target_visualizer"):self.target_visualizer.set_visibility(False)
- def_debug_vis_callback(self,event):
+ def_debug_vis_callback(self,event):# check where to visualizetargets_enabled=self.data.nodal_kinematic_target[:,:,3]==0.0num_enabled=int(torch.sum(targets_enabled).item())
@@ -921,7 +921,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object# show target visualizer
self.target_visualizer.visualize(positions)
- def_invalidate_initialize_callback(self,event):
+ def_invalidate_initialize_callback(self,event):"""Invalidates the scene elements."""# call parentsuper()._invalidate_initialize_callback(event)
@@ -975,7 +975,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object
- Last updated on Jan 03, 2025.
+ Last updated on Jan 07, 2025.
[docs]classDeformableObjectData:"""Data container for a deformable object. This class contains the data for a deformable object in the simulation. The data includes the nodal states of
@@ -549,7 +549,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
is older than the current simulation timestamp. The timestamp is updated whenever the data is updated. """
- def__init__(self,root_physx_view:physx.SoftBodyView,device:str):
+ def__init__(self,root_physx_view:physx.SoftBodyView,device:str):"""Initializes the deformable object data. Args:
@@ -581,7 +581,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
self._sim_element_stress_w=TimestampedBuffer()self._collision_element_stress_w=TimestampedBuffer()
-
[docs]defupdate(self,dt:float):"""Updates the data for the deformable object. Args:
@@ -618,7 +618,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
##@property
- defnodal_pos_w(self):
+ defnodal_pos_w(self):"""Nodal positions in simulation world frame. Shape is (num_instances, max_sim_vertices_per_body, 3)."""ifself._nodal_pos_w.timestamp<self._sim_timestamp:self._nodal_pos_w.data=self._root_physx_view.get_sim_nodal_positions()
@@ -626,7 +626,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._nodal_pos_w.data@property
- defnodal_vel_w(self):
+ defnodal_vel_w(self):"""Nodal velocities in simulation world frame. Shape is (num_instances, max_sim_vertices_per_body, 3)."""ifself._nodal_vel_w.timestamp<self._sim_timestamp:self._nodal_vel_w.data=self._root_physx_view.get_sim_nodal_velocities()
@@ -634,7 +634,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._nodal_vel_w.data@property
- defnodal_state_w(self):
+ defnodal_state_w(self):"""Nodal state ``[nodal_pos, nodal_vel]`` in simulation world frame. Shape is (num_instances, max_sim_vertices_per_body, 6). """
@@ -647,7 +647,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._nodal_state_w.data@property
- defsim_element_quat_w(self):
+ defsim_element_quat_w(self):"""Simulation mesh element-wise rotations as quaternions for the deformable bodies in simulation world frame. Shape is (num_instances, max_sim_elements_per_body, 4).
@@ -663,7 +663,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._sim_element_quat_w.data@property
- defcollision_element_quat_w(self):
+ defcollision_element_quat_w(self):"""Collision mesh element-wise rotations as quaternions for the deformable bodies in simulation world frame. Shape is (num_instances, max_collision_elements_per_body, 4).
@@ -679,7 +679,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._collision_element_quat_w.data@property
- defsim_element_deform_gradient_w(self):
+ defsim_element_deform_gradient_w(self):"""Simulation mesh element-wise second-order deformation gradient tensors for the deformable bodies in simulation world frame. Shape is (num_instances, max_sim_elements_per_body, 3, 3). """
@@ -694,7 +694,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._sim_element_deform_gradient_w.data@property
- defcollision_element_deform_gradient_w(self):
+ defcollision_element_deform_gradient_w(self):"""Collision mesh element-wise second-order deformation gradient tensors for the deformable bodies in simulation world frame. Shape is (num_instances, max_collision_elements_per_body, 3, 3). """
@@ -707,7 +707,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._collision_element_deform_gradient_w.data@property
- defsim_element_stress_w(self):
+ defsim_element_stress_w(self):"""Simulation mesh element-wise second-order Cauchy stress tensors for the deformable bodies in simulation world frame. Shape is (num_instances, max_sim_elements_per_body, 3, 3). """
@@ -720,7 +720,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself._sim_element_stress_w.data@property
- defcollision_element_stress_w(self):
+ defcollision_element_stress_w(self):"""Collision mesh element-wise second-order Cauchy stress tensors for the deformable bodies in simulation world frame. Shape is (num_instances, max_collision_elements_per_body, 3, 3). """
@@ -737,7 +737,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
##@property
- defroot_pos_w(self)->torch.Tensor:
+ defroot_pos_w(self)->torch.Tensor:"""Root position from nodal positions of the simulation mesh for the deformable bodies in simulation world frame. Shape is (num_instances, 3).
@@ -746,7 +746,7 @@
Source code for omni.isaac.lab.assets.deformable_object.deformable_object_da
returnself.nodal_pos_w.mean(dim=1)@property
- defroot_vel_w(self)->torch.Tensor:
+ defroot_vel_w(self)->torch.Tensor:"""Root velocity from vertex velocities for the deformable bodies in simulation world frame. Shape is (num_instances, 3).
@@ -800,7 +800,7 @@
[docs]classRigidObject(AssetBase):"""A rigid object asset class. Rigid objects are assets comprising of rigid bodies. They can be used to represent dynamic objects
@@ -565,7 +565,7 @@
Source code for omni.isaac.lab.assets.rigid_object.rigid_object
cfg:RigidObjectCfg"""Configuration instance for the rigid object."""
-