Manipulators [omni.isaac.manipulators]
Single Manipulator
Provides high level functions to set/ get properties and actions of a manipulator with a single end effector and optionally a gripper.
- param prim_path
prim path of the Prim to encapsulate or create.
- type prim_path
str
- param end_effector_prim_name
end effector prim name to be used to track the rigid body that corresponds to the end effector. One of the following args can be specified only: end_effector_prim_name or end_effector_prim_path.
- type end_effector_prim_name
str
- param end_effector_prim_path
end effector prim path to be used to track the rigid body that corresponds to the end effector. One of the following args can be specified only: end_effector_prim_name or end_effector_prim_path.
- type end_effector_prim_path
str
- param name
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”.
- type name
str, optional
- param position
position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.
- type position
Optional[Sequence[float]], optional
- param translation
translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.
- type translation
Optional[Sequence[float]], optional
- param orientation
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.
- type orientation
Optional[Sequence[float]], optional
- param scale
local scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.
- type scale
Optional[Sequence[float]], optional
- param visible
set to false for an invisible prim in the stage while rendering. Defaults to True.
- type visible
Optional[bool], optional
- param gripper
Gripper to be used with the manipulator. Defaults to None.
- type gripper
Gripper, optional
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
- 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
- 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
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.
Example:
>>> from omni.isaac.core.materials import OmniGlass >>> >>> # create a dark-red glass visual material >>> material = OmniGlass( ... prim_path="/World/material/glass", # path to the material prim to create ... ior=1.25, ... depth=0.001, ... thin_walled=False, ... color=np.array([0.5, 0.0, 0.0]) ... ) >>> prim.apply_visual_material(material)
- abstract close() None
Applies actions to the articulation that closes the gripper (ex: to hold an object).
- disable_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- 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
- get_angular_velocity()
Get the angular velocity of the rigid body
- 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
Return 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- abstract get_default_state(*args, **kwargs)
Gets the default state of the gripper
- get_density() float
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]
Get prim’s pose with respect to the local frame (the prim’s parent frame)
- Returns
first index is the position in the local frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the local frame
- Return type
Tuple[np.ndarray, np.ndarray]
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_local_pose() >>> position [0. 0. 0.] >>> orientation [0. 0. 0.]
- get_local_scale() numpy.ndarray
Get 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
Example:
>>> prim.get_local_scale() [1. 1. 1.]
- get_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- 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
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_visibility() bool
- Returns
true if the prim is visible in stage. false otherwise.
- Return type
bool
Example:
>>> # get the visible state of an visible prim on the stage >>> prim.get_visibility() True
- get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]
Get prim’s pose with respect to the world’s frame
- Returns
first index is the position in the world frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the world frame
- Return type
Tuple[np.ndarray, np.ndarray]
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_world_pose() >>> position [1. 0.5 0. ] >>> orientation [1. 0. 0. 0.]
- get_world_scale() numpy.ndarray
Get 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
Example:
>>> prim.get_world_scale() [1. 1. 1.]
- 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
Check if the prim path has a valid USD Prim at it
- Returns
True is the current prim path corresponds to a valid prim in stage. False otherwise.
- Return type
bool
Example:
>>> # given an existing and valid prim >>> prims.is_valid() True
- is_visual_material_applied() bool
Check if there is a visual material applied
- Returns
True if there is a visual material applied. False otherwise.
- Return type
bool
Example:
>>> # given a visual material applied >>> prim.is_visual_material_applied() True
- property name: Optional[str]
Returns: str: name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- Return type
bool
Example:
>>> # for a wrapped articulation (where the root prim has the Physics Articulation Root property applied) >>> prim.non_root_articulation_link False
- abstract open() None
Applies actions to the articulation that opens the gripper (ex: to release an object held).
- post_reset() None
Reset the prim to its default state (position and orientation).
Note
For an articulation, in addition to configuring the root prim’s default position and spatial orientation (defined via the
set_default_state
method), the joint’s positions, velocities, and efforts (defined via theset_joints_default_state
method) are imposedExample:
>>> prim.post_reset()
- 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
Set the angular velocity of the rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- abstract set_default_state(*args, **kwargs)
Sets the default state of the gripper
- set_density(density: float) None
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- 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
Set prim’s pose with respect to the local frame (the prim’s parent frame).
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- 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.
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_local_pose(translation=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_local_scale(scale: Optional[Sequence[float]]) None
Set 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.
Example:
>>> # scale prim 10 times smaller >>> prim.set_local_scale(np.array([0.1, 0.1, 0.1]))
- set_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- 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.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_visibility(visible: bool) None
Set the visibility of the prim in stage
- Parameters
visible (bool) – flag to set the visibility of the usd prim in stage.
Example:
>>> # make prim not visible in the stage >>> prim.set_visibility(visible=False)
- set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None
Ses prim’s pose with respect to the world’s frame
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- 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.
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_world_pose(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
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
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.
Example:
>>> from omni.isaac.core.materials import OmniGlass >>> >>> # create a dark-red glass visual material >>> material = OmniGlass( ... prim_path="/World/material/glass", # path to the material prim to create ... ior=1.25, ... depth=0.001, ... thin_walled=False, ... color=np.array([0.5, 0.0, 0.0]) ... ) >>> prim.apply_visual_material(material)
- close() None
Applies actions to the articulation that closes the gripper (ex: to hold an object).
- disable_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- 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
- 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()
Get the angular velocity of the rigid body
- 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
Return 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- 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
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- 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
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]
Get prim’s pose with respect to the local frame (the prim’s parent frame)
- Returns
first index is the position in the local frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the local frame
- Return type
Tuple[np.ndarray, np.ndarray]
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_local_pose() >>> position [0. 0. 0.] >>> orientation [0. 0. 0.]
- get_local_scale() numpy.ndarray
Get 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
Example:
>>> prim.get_local_scale() [1. 1. 1.]
- get_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- 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
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_visibility() bool
- Returns
true if the prim is visible in stage. false otherwise.
- Return type
bool
Example:
>>> # get the visible state of an visible prim on the stage >>> prim.get_visibility() True
- get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]
Get prim’s pose with respect to the world’s frame
- Returns
first index is the position in the world frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the world frame
- Return type
Tuple[np.ndarray, np.ndarray]
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_world_pose() >>> position [1. 0.5 0. ] >>> orientation [1. 0. 0. 0.]
- get_world_scale() numpy.ndarray
Get 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
Example:
>>> prim.get_world_scale() [1. 1. 1.]
- 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
Check if the prim path has a valid USD Prim at it
- Returns
True is the current prim path corresponds to a valid prim in stage. False otherwise.
- Return type
bool
Example:
>>> # given an existing and valid prim >>> prims.is_valid() True
- is_visual_material_applied() bool
Check if there is a visual material applied
- Returns
True if there is a visual material applied. False otherwise.
- Return type
bool
Example:
>>> # given a visual material applied >>> prim.is_visual_material_applied() True
- 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.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- Return type
bool
Example:
>>> # for a wrapped articulation (where the root prim has the Physics Articulation Root property applied) >>> prim.non_root_articulation_link False
- open() None
Applies actions to the articulation that opens the gripper (ex: to release an object held).
- post_reset()
Reset the prim to its default state (position and orientation).
Note
For an articulation, in addition to configuring the root prim’s default position and spatial orientation (defined via the
set_default_state
method), the joint’s positions, velocities, and efforts (defined via theset_joints_default_state
method) are imposedExample:
>>> prim.post_reset()
- 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
Set the angular velocity of the rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- 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
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- 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)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- 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
Set prim’s pose with respect to the local frame (the prim’s parent frame).
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- 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.
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_local_pose(translation=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_local_scale(scale: Optional[Sequence[float]]) None
Set 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.
Example:
>>> # scale prim 10 times smaller >>> prim.set_local_scale(np.array([0.1, 0.1, 0.1]))
- set_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- 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.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_visibility(visible: bool) None
Set the visibility of the prim in stage
- Parameters
visible (bool) – flag to set the visibility of the usd prim in stage.
Example:
>>> # make prim not visible in the stage >>> prim.set_visibility(visible=False)
- set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None
Ses prim’s pose with respect to the world’s frame
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- 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.
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_world_pose(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
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
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.
Example:
>>> from omni.isaac.core.materials import OmniGlass >>> >>> # create a dark-red glass visual material >>> material = OmniGlass( ... prim_path="/World/material/glass", # path to the material prim to create ... ior=1.25, ... depth=0.001, ... thin_walled=False, ... color=np.array([0.5, 0.0, 0.0]) ... ) >>> prim.apply_visual_material(material)
- close() None
Applies actions to the articulation that closes the gripper (ex: to hold an object).
- disable_rigid_body_physics() None
Disable the rigid body physics
When disabled, the object will not be moved by external forces such as gravity and collisions
Example:
>>> prim.disable_rigid_body_physics()
- enable_rigid_body_physics() None
Enable the rigid body physics
When enabled, the object will be moved by external forces such as gravity and collisions
Example:
>>> prim.enable_rigid_body_physics()
- 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
- get_angular_velocity()
Get the angular velocity of the rigid body
- 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
Return 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
Example:
>>> # given a visual material applied >>> prim.get_applied_visual_material() <omni.isaac.core.materials.omni_glass.OmniGlass object at 0x7f36263106a0>
- get_com() float
Get the center of mass pose of the rigid body
- Returns
position of the center of mass of the rigid body. np.ndarray: orientation of the center of mass of the rigid body.
- Return type
np.ndarray
- get_current_dynamic_state() omni.isaac.core.utils.types.DynamicState
Get the current rigid body state (position, orientation and linear and angular velocities)
- Returns
the dynamic state of the rigid body prim
- Return type
Example:
>>> # for the example the rigid body is in free fall >>> state = prim.get_current_dynamic_state() >>> state <omni.isaac.core.utils.types.DynamicState object at 0x7f740b36f670> >>> state.position [ 0.99999857 2.0000017 -74.2862 ] >>> state.orientation [ 1.0000000e+00 -2.3961178e-07 -4.9891562e-09 4.9388258e-09] >>> state.linear_velocity [ 0. 0. -38.09554] >>> state.angular_velocity [0. 0. 0.]
- 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
Get the density of the rigid body
- Returns
density of the rigid body.
- Return type
float
Example:
>>> prim.get_density() 0
- get_linear_velocity() numpy.ndarray
Get the linear velocity of the rigid body
- Returns
current linear velocity of the the rigid prim. Shape (3,).
- Return type
np.ndarray
Example:
>>> prim.get_linear_velocity() [ 1.0812164e-04 6.1415871e-05 -2.1341663e-04]
- get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]
Get prim’s pose with respect to the local frame (the prim’s parent frame)
- Returns
first index is the position in the local frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the local frame
- Return type
Tuple[np.ndarray, np.ndarray]
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_local_pose() >>> position [0. 0. 0.] >>> orientation [0. 0. 0.]
- get_local_scale() numpy.ndarray
Get 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
Example:
>>> prim.get_local_scale() [1. 1. 1.]
- get_mass() float
Get the mass of the rigid body
- Returns
mass of the rigid body in kg.
- Return type
float
Example:
>>> prim.get_mass() 0
- get_sleep_threshold() float
Get the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- 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
Example:
>>> prim.get_sleep_threshold() 5e-05
- get_visibility() bool
- Returns
true if the prim is visible in stage. false otherwise.
- Return type
bool
Example:
>>> # get the visible state of an visible prim on the stage >>> prim.get_visibility() True
- get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]
Get prim’s pose with respect to the world’s frame
- Returns
first index is the position in the world frame (with shape (3, )). Second index is quaternion orientation (with shape (4, )) in the world frame
- Return type
Tuple[np.ndarray, np.ndarray]
Example:
>>> # if the prim is in position (1.0, 0.5, 0.0) with respect to the world frame >>> position, orientation = prim.get_world_pose() >>> position [1. 0.5 0. ] >>> orientation [1. 0. 0. 0.]
- get_world_scale() numpy.ndarray
Get 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
Example:
>>> prim.get_world_scale() [1. 1. 1.]
- 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
Check if the prim path has a valid USD Prim at it
- Returns
True is the current prim path corresponds to a valid prim in stage. False otherwise.
- Return type
bool
Example:
>>> # given an existing and valid prim >>> prims.is_valid() True
- is_visual_material_applied() bool
Check if there is a visual material applied
- Returns
True if there is a visual material applied. False otherwise.
- Return type
bool
Example:
>>> # given a visual material applied >>> prim.is_visual_material_applied() True
- property name: Optional[str]
Returns: str: name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool
Used to query if the prim is a non root articulation link
- Returns
True if the prim itself is a non root link
- Return type
bool
Example:
>>> # for a wrapped articulation (where the root prim has the Physics Articulation Root property applied) >>> prim.non_root_articulation_link False
- open() None
Applies actions to the articulation that opens the gripper (ex: to release an object held).
- post_reset()
Reset the prim to its default state (position and orientation).
Note
For an articulation, in addition to configuring the root prim’s default position and spatial orientation (defined via the
set_default_state
method), the joint’s positions, velocities, and efforts (defined via theset_joints_default_state
method) are imposedExample:
>>> prim.post_reset()
- 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
Set the angular velocity of the rigid body in stage
Warning
This method will immediately set the articulation state
- Parameters
velocity (np.ndarray) – angular velocity to set the rigid prim to. Shape (3,).
- set_com(position: numpy.ndarray, orientation: numpy.ndarray) None
Set the center of mass pose of the rigid body
- Parameters
position (np.ndarray) – center of mass position. Shape (3,).
orientation (np.ndarray) – center of mass orientation. Shape (4,).
- 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
Set the density of the rigid body
- Parameters
mass (float) – density of the rigid body.
Example:
>>> prim.set_density(0.9)
- set_direction(value: float) None
- set_force_limit(value: float) None
- set_linear_velocity(velocity: numpy.ndarray)
Set the linear velocity of the rigid body in stage
Warning
This method will immediately set the rigid prim state
- 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
Set prim’s pose with respect to the local frame (the prim’s parent frame).
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- 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.
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_local_pose(translation=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- set_local_scale(scale: Optional[Sequence[float]]) None
Set 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.
Example:
>>> # scale prim 10 times smaller >>> prim.set_local_scale(np.array([0.1, 0.1, 0.1]))
- set_mass(mass: float) None
Set the mass of the rigid body
- Parameters
mass (float) – mass of the rigid body in kg.
Example:
>>> prim.set_mass(1.0)
- set_sleep_threshold(threshold: float) None
Set the threshold for the rigid body to enter a sleep state
Search for Rigid Body Dynamics > Sleeping in PhysX docs for more details
- 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.
Example:
>>> prim.set_sleep_threshold(1e-5)
- set_torque_limit(value: float) None
- set_translate(value: float) None
- set_visibility(visible: bool) None
Set the visibility of the prim in stage
- Parameters
visible (bool) – flag to set the visibility of the usd prim in stage.
Example:
>>> # make prim not visible in the stage >>> prim.set_visibility(visible=False)
- set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None
Ses prim’s pose with respect to the world’s frame
Warning
This method will change (teleport) the prim pose immediately to the indicated value
- 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.
Hint
This method belongs to the methods used to set the prim state
Example:
>>> prim.set_world_pose(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1., 0., 0., 0.]))
- update() None