Franka Robot [omni.isaac.franka]
Franka
- class Franka(prim_path: str, name: str = 'franka_robot', usd_path: Optional[str] = None, position: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, end_effector_prim_name: Optional[str] = None, gripper_dof_names: Optional[List[str]] = None, gripper_open_position: Optional[numpy.ndarray] = None, gripper_closed_position: Optional[numpy.ndarray] = None, deltas: Optional[numpy.ndarray] = None)
 [summary]
- Parameters
 prim_path (str) – [description]
name (str, optional) – [description]. Defaults to “franka_robot”.
usd_path (Optional[str], optional) – [description]. Defaults to None.
position (Optional[np.ndarray], optional) – [description]. Defaults to None.
orientation (Optional[np.ndarray], optional) – [description]. Defaults to None.
end_effector_prim_name (Optional[str], optional) – [description]. Defaults to None.
gripper_dof_names (Optional[List[str]], optional) – [description]. Defaults to None.
gripper_open_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
gripper_closed_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
- apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None
 Apply joint positions, velocities and/or efforts to control an articulation
- 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.
Hint
High stiffness makes the joints snap faster and harder to the desired target, and higher damping smoothes but also slows down the joint’s movement to target
For position control, set relatively high stiffness and low damping (to reduce vibrations)
For velocity control, stiffness must be set to zero with a non-zero damping
For effort control, stiffness and damping must be set to zero
Example:
>>> from omni.isaac.core.utils.types import ArticulationAction >>> >>> # move all the robot joints to the indicated position >>> action = ArticulationAction(joint_positions=np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04])) >>> prim.apply_action(action) >>> >>> # close the robot fingers: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 0.0 >>> action = ArticulationAction(joint_positions=np.array([0.0, 0.0]), joint_indices=np.array([7, 8])) >>> prim.apply_action(action)
- 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)
- disable_gravity() None
 Keep gravity from affecting the robot
Example:
>>> prim.disable_gravity()
- property dof_names: List[str]
 List of prim names for each DOF.
- Returns
 prim names
- Return type
 list(string)
Example:
>>> prim.dof_names ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7', 'panda_finger_joint1', 'panda_finger_joint2']
- property dof_properties: numpy.ndarray
 Articulation DOF properties
DOF properties Index
Property name
Description
0
typeDOF type: invalid/unknown/uninitialized (0), rotation (1), translation (2)
1
hasLimitsWhether the DOF has limits
2
lowerLower DOF limit (in radians or meters)
3
upperUpper DOF limit (in radians or meters)
4
driveModeDrive mode for the DOF: force (1), acceleration (2)
5
maxVelocityMaximum DOF velocity. In radians/s, or stage_units/s
6
maxEffortMaximum DOF effort. In N or N*stage_units
7
stiffnessDOF stiffness
8
dampingDOF damping
- Returns
 named NumPy array of shape (num_dof, 9)
- Return type
 np.ndarray
Example:
>>> # get properties for all DOFs >>> prim.dof_properties [(1, True, -2.8973, 2.8973, 1, 1.0000000e+01, 5220., 60000., 3000.) (1, True, -1.7628, 1.7628, 1, 1.0000000e+01, 5220., 60000., 3000.) (1, True, -2.8973, 2.8973, 1, 5.9390470e+36, 5220., 60000., 3000.) (1, True, -3.0718, -0.0698, 1, 5.9390470e+36, 5220., 60000., 3000.) (1, True, -2.8973, 2.8973, 1, 5.9390470e+36, 720., 25000., 3000.) (1, True, -0.0175, 3.7525, 1, 5.9390470e+36, 720., 15000., 3000.) (1, True, -2.8973, 2.8973, 1, 1.0000000e+01, 720., 5000., 3000.) (2, True, 0. , 0.04 , 1, 3.4028235e+38, 720., 6000., 1000.) (2, True, 0. , 0.04 , 1, 3.4028235e+38, 720., 6000., 1000.)] >>> >>> # property names >>> prim.dof_properties.dtype.names ('type', 'hasLimits', 'lower', 'upper', 'driveMode', 'maxVelocity', 'maxEffort', 'stiffness', 'damping') >>> >>> # get DOF upper limits >>> prim.dof_properties["upper"] [ 2.8973 1.7628 2.8973 -0.0698 2.8973 3.7525 2.8973 0.04 0.04 ] >>> >>> # get the last DOF (panda_finger_joint2) upper limit >>> prim.dof_properties["upper"][8] # or prim.dof_properties[8][3] 0.04
- enable_gravity() None
 Gravity will affect the robot
Example:
>>> prim.enable_gravity()
- property end_effector: omni.isaac.core.prims.rigid_prim.RigidPrim
 [summary]
- Returns
 [description]
- Return type
 
- get_angular_velocity() numpy.ndarray
 Get the angular velocity of the root articulation prim
- Returns
 3D angular velocity vector. Shape (3,)
- Return type
 np.ndarray
Example:
>>> prim.get_angular_velocity() [0. 0. 0.]
- get_applied_action() omni.isaac.core.utils.types.ArticulationAction
 Get the last applied action
- Returns
 last applied action. Note: a dictionary is used as the object’s string representation
- Return type
 
Example:
>>> # last applied action: joint_positions -> [0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04] >>> prim.get_applied_action() {'joint_positions': [0.0, -1.0, 0.0, -2.200000047683716, 0.0, 2.4000000953674316, 0.800000011920929, 0.03999999910593033, 0.03999999910593033], 'joint_velocities': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], 'joint_efforts': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]}
- get_applied_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray
 Get the efforts applied to the joints set by the
set_joint_effortsmethod- Parameters
 joint_indices (Optional[Union[List, np.ndarray]], optional) – indices to specify which joints to read. Defaults to None (all joints)
- Raises
 Exception – If the handlers are not initialized
- Returns
 all or selected articulation joint applied efforts
- Return type
 np.ndarray
Example:
>>> # get all applied joint efforts >>> prim.get_applied_joint_efforts() [ 0. 0. 0. 0. 0. 0. 0. 0. 0.] >>> >>> # get finger applied efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_applied_joint_efforts(joint_indices=np.array([7, 8])) [0. 0.]
- 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_articulation_body_count() int
 Get the number of bodies (links) that make up the articulation
- Returns
 amount of bodies
- Return type
 int
Example:
>>> prim.get_articulation_body_count() 12
- get_articulation_controller() omni.isaac.core.controllers.articulation_controller.ArticulationController
 Get the articulation controller
Note
If no
articulation_controllerwas passed during class instantiation, a default controller of typeArticulationController(a Proportional-Derivative controller that can apply position targets, velocity targets and efforts) will be used- Returns
 articulation controller
- Return type
 
Example:
>>> prim.get_articulation_controller() <omni.isaac.core.controllers.articulation_controller.ArticulationController object at 0x7f04a0060190>
- get_default_state() omni.isaac.core.utils.types.XFormPrimState
 Get the default prim states (spatial position and orientation).
- Returns
 an object that contains the default state of the prim (position and orientation)
- Return type
 
Example:
>>> state = prim.get_default_state() >>> state <omni.isaac.core.utils.types.XFormPrimState object at 0x7f33addda650> >>> >>> state.position [-4.5299529e-08 -1.8347054e-09 -2.8610229e-08] >>> state.orientation [1. 0. 0. 0.]
- get_dof_index(dof_name: str) int
 Get a DOF index given its name
- Parameters
 dof_name (str) – name of the DOF
- Returns
 DOF index
- Return type
 int
Example:
>>> prim.get_dof_index("panda_finger_joint2") 8
- get_enabled_self_collisions() int
 Get the enable self collisions flag (
physxArticulation:enabledSelfCollisions)- Returns
 self collisions flag (boolean interpreted as int)
- Return type
 int
Example:
>>> prim.get_enabled_self_collisions() 0
- get_joint_positions(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray
 Get the articulation joint positions
- Parameters
 joint_indices (Optional[Union[List, np.ndarray]], optional) – indices to specify which joints to read. Defaults to None (all joints)
- Returns
 all or selected articulation joint positions
- Return type
 np.ndarray
Example:
>>> # get all joint positions >>> prim.get_joint_positions() [ 1.1999920e-02 -5.6962633e-01 1.3480479e-08 -2.8105433e+00 6.8284894e-06 3.0301569e+00 7.3234749e-01 3.9912373e-02 3.9999999e-02] >>> >>> # get finger positions: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_joint_positions(joint_indices=np.array([7, 8])) [0.03991237 3.9999999e-02]
- get_joint_velocities(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray
 Get the articulation joint velocities
- Parameters
 joint_indices (Optional[Union[List, np.ndarray]], optional) – indices to specify which joints to read. Defaults to None (all joints)
- Returns
 all or selected articulation joint velocities
- Return type
 np.ndarray
Example:
>>> # get all joint velocities >>> prim.get_joint_velocities() [ 1.91603772e-06 -7.67638255e-03 -2.19138826e-07 1.10636465e-02 -4.63412944e-05 3.48245539e-02 8.84692147e-02 5.40335372e-04 1.02849208e-05] >>> >>> # get finger velocities: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_joint_velocities(joint_indices=np.array([7, 8])) [5.4033537e-04 1.0284921e-05]
- get_joints_default_state() omni.isaac.core.utils.types.JointsState
 Get the default joint states (positions and velocities).
- Returns
 an object that contains the default joint positions and velocities
- Return type
 
Example:
>>> state = prim.get_joints_default_state() >>> state <omni.isaac.core.utils.types.JointsState object at 0x7f04a0061240> >>> >>> state.positions [ 0.012 -0.57000005 0. -2.81 0. 3.037 0.785398 0.04 0.04 ] >>> state.velocities [0. 0. 0. 0. 0. 0. 0. 0. 0.]
- get_joints_state() omni.isaac.core.utils.types.JointsState
 Get the current joint states (positions and velocities)
- Returns
 an object that contains the current joint positions and velocities
- Return type
 
Example:
>>> state = prim.get_joints_state() >>> state <omni.isaac.core.utils.types.JointsState object at 0x7f02f6df57b0> >>> >>> state.positions [ 1.1999920e-02 -5.6962633e-01 1.3480479e-08 -2.8105433e+00 6.8284894e-06 3.0301569e+00 7.3234749e-01 3.9912373e-02 3.9999999e-02] >>> state.velocities [ 1.91603772e-06 -7.67638255e-03 -2.19138826e-07 1.10636465e-02 -4.63412944e-05 245539e-02 8.84692147e-02 5.40335372e-04 1.02849208e-05]
- get_linear_velocity() numpy.ndarray
 Get the linear velocity of the root articulation prim
- Returns
 3D linear velocity vector. Shape (3,)
- Return type
 np.ndarray
Example:
>>> prim.get_linear_velocity() [0. 0. 0.]
- 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_measured_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray
 Returns the efforts computed/measured by the physics solver of the joint forces in the DOF motion direction
- Parameters
 joint_indices (Optional[Union[List, np.ndarray]], optional) – indices to specify which joints to read. Defaults to None (all joints)
- Raises
 Exception – If the handlers are not initialized
- Returns
 all or selected articulation joint measured efforts
- Return type
 np.ndarray
Example:
>>> # get all joint efforts >>> prim.get_measured_joint_efforts() [ 2.7897308e-06 -6.9083519e+00 -3.6398471e-06 1.9158335e+01 -4.3552645e-06 1.1866090e+00 -4.7079347e-06 3.2339853e-04 -3.2044132e-04] >>> >>> # get finger efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) >>> prim.get_measured_joint_efforts(joint_indices=np.array([7, 8])) [ 0.0003234 -0.00032044]
- get_measured_joint_forces(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray
 Get the measured joint reaction forces and torques (link incoming joint forces and torques) to external loads
Note
Since the name->index map for joints has not been exposed yet, it is possible to access the joint names and their indices through the articulation metadata.
prim._articulation_view._metadata.joint_names # list of names prim._articulation_view._metadata.joint_indices # dict of name: index
To retrieve a specific row for the link incoming joint force/torque use
joint_index + 1- Parameters
 joint_indices (Optional[Union[List, np.ndarray]], optional) – indices to specify which joints to read. Defaults to None (all joints)
- Raises
 Exception – If the handlers are not initialized
- Returns
 measured joint forces and torques. Shape is (num_joint + 1, 6). Row index 0 is the incoming joint of the base link. For the last dimension the first 3 values are for forces and the last 3 for torques
- Return type
 np.ndarray
Example:
>>> # get all measured joint forces and torques >>> prim.get_measured_joint_forces() [[ 0.0000000e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00 0.0000000e+00] [ 1.4995076e+02 4.2574748e-06 5.6364370e-04 4.8701895e-05 -6.9072924e+00 3.1881387e-05] [-2.8971717e-05 -1.0677823e+02 -6.8384506e+01 -6.9072924e+00 -5.4927128e-05 6.1222494e-07] [ 8.7120995e+01 -4.3871860e-05 -5.5795174e+01 5.3687054e-05 -2.4538563e+01 1.3333466e-05] [ 5.3519474e-05 -4.8109909e+01 6.0709282e+01 1.9157074e+01 -5.9258469e-05 8.2744418e-07] [-3.1691040e+01 2.3313689e-04 3.9990173e+01 -5.8968733e-05 -1.1863431e+00 2.2335558e-05] [-1.0809851e-04 1.5340537e+01 -1.5458489e+01 1.1863426e+00 6.1094368e-05 -1.5940281e-05] [-7.5418940e+00 -5.0814648e+00 -5.6512990e+00 -5.6385466e-05 3.8859999e-01 -3.4943256e-01] [ 4.7421460e+00 -3.1945827e+00 3.5528181e+00 5.5852943e-05 8.4794536e-03 7.6405057e-03] [ 4.0760727e+00 2.1640673e-01 -4.0513167e+00 -5.9565349e-04 1.1407082e-02 2.1432268e-06] [ 5.1680198e-03 -9.7754575e-02 -9.7093947e-02 -8.4155556e-12 -1.2910691e-12 -1.9347857e-11] [-5.1910793e-03 9.7588278e-02 -9.7106412e-02 8.4155573e-12 1.2910637e-12 -1.9347855e-11]] >>> >>> # get measured joint force and torque for the fingers >>> metadata = prim._articulation_view._metadata >>> joint_indices = 1 + np.array([ ... metadata.joint_indices["panda_finger_joint1"], ... metadata.joint_indices["panda_finger_joint2"], ... ]) >>> joint_indices [10 11] >>> prim.get_measured_joint_forces(joint_indices) [[ 5.1680198e-03 -9.7754575e-02 -9.7093947e-02 -8.4155556e-12 -1.2910691e-12 -1.9347857e-11] [-5.1910793e-03 9.7588278e-02 -9.7106412e-02 8.4155573e-12 1.2910637e-12 -1.9347855e-11]]
- get_sleep_threshold() float
 Get the threshold for articulations to enter a sleep state
Search for Articulations and Sleeping in PhysX docs for more details
- Returns
 sleep threshold
- Return type
 float
Example:
>>> prim.get_sleep_threshold() 0.005
- get_solver_position_iteration_count() int
 Get the solver (position) iteration count for the articulation
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
- Returns
 position iteration count
- Return type
 int
Example:
>>> prim.get_solver_position_iteration_count() 32
- get_solver_velocity_iteration_count() int
 Get the solver (velocity) iteration count for the articulation
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
- Returns
 velocity iteration count
- Return type
 int
Example:
>>> prim.get_solver_velocity_iteration_count() 32
- get_stabilization_threshold() float
 Get the mass-normalized kinetic energy below which the articulation may participate in stabilization
Search for Stabilization Threshold in PhysX docs for more details
- Returns
 stabilization threshold
- Return type
 float
Example:
>>> prim.get_stabilization_threshold() 0.0009999999
- 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.]
- get_world_velocity() numpy.ndarray
 Get the articulation root velocity
- Returns
 current velocity of the the root prim. Shape (3,).
- Return type
 np.ndarray
- property gripper: omni.isaac.manipulators.grippers.parallel_gripper.ParallelGripper
 [summary]
- Returns
 [description]
- Return type
 
- property handles_initialized: bool
 Check if articulation handler is initialized
- Returns
 whether the handler was initialized
- Return type
 bool
Example:
>>> prim.handles_initialized True
- initialize(physics_sim_view=None) None
 [summary]
- 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
- property num_bodies: int
 Number of articulation links
- Returns
 number of links
- Return type
 int
Example:
>>> prim.num_bodies 9
- property num_dof: int
 Number of DOF of the articulation
- Returns
 amount of DOFs
- Return type
 int
Example:
>>> prim.num_dof 9
- post_reset() None
 [summary]
- 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 root articulation prim
Warning
This method will immediately set the articulation state
- Parameters
 velocity (np.ndarray) – 3D angular velocity vector. Shape (3,)
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> prim.set_angular_velocity(np.array([0.1, 0.0, 0.0]))
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None
 Set 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.
Example:
>>> # configure default state >>> prim.set_default_state(position=np.array([1.0, 0.5, 0.0]), orientation=np.array([1, 0, 0, 0])) >>> >>> # set default states during post-reset >>> prim.post_reset()
- set_enabled_self_collisions(flag: bool) None
 Set the enable self collisions flag (
physxArticulation:enabledSelfCollisions)- Parameters
 flag (bool) – whether to enable self collisions
Example:
>>> prim.set_enabled_self_collisions(True)
- set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None
 Set the articulation joint efforts
Note
This method can be used for effort control. For this purpose, there must be no joint drive or the stiffness and damping must be set to zero.
- Parameters
 efforts (np.ndarray) – articulation joint efforts
joint_indices (Optional[Union[list, np.ndarray]], optional) – indices to specify which joints to manipulate. Defaults to None (all joints)
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> # set all the robot joint efforts to 0.0 >>> prim.set_joint_efforts(np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])) >>> >>> # set only the fingers efforts: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 10 >>> prim.set_joint_efforts(np.array([10, 10]), joint_indices=np.array([7, 8]))
- set_joint_positions(positions: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None
 Set the articulation joint positions
Warning
This method will immediately set (teleport) the affected joints to the indicated value. Use the
apply_actionmethod to control robot joints.- Parameters
 positions (np.ndarray) – articulation joint positions
joint_indices (Optional[Union[list, np.ndarray]], optional) – indices to specify which joints to manipulate. Defaults to None (all joints)
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> # set all the robot joints >>> prim.set_joint_positions(np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04])) >>> >>> # set only the fingers in closed position: panda_finger_joint1 (7) and panda_finger_joint2 (8) to 0.0 >>> prim.set_joint_positions(np.array([0.04, 0.04]), joint_indices=np.array([7, 8]))
- set_joint_velocities(velocities: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None
 Set the articulation joint velocities
Warning
This method will immediately set the affected joints to the indicated value. Use the
apply_actionmethod to control robot joints.- Parameters
 velocities (np.ndarray) – articulation joint velocities
joint_indices (Optional[Union[list, np.ndarray]], optional) – indices to specify which joints to manipulate. Defaults to None (all joints)
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> # set all the robot joint velocities to 0.0 >>> prim.set_joint_velocities(np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])) >>> >>> # set only the fingers velocities: panda_finger_joint1 (7) and panda_finger_joint2 (8) to -0.01 >>> prim.set_joint_velocities(np.array([-0.01, -0.01]), joint_indices=np.array([7, 8]))
- set_joints_default_state(positions: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.ndarray] = None) None
 Set the joint default states (positions, velocities and/or efforts) to be applied after each reset.
Note
The default states will be set during post-reset (e.g., calling
.post_reset()orworld.reset()methods)- Parameters
 positions (Optional[np.ndarray], optional) – joint positions. Defaults to None.
velocities (Optional[np.ndarray], optional) – joint velocities. Defaults to None.
efforts (Optional[np.ndarray], optional) – joint efforts. Defaults to None.
Example:
>>> # configure default joint states >>> prim.set_joints_default_state( ... positions=np.array([0.0, -1.0, 0.0, -2.2, 0.0, 2.4, 0.8, 0.04, 0.04]), ... velocities=np.zeros(shape=(prim.num_dof,)), ... efforts=np.zeros(shape=(prim.num_dof,)) ... ) >>> >>> # set default states during post-reset >>> prim.post_reset()
- set_linear_velocity(velocity: numpy.ndarray) None
 Set the linear velocity of the root articulation prim
Warning
This method will immediately set the articulation state
- Parameters
 velocity (np.ndarray) – 3D linear velocity vector. Shape (3,).
Hint
This method belongs to the methods used to set the articulation kinematic state:
set_linear_velocity,set_angular_velocity,set_joint_positions,set_joint_velocities,set_joint_effortsExample:
>>> prim.set_linear_velocity(np.array([0.1, 0.0, 0.0]))
- 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_sleep_threshold(threshold: float) None
 Set the threshold for articulations to enter a sleep state
Search for Articulations and Sleeping in PhysX docs for more details
- Parameters
 threshold (float) – sleep threshold
Example:
>>> prim.set_sleep_threshold(0.01)
- set_solver_position_iteration_count(count: int) None
 Set the solver (position) iteration count for the articulation
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
Warning
Setting a higher number of iterations may improve the fidelity of the simulation, although it may affect its performance.
- Parameters
 count (int) – position iteration count
Example:
>>> prim.set_solver_position_iteration_count(64)
- set_solver_velocity_iteration_count(count: int)
 Set the solver (velocity) iteration count for the articulation
The solver iteration count determines how accurately contacts, drives, and limits are resolved. Search for Solver Iteration Count in PhysX docs for more details.
Warning
Setting a higher number of iterations may improve the fidelity of the simulation, although it may affect its performance.
- Parameters
 count (int) – velocity iteration count
Example:
>>> prim.set_solver_velocity_iteration_count(64)
- set_stabilization_threshold(threshold: float) None
 Set the mass-normalized kinetic energy below which the articulation may participate in stabilization
Search for Stabilization Threshold in PhysX docs for more details
- Parameters
 threshold (float) – stabilization threshold
Example:
>>> prim.set_stabilization_threshold(0.005)
- 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.]))
- set_world_velocity(velocity: numpy.ndarray)
 Set the articulation root velocity
- Parameters
 velocity (np.ndarray) – linear and angular velocity to set the root prim to. Shape (6,).
Franka Kinematics Solver
- class KinematicsSolver(robot_articulation: omni.isaac.core.articulations.articulation.Articulation, end_effector_frame_name: Optional[str] = None)
 Kinematics Solver for Franka robot. This class loads a LulaKinematicsSovler object
- Parameters
 robot_articulation (Articulation) – An initialized Articulation object representing this Franka
end_effector_frame_name (Optional[str]) – The name of the Franka end effector. If None, an end effector link will be automatically selected. Defaults to None.
- compute_end_effector_pose(position_only=False) Tuple[numpy.array, numpy.array]
 Compute the pose of the robot end effector using the simulated robot’s current joint positions
- Parameters
 position_only (bool) – If True, only the frame positions need to be calculated. The returned rotation may be left undefined.
- Returns
 position: Translation vector describing the translation of the robot end effector relative to the USD global frame (in stage units)
rotation: (3x3) rotation matrix describing the rotation of the frame relative to the USD stage global frame
- Return type
 Tuple[np.array,np.array]
- compute_inverse_kinematics(target_position: numpy.array, target_orientation: Optional[numpy.array] = None, position_tolerance: Optional[float] = None, orientation_tolerance: Optional[float] = None) Tuple[omni.isaac.core.utils.types.ArticulationAction, bool]
 Compute inverse kinematics for the end effector frame using the current robot position as a warm start. The result is returned in an articulation action that can be directly applied to the robot.
- Parameters
 target_position (np.array) – target translation of the target frame (in stage units) relative to the USD stage origin
target_orientation (np.array) – target orientation of the target frame relative to the USD stage global frame. Defaults to None.
position_tolerance (float) – l-2 norm of acceptable position error (in stage units) between the target and achieved translations. Defaults to None.
tolerance (orientation) – magnitude of rotation (in radians) separating the target orientation from the achieved orienatation. orientation_tolerance is well defined for values between 0 and pi. Defaults to None.
- Returns
 ik_result: An ArticulationAction that can be applied to the robot to move the end effector frame to the desired position.
success: Solver converged successfully
- Return type
 Tuple[ArticulationAction, bool]
- get_end_effector_frame() str
 Get the end effector frame
- Returns
 Name of the end effector frame
- Return type
 str
- get_joints_subset() omni.isaac.core.articulations.articulation_subset.ArticulationSubset
 - Returns
 A wrapper class for querying USD robot joint states in the order expected by the kinematics solver
- Return type
 ArticulationSubset
- get_kinematics_solver() omni.isaac.motion_generation.kinematics_interface.KinematicsSolver
 Get the underlying KinematicsSolver instance used by this class.
- Returns
 A class that can solve forward and inverse kinematics for a specified robot.
- Return type
 
- set_end_effector_frame(end_effector_frame_name: str) None
 Set the name for the end effector frame. If the frame is not recognized by the internal KinematicsSolver instance, an error will be thrown
- Parameters
 end_effector_frame_name (str) – Name of the robot end effector frame.
Franka Controllers
- class PickPlaceController(name: str, gripper: omni.isaac.manipulators.grippers.parallel_gripper.ParallelGripper, robot_articulation: omni.isaac.core.articulations.articulation.Articulation, end_effector_initial_height: Optional[float] = None, events_dt: Optional[List[float]] = None)
 [summary]
- Parameters
 name (str) – [description]
gripper (ParallelGripper) – [description]
robot_articulation (Articulation) – [description]
end_effector_initial_height (Optional[float], optional) – [description]. Defaults to None.
events_dt (Optional[List[float]], optional) – [description]. Defaults to None.
- 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.
- class RMPFlowController(name: str, robot_articulation: omni.isaac.core.articulations.articulation.Articulation, physics_dt: float = 0.016666666666666666)
 [summary]
- Parameters
 name (str) – [description]
robot_articulation (Articulation) – [description]
physics_dt (float, optional) – [description]. Defaults to 1.0/60.0.
- add_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/builds/omniverse/isaac/omni_isaac_sim/_build/linux-x86_64/debug/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>, static: bool = False) None
 Add an object from omni.isaac.core.objects as an obstacle to the motion_policy
- Parameters
 obstacle (omni.isaac.core.objects) – Dynamic, Visual, or Fixed object from omni.isaac.core.objects
static (bool) – If True, the obstacle may be assumed by the MotionPolicy to remain stationary over time
- forward(target_end_effector_position: numpy.ndarray, target_end_effector_orientation: Optional[numpy.ndarray] = None) omni.isaac.core.utils.types.ArticulationAction
 Compute an ArticulationAction representing the desired robot state for the next simulation frame
- Parameters
 target_translation (nd.array) – Translation vector (3x1) for robot end effector. Target translation should be specified in the same units as the USD stage, relative to the stage origin.
target_orientation (Optional[np.ndarray], optional) – Quaternion of desired rotation for robot end effector relative to USD stage global frame. Target orientation defaults to None, which means that the robot may reach the target with any orientation.
- Returns
 A wrapper object containing the desired next state for the robot
- Return type
 
- get_articulation_motion_policy() omni.isaac.motion_generation.articulation_motion_policy.ArticulationMotionPolicy
 Get ArticulationMotionPolicy that was passed to this class on initialization
- Returns
 a wrapper around a MotionPolicy for computing ArticulationActions that can be directly applied to the robot
- Return type
 
- get_motion_policy() omni.isaac.motion_generation.motion_policy_interface.MotionPolicy
 Get MotionPolicy object that is being used to generate robot motions
- Returns
 An instance of a MotionPolicy that is being used to compute robot motions
- Return type
 
- remove_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/builds/omniverse/isaac/omni_isaac_sim/_build/linux-x86_64/debug/exts/omni.isaac.core/omni/isaac/core/objects/__init__.py'>) None
 Remove and added obstacle from the motion_policy
- Parameters
 obstacle (omni.isaac.core.objects) – Object from omni.isaac.core.objects that has been added to the motion_policy
- reset()
 
- class StackingController(name: str, gripper: omni.isaac.manipulators.grippers.parallel_gripper.ParallelGripper, robot_articulation: omni.isaac.core.articulations.articulation.Articulation, picking_order_cube_names: List[str], robot_observation_name: str)
 [summary]
- Parameters
 name (str) – [description]
gripper (ParallelGripper) – [description]
robot_prim_path (str) – [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.
Franka Tasks
- class FollowTarget(name: str = 'franka_follow_target', target_prim_path: Optional[str] = None, target_name: Optional[str] = None, target_position: Optional[numpy.ndarray] = None, target_orientation: Optional[numpy.ndarray] = None, offset: Optional[numpy.ndarray] = None, franka_prim_path: Optional[str] = None, franka_robot_name: Optional[str] = None)
 [summary]
- Parameters
 name (str, optional) – [description]. Defaults to “franka_follow_target”.
target_prim_path (Optional[str], optional) – [description]. Defaults to None.
target_name (Optional[str], optional) – [description]. Defaults to None.
target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
target_orientation (Optional[np.ndarray], optional) – [description]. Defaults to None.
offset (Optional[np.ndarray], optional) – [description]. Defaults to None.
franka_prim_path (Optional[str], optional) – [description]. Defaults to None.
franka_robot_name (Optional[str], optional) – [description]. Defaults to None.
- add_obstacle(position: Optional[numpy.ndarray] = None)
 [summary]
- Parameters
 position (np.ndarray, optional) – [description]. Defaults to np.array([0.1, 0.1, 1.0]).
- calculate_metrics() dict
 [summary]
- cleanup() None
 [summary]
- property device
 
- get_description() str
 [summary]
- Returns
 [description]
- Return type
 str
- get_observations() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- get_obstacle_to_delete() None
 [summary]
- Returns
 [description]
- Return type
 [type]
- get_params() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- get_task_objects() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- is_done() bool
 [summary]
- property name: str
 [summary]
- Returns
 [description]
- Return type
 str
- obstacles_exist() bool
 [summary]
- Returns
 [description]
- Return type
 bool
- post_reset() None
 [summary]
- pre_step(time_step_index: int, simulation_time: float) None
 [summary]
- Parameters
 time_step_index (int) – [description]
simulation_time (float) – [description]
- remove_obstacle(name: Optional[str] = None) None
 [summary]
- Parameters
 name (Optional[str], optional) – [description]. Defaults to None.
- property scene: omni.isaac.core.scenes.scene.Scene
 Scene of the world
- Returns
 [description]
- Return type
 
- set_params(target_prim_path: Optional[str] = None, target_name: Optional[str] = None, target_position: Optional[numpy.ndarray] = None, target_orientation: Optional[numpy.ndarray] = None) None
 [summary]
- Parameters
 target_prim_path (Optional[str], optional) – [description]. Defaults to None.
target_name (Optional[str], optional) – [description]. Defaults to None.
target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
target_orientation (Optional[np.ndarray], optional) – [description]. Defaults to None.
- set_robot() omni.isaac.franka.franka.Franka
 [summary]
- Returns
 [description]
- Return type
 
- set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None
 [summary]
- Parameters
 scene (Scene) – [description]
- target_reached() bool
 [summary]
- Returns
 [description]
- Return type
 bool
- class PickPlace(name: str = 'franka_pick_place', cube_initial_position: Optional[numpy.ndarray] = None, cube_initial_orientation: Optional[numpy.ndarray] = None, target_position: Optional[numpy.ndarray] = None, cube_size: Optional[numpy.ndarray] = None, offset: Optional[numpy.ndarray] = None)
 [summary]
- Parameters
 name (str, optional) – [description]. Defaults to “franka_pick_place”.
cube_initial_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
cube_initial_orientation (Optional[np.ndarray], optional) – [description]. Defaults to None.
target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
cube_size (Optional[np.ndarray], optional) – [description]. Defaults to None.
offset (Optional[np.ndarray], optional) – [description]. Defaults to None.
- calculate_metrics() dict
 [summary]
- cleanup() None
 Called before calling a reset() on the world to removed temporary objects that were added during simulation for instance.
- property device
 
- get_description() str
 [summary]
- Returns
 [description]
- Return type
 str
- get_observations() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- get_params() dict
 - Gets the parameters of the task.
 This is defined differently for each task in order to access the task’s objects and values. Note that this is different from get_observations. Things like the robot name, block name..etc can be defined here for faster retrieval. should have the form of params_representation[“param_name”] = {“value”: param_value, “modifiable”: bool}
- Raises
 NotImplementedError – [description]
- Returns
 defined parameters of the task.
- Return type
 dict
- get_task_objects() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- is_done() bool
 [summary]
- property name: str
 [summary]
- Returns
 [description]
- Return type
 str
- post_reset() None
 Calls while doing a .reset() on the world.
- pre_step(time_step_index: int, simulation_time: float) None
 [summary]
- Parameters
 time_step_index (int) – [description]
simulation_time (float) – [description]
- property scene: omni.isaac.core.scenes.scene.Scene
 Scene of the world
- Returns
 [description]
- Return type
 
- set_params(cube_position: Optional[numpy.ndarray] = None, cube_orientation: Optional[numpy.ndarray] = None, target_position: Optional[numpy.ndarray] = None) None
 Changes the modifiable parameters of the task
- Raises
 NotImplementedError – [description]
- set_robot() omni.isaac.franka.franka.Franka
 [summary]
- Returns
 [description]
- Return type
 
- set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None
 [summary]
- Parameters
 scene (Scene) – [description]
- class Stacking(name: str = 'franka_stacking', target_position: Optional[numpy.ndarray] = None, cube_size: Optional[numpy.ndarray] = None, offset: Optional[numpy.ndarray] = None)
 [summary]
- Parameters
 name (str, optional) – [description]. Defaults to “franka_stacking”.
target_position (Optional[np.ndarray], optional) – [description]. Defaults to None.
cube_size (Optional[np.ndarray], optional) – [description]. Defaults to None.
offset (Optional[np.ndarray], optional) – [description]. Defaults to None.
- calculate_metrics() dict
 [summary]
- Raises
 NotImplementedError – [description]
- Returns
 [description]
- Return type
 dict
- cleanup() None
 Called before calling a reset() on the world to removed temporary objects that were added during simulation for instance.
- property device
 
- get_cube_names() List[str]
 [summary]
- Returns
 [description]
- Return type
 List[str]
- get_description() str
 [summary]
- Returns
 [description]
- Return type
 str
- get_observations() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- get_params() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- get_task_objects() dict
 [summary]
- Returns
 [description]
- Return type
 dict
- is_done() bool
 [summary]
- Raises
 NotImplementedError – [description]
- Returns
 [description]
- Return type
 bool
- property name: str
 [summary]
- Returns
 [description]
- Return type
 str
- post_reset() None
 [summary]
- pre_step(time_step_index: int, simulation_time: float) None
 [summary]
- Parameters
 time_step_index (int) – [description]
simulation_time (float) – [description]
- property scene: omni.isaac.core.scenes.scene.Scene
 Scene of the world
- Returns
 [description]
- Return type
 
- set_params(cube_name: Optional[str] = None, cube_position: Optional[str] = None, cube_orientation: Optional[str] = None, stack_target_position: Optional[str] = None) None
 [summary]
- Parameters
 cube_name (Optional[str], optional) – [description]. Defaults to None.
cube_position (Optional[str], optional) – [description]. Defaults to None.
cube_orientation (Optional[str], optional) – [description]. Defaults to None.
stack_target_position (Optional[str], optional) – [description]. Defaults to None.
- set_robot() omni.isaac.franka.franka.Franka
 [summary]
- Returns
 [description]
- Return type
 
- set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None
 [summary]
- Parameters
 scene (Scene) – [description]