Manipulators [omni.isaac.manipulators]

Single Manipulator

class SingleManipulator(prim_path: str, end_effector_prim_name: str, name: str = 'single_manipulator', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, gripper: Optional[omni.isaac.manipulators.grippers.gripper.Gripper] = None)

Provides high level functions to set/ get properties and actions of a manipulator with a single end effector and optionally a gripper.

Parameters
  • prim_path (str) – prim path of the Prim to encapsulate or create.

  • end_effector_prim_name (str) – end effector prim name to be used to track the rigid body that corresponds to the end effector.

  • name (str, optional) – shortname to be used as a key by Scene class. Note: needs to be unique if the object is added to the Scene. Defaults to “single_manipulator”.

  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world/ local frame of the prim (depends if translation or position is specified). quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

  • scale (Optional[Sequence[float]], optional) – local scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

  • visible (Optional[bool], optional) – set to false for an invisible prim in the stage while rendering. Defaults to True.

  • gripper (Gripper, optional) – Gripper to be used with the manipulator. Defaults to None.

apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

[summary]

Parameters
  • control_actions (ArticulationAction) – actions to be applied for next physics step.

  • indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.

Raises

Exception – [description]

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

property articulation_handle: int

[summary]

Returns

[description]

Return type

int

disable_gravity() None

Keep gravity from affecting the robot

property dof_names: List[str]

List of prim names for each DOF.

Returns

prim names

Return type

list(string)

property dof_properties: numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

enable_gravity() None

Gravity will affect the robot

property end_effector: omni.isaac.core.prims.rigid_prim.RigidPrim

Returns: RigidPrim: end effector of the manipulator (can be used to get its world pose, angular velocity..etc).

get_angular_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_applied_action() omni.isaac.core.utils.types.ArticulationAction

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

ArticulationAction

get_applied_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the efforts applied to the joints

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_articulation_body_count() int

[summary]

Returns

[description]

Return type

int

get_articulation_controller() omni.isaac.core.controllers.articulation_controller.ArticulationController
Returns

PD Controller of all degrees of freedom of an articulation, can apply position targets, velocity targets and efforts.

Return type

ArticulationController

get_default_state() omni.isaac.core.utils.types.XFormPrimState
Returns

returns the default state of the prim (position and orientation) that is used after each reset.

Return type

XFormPrimState

get_dof_index(dof_name: str) int

[summary]

Parameters

dof_name (str) – [description]

Returns

[description]

Return type

int

get_enabled_self_collisions() bool

[summary]

Returns

[description]

Return type

bool

get_joint_positions(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joint_velocities(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joints_default_state() omni.isaac.core.utils.types.JointsState

Accessor for the default joints state.

Returns

The defaults that the robot is reset to when post_reset() is called (often automatically called during world.reset()).

Return type

JointsState

get_joints_state() omni.isaac.core.utils.types.JointsState

[summary]

Returns

[description]

Return type

JointsState

get_linear_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_measured_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Returns the dof efforts computed/measured by the physics solver

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_measured_joint_forces(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the measured joint forces

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_sleep_threshold() float

[summary]

Returns

[description]

Return type

float

get_solver_position_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_solver_velocity_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_stabilization_threshold() float

[summary]

Returns

[description]

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

property gripper: omni.isaac.manipulators.grippers.gripper.Gripper

Returns: Gripper: gripper of the manipulator (can be used to open or close the gripper, get its world pose or angular velocity..etc).

property handles_initialized: bool

[summary]

Returns

[description]

Return type

bool

initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None
Create a physics simulation view if not passed and creates an articulation view using physX tensor api.

This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.

Parameters

physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.

is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

_summary_

Returns

_description_

Return type

bool

property num_dof: int

[summary]

Returns

[description]

Return type

int

post_reset() None

Resets the manipulator, the end effector and the gripper to its default state.

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

set_angular_velocity(velocity: numpy.ndarray) None

[summary]

Parameters

velocity (np.ndarray) – [description]

set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets the default state of the prim (position and orientation), that will be used after each reset.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_enabled_self_collisions(flag: bool) None

[summary]

Parameters

flag (bool) – [description]

set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • efforts (np.ndarray) – [description]

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_positions(positions: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • positions (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_velocities(velocities: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • velocities (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joints_default_state(positions: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.ndarray] = None) None

[summary]

Parameters
  • positions (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • velocities (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • efforts (Optional[np.ndarray], optional) – [description]. Defaults to None.

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage.

Parameters

velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_sleep_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_solver_position_iteration_count(count: int) None

[summary]

Parameters

count (int) – [description]

set_solver_velocity_iteration_count(count: int)

[summary]

Parameters

count (int) – [description]

set_stabilization_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

Controllers

Pick and Place Controller

class PickPlaceController(name: str, cspace_controller: omni.isaac.core.controllers.base_controller.BaseController, gripper: omni.isaac.manipulators.grippers.gripper.Gripper, end_effector_initial_height: Optional[float] = None, events_dt: Optional[List[float]] = None)

A simple pick and place state machine for tutorials

Each phase runs for 1 second, which is the internal time of the state machine

Dt of each phase/ event step is defined

  • Phase 0: Move end_effector above the cube center at the ‘end_effector_initial_height’.

  • Phase 1: Lower end_effector down to encircle the target cube

  • Phase 2: Wait for Robot’s inertia to settle.

  • Phase 3: close grip.

  • Phase 4: Move end_effector up again, keeping the grip tight (lifting the block).

  • Phase 5: Smoothly move the end_effector toward the goal xy, keeping the height constant.

  • Phase 6: Move end_effector vertically toward goal height at the ‘end_effector_initial_height’.

  • Phase 7: loosen the grip.

  • Phase 8: Move end_effector vertically up again at the ‘end_effector_initial_height’

  • Phase 9: Move end_effector towards the old xy position.

Parameters
  • name (str) – Name id of the controller

  • cspace_controller (BaseController) – a cartesian space controller that returns an ArticulationAction type

  • gripper (Gripper) – a gripper controller for open/ close actions.

  • end_effector_initial_height (Optional[float], optional) – end effector initial picking height to start from (more info in phases above). If not defined, set to 0.3 meters. Defaults to None.

  • events_dt (Optional[List[float]], optional) – Dt of each phase/ event step. 10 phases dt has to be defined. Defaults to None.

Raises
  • Exception – events dt need to be list or numpy array

  • Exception – events dt need have length of 10

forward(picking_position: numpy.ndarray, placing_position: numpy.ndarray, current_joint_positions: numpy.ndarray, end_effector_offset: Optional[numpy.ndarray] = None, end_effector_orientation: Optional[numpy.ndarray] = None) omni.isaac.core.utils.types.ArticulationAction

Runs the controller one step.

Parameters
  • picking_position (np.ndarray) – The object’s position to be picked in local frame.

  • placing_position (np.ndarray) – The object’s position to be placed in local frame.

  • current_joint_positions (np.ndarray) – Current joint positions of the robot.

  • end_effector_offset (Optional[np.ndarray], optional) – offset of the end effector target. Defaults to None.

  • end_effector_orientation (Optional[np.ndarray], optional) – end effector orientation while picking and placing. Defaults to None.

Returns

action to be executed by the ArticulationController

Return type

ArticulationAction

get_current_event() int
Returns

Current event/ phase of the state machine

Return type

int

is_done() bool
Returns

True if the state machine reached the last phase. Otherwise False.

Return type

bool

is_paused() bool
Returns

True if the state machine is paused. Otherwise False.

Return type

bool

pause() None

Pauses the state machine’s time and phase.

reset(end_effector_initial_height: Optional[float] = None, events_dt: Optional[List[float]] = None) None

Resets the state machine to start from the first phase/ event

Parameters
  • end_effector_initial_height (Optional[float], optional) – end effector initial picking height to start from. If not defined, set to 0.3 meters. Defaults to None.

  • events_dt (Optional[List[float]], optional) – Dt of each phase/ event step. 10 phases dt has to be defined. Defaults to None.

Raises
  • Exception – events dt need to be list or numpy array

  • Exception – events dt need have length of 10

resume() None

Resumes the state machine’s time and phase.

Stacking Controller

class StackingController(name: str, pick_place_controller: omni.isaac.manipulators.controllers.pick_place_controller.PickPlaceController, picking_order_cube_names: List[str], robot_observation_name: str)

[summary]

Parameters
  • name (str) – [description]

  • pick_place_controller (PickPlaceController) – [description]

  • picking_order_cube_names (List[str]) – [description]

  • robot_observation_name (str) – [description]

forward(observations: dict, end_effector_orientation: Optional[numpy.ndarray] = None, end_effector_offset: Optional[numpy.ndarray] = None) omni.isaac.core.utils.types.ArticulationAction
A controller should take inputs and returns an ArticulationAction to be then passed to the

ArticulationController.

Parameters

observations (dict) – [description]

Raises

NotImplementedError – [description]

Returns

[description]

Return type

ArticulationAction

is_done() bool

[summary]

Returns

[description]

Return type

bool

reset(picking_order_cube_names: Optional[List[str]] = None) None

[summary]

Parameters

picking_order_cube_names (Optional[List[str]], optional) – [description]. Defaults to None.

Grippers

Base Gripper

class Gripper(end_effector_prim_path: str)

Provides high level functions to set/ get properties and actions of a gripper.

Parameters

end_effector_prim_path (str) – prim path of the Prim that corresponds to the gripper root/ end effector.

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

abstract close() None

Applies actions to the articulation that closes the gripper (ex: to hold an object).

disable_rigid_body_physics() None

disable rigid body physics (enabled by default): Object will not be moved by external forces such as gravity and collisions

enable_rigid_body_physics() None

enable rigid body physics (enabled by default): Object will be moved by external forces such as gravity and collisions

abstract forward(*args, **kwargs) omni.isaac.core.utils.types.ArticulationAction
calculates the ArticulationAction for all of the articulation joints that corresponds to a specific action

such as “open” for an example.

Returns

articulation action to be passed to the articulation itself

(includes all joints of the articulation).

Return type

ArticulationAction

get_angular_velocity()
Returns

current angular velocity of the the rigid prim. Shape (3,).

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Returns

the dynamic state of the rigid body including position, orientation, linear_velocity and angular_velocity.

Return type

DynamicState

abstract get_default_state(*args, **kwargs)

Gets the default state of the gripper

get_density() float
Returns

density of the rigid body.

Return type

float

get_linear_velocity() numpy.ndarray
Returns

current linear velocity of the the rigid prim. Shape (3,).

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_mass() float
Returns

mass of the rigid body in kg.

Return type

float

get_sleep_threshold() float
Returns

Mass-normalized kinetic energy threshold below which

an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None
Create a physics simulation view if not passed and creates a rigid prim view using physX tensor api.

This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.

Parameters

physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.

is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

_summary_

Returns

_description_

Return type

bool

abstract open() None

Applies actions to the articulation that opens the gripper (ex: to release an object held).

post_reset() None

Resets the prim to its default state (position and orientation).

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

set_angular_velocity(velocity: numpy.ndarray) None

Sets the angular velocity of the prim in stage. :param velocity: angular velocity to set the rigid prim to. Shape (3,). :type velocity: np.ndarray

abstract set_default_state(*args, **kwargs)

Sets the default state of the gripper

set_density(density: float) None
Parameters

mass (float) – density of the rigid body.

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage. :param velocity: linear velocity to set the rigid prim to. Shape (3,). :type velocity: np.ndarray

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_mass(mass: float) None
Parameters

mass (float) – mass of the rigid body in kg.

set_sleep_threshold(threshold: float) None
Parameters

threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

Parallel Gripper

class ParallelGripper(end_effector_prim_path: str, joint_prim_names: List[str], joint_opened_positions: numpy.ndarray, joint_closed_positions: numpy.ndarray, action_deltas: Optional[numpy.ndarray] = None)

Provides high level functions to set/ get properties and actions of a parllel gripper (a gripper that has two fingers).

Parameters
  • end_effector_prim_path (str) – prim path of the Prim that corresponds to the gripper root/ end effector.

  • joint_prim_names (List[str]) – the left finger joint prim name and the right finger joint prim name respectively.

  • joint_opened_positions (np.ndarray) – joint positions of the left finger joint and the right finger joint respectively when opened.

  • joint_closed_positions (np.ndarray) – joint positions of the left finger joint and the right finger joint respectively when closed.

  • action_deltas (np.ndarray, optional) – deltas to apply for finger joint positions when openning or closing the gripper. Defaults to None.

apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

Applies actions to all the joints of an articulation that corresponds to the ArticulationAction of the finger joints only.

Parameters

control_actions (ArticulationAction) – ArticulationAction for the left finger joint and the right finger joint respectively.

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

close() None

Applies actions to the articulation that closes the gripper (ex: to hold an object).

disable_rigid_body_physics() None

disable rigid body physics (enabled by default): Object will not be moved by external forces such as gravity and collisions

enable_rigid_body_physics() None

enable rigid body physics (enabled by default): Object will be moved by external forces such as gravity and collisions

forward(action: str) omni.isaac.core.utils.types.ArticulationAction
calculates the ArticulationAction for all of the articulation joints that corresponds to “open”

or “close” actions.

Parameters

action (str) – “open” or “close” as an abstract action.

Raises

Exception – _description_

Returns

articulation action to be passed to the articulation itself

(includes all joints of the articulation).

Return type

ArticulationAction

get_action_deltas() numpy.ndarray
Returns

deltas that will be applied for finger joint positions when openning or closing the gripper.

[left, right]. Defaults to None.

Return type

np.ndarray

get_angular_velocity()
Returns

current angular velocity of the the rigid prim. Shape (3,).

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Returns

the dynamic state of the rigid body including position, orientation, linear_velocity and angular_velocity.

Return type

DynamicState

get_default_state() numpy.ndarray

Gets the default state of the gripper

Returns

joint positions of the left finger joint and the right finger joint respectively.

Return type

np.ndarray

get_density() float
Returns

density of the rigid body.

Return type

float

get_joint_positions() numpy.ndarray
Returns

joint positions of the left finger joint and the right finger joint respectively.

Return type

np.ndarray

get_linear_velocity() numpy.ndarray
Returns

current linear velocity of the the rigid prim. Shape (3,).

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_mass() float
Returns

mass of the rigid body in kg.

Return type

float

get_sleep_threshold() float
Returns

Mass-normalized kinetic energy threshold below which

an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

initialize(articulation_apply_action_func: Callable, get_joint_positions_func: Callable, set_joint_positions_func: Callable, dof_names: List, physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None) None
Create a physics simulation view if not passed and creates a rigid prim view using physX tensor api.

This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.

Parameters
  • articulation_apply_action_func (Callable) – apply_action function from the Articulation class.

  • get_joint_positions_func (Callable) – get_joint_positions function from the Articulation class.

  • set_joint_positions_func (Callable) – set_joint_positions function from the Articulation class.

  • dof_names (List) – dof names from the Articulation class.

  • physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None

Raises

Exception – _description_

is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property joint_closed_positions: numpy.ndarray

Returns: np.ndarray: joint positions of the left finger joint and the right finger joint respectively when closed.

property joint_dof_indicies: numpy.ndarray

Returns: np.ndarray: joint dof indices in the articulation of the left finger joint and the right finger joint respectively.

property joint_opened_positions: numpy.ndarray

Returns: np.ndarray: joint positions of the left finger joint and the right finger joint respectively when opened.

property joint_prim_names: List[str]

Returns: List[str]: the left finger joint prim name and the right finger joint prim name respectively.

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

_summary_

Returns

_description_

Return type

bool

open() None

Applies actions to the articulation that opens the gripper (ex: to release an object held).

post_reset()

Resets the prim to its default state (position and orientation).

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

set_action_deltas(value: numpy.ndarray) None
Parameters

value (np.ndarray) – deltas to apply for finger joint positions when openning or closing the gripper. [left, right]. Defaults to None.

set_angular_velocity(velocity: numpy.ndarray) None

Sets the angular velocity of the prim in stage. :param velocity: angular velocity to set the rigid prim to. Shape (3,). :type velocity: np.ndarray

set_default_state(joint_positions: numpy.ndarray) None

Sets the default state of the gripper

Parameters

joint_positions (np.ndarray) – joint positions of the left finger joint and the right finger joint respectively.

set_density(density: float) None
Parameters

mass (float) – density of the rigid body.

set_joint_positions(positions: numpy.ndarray) None
Parameters

positions (np.ndarray) – joint positions of the left finger joint and the right finger joint respectively.

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage. :param velocity: linear velocity to set the rigid prim to. Shape (3,). :type velocity: np.ndarray

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_mass(mass: float) None
Parameters

mass (float) – mass of the rigid body in kg.

set_sleep_threshold(threshold: float) None
Parameters

threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

Surface Gripper

class SurfaceGripper(end_effector_prim_path: str, translate: float = 0, direction: str = 'x', grip_threshold: float = 0.01, force_limit: float = 1000000.0, torque_limit: float = 10000.0, bend_angle: float = 0.1308996938995747, kp: float = 100.0, kd: float = 100.0, disable_gravity: bool = True)

Provides high level functions to set/ get properties and actions of a surface gripper (a suction cup for example).

Parameters
  • end_effector_prim_path (str) – prim path of the Prim that corresponds to the gripper root/ end effector.

  • translate (float, optional) – _description_. Defaults to 0.

  • direction (str, optional) – _description_. Defaults to “x”.

  • grip_threshold (float, optional) – _description_. Defaults to 0.01.

  • force_limit (float, optional) – _description_. Defaults to 1.0e6.

  • torque_limit (float, optional) – _description_. Defaults to 1.0e4.

  • bend_angle (float, optional) – _description_. Defaults to np.pi/24.

  • kp (float, optional) – _description_. Defaults to 1.0e2.

  • kd (float, optional) – _description_. Defaults to 1.0e2.

  • disable_gravity (bool, optional) – _description_. Defaults to True.

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

close() None

Applies actions to the articulation that closes the gripper (ex: to hold an object).

disable_rigid_body_physics() None

disable rigid body physics (enabled by default): Object will not be moved by external forces such as gravity and collisions

enable_rigid_body_physics() None

enable rigid body physics (enabled by default): Object will be moved by external forces such as gravity and collisions

forward(action: str) omni.isaac.core.utils.types.ArticulationAction
calculates the ArticulationAction for all of the articulation joints that corresponds to “open”

or “close” actions.

Parameters

action (str) – “open” or “close” as an abstract action.

Raises

Exception – _description_

Returns

articulation action to be passed to the articulation itself

(includes all joints of the articulation).

Return type

ArticulationAction

get_angular_velocity()
Returns

current angular velocity of the the rigid prim. Shape (3,).

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Returns

the dynamic state of the rigid body including position, orientation, linear_velocity and angular_velocity.

Return type

DynamicState

get_default_state() dict

Gets the default state of the gripper

Returns

key is “opened” and value would be true if the surface gripper should start in an opened state. False otherwise.

Return type

dict

get_density() float
Returns

density of the rigid body.

Return type

float

get_linear_velocity() numpy.ndarray
Returns

current linear velocity of the the rigid prim. Shape (3,).

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_mass() float
Returns

mass of the rigid body in kg.

Return type

float

get_sleep_threshold() float
Returns

Mass-normalized kinetic energy threshold below which

an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

initialize(physics_sim_view: Optional[omni.physics.tensors.bindings._physicsTensors.SimulationView] = None, articulation_num_dofs: Optional[int] = None) None
Create a physics simulation view if not passed and creates a rigid prim view using physX tensor api.

This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.

Parameters
  • physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None

  • articulation_num_dofs (int, optional) – num of dofs of the Articulation. Defaults to None.

is_closed() bool
is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

property non_root_articulation_link: bool

_summary_

Returns

_description_

Return type

bool

open() None

Applies actions to the articulation that opens the gripper (ex: to release an object held).

post_reset()

Resets the prim to its default state (position and orientation).

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

set_angular_velocity(velocity: numpy.ndarray) None

Sets the angular velocity of the prim in stage. :param velocity: angular velocity to set the rigid prim to. Shape (3,). :type velocity: np.ndarray

set_default_state(opened: bool)

Sets the default state of the gripper

Parameters

opened (bool) – True if the surface gripper should start in an opened state. False otherwise.

set_density(density: float) None
Parameters

mass (float) – density of the rigid body.

set_direction(value: float) None
set_force_limit(value: float) None
set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage. :param velocity: linear velocity to set the rigid prim to. Shape (3,). :type velocity: np.ndarray

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_mass(mass: float) None
Parameters

mass (float) – mass of the rigid body in kg.

set_sleep_threshold(threshold: float) None
Parameters

threshold (float) – Mass-normalized kinetic energy threshold below which an actor may go to sleep. Range: [0, inf) Defaults: 0.00005 * tolerancesSpeed* tolerancesSpeed Units: distance^2 / second^2.

set_torque_limit(value: float) None
set_translate(value: float) None
set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

update() None