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

[summary]

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

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

Raises

Exception – [description]

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

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

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

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

property articulation_handle: int

[summary]

Returns

[description]

Return type

int

disable_gravity() None

Keep gravity from affecting the robot

property dof_names: List[str]

List of prim names for each DOF.

Returns

prim names

Return type

list(string)

property dof_properties: numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

enable_gravity() None

Gravity will affect the robot

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

[summary]

Returns

[description]

Return type

RigidPrim

get_angular_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

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

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

ArticulationAction

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

Gets the efforts applied to the joints

Parameters

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

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

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

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

Returns

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

Return type

VisualMaterial

get_articulation_body_count() int

[summary]

Returns

[description]

Return type

int

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

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

Return type

ArticulationController

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

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

Return type

XFormPrimState

get_dof_index(dof_name: str) int

[summary]

Parameters

dof_name (str) – [description]

Returns

[description]

Return type

int

get_enabled_self_collisions() bool

[summary]

Returns

[description]

Return type

bool

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

_summary_

Parameters

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

Returns

_description_

Return type

np.ndarray

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

_summary_

Parameters

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

Returns

_description_

Return type

np.ndarray

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

Accessor for the default joints state.

Returns

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

Return type

JointsState

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

[summary]

Returns

[description]

Return type

JointsState

get_linear_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

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

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

Returns

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

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

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

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

Returns

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

Return type

np.ndarray

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

Returns the dof efforts computed/measured by the physics solver

Parameters

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

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

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

Gets the measured joint forces

Parameters

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

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_sleep_threshold() float

[summary]

Returns

[description]

Return type

float

get_solver_position_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_solver_velocity_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_stabilization_threshold() float

[summary]

Returns

[description]

Return type

float

get_visibility() bool
Returns

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

Return type

bool

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

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

Returns

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

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

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

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

Returns

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

Return type

np.ndarray

property gripper: omni.isaac.manipulators.grippers.parallel_gripper.ParallelGripper

[summary]

Returns

[description]

Return type

ParallelGripper

property handles_initialized: bool

[summary]

Returns

[description]

Return type

bool

initialize(physics_sim_view=None) None

[summary]

is_valid() bool
Returns

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

Return type

bool

is_visual_material_applied() bool
Returns

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

Return type

bool

property name: Optional[str]

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

_summary_

Returns

_description_

Return type

bool

property num_dof: int

[summary]

Returns

[description]

Return type

int

post_reset() None

[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

[summary]

Parameters

velocity (np.ndarray) – [description]

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

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

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

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

set_enabled_self_collisions(flag: bool) None

[summary]

Parameters

flag (bool) – [description]

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

[summary]

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

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

Raises

Exception – [description]

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

[summary]

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

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

Raises

Exception – [description]

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

[summary]

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

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

Raises

Exception – [description]

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

[summary]

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

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

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

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage.

Parameters

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

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

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

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

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

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

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

Parameters

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

set_sleep_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_solver_position_iteration_count(count: int) None

[summary]

Parameters

count (int) – [description]

set_solver_velocity_iteration_count(count: int)

[summary]

Parameters

count (int) – [description]

set_stabilization_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

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

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

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

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

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

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

KinematicsSolver

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

ArticulationAction

get_current_event() int
Returns

Current event/ phase of the state machine

Return type

int

is_done() bool
Returns

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

Return type

bool

is_paused() bool
Returns

True if the state machine is paused. Otherwise False.

Return type

bool

pause() None

Pauses the state machine’s time and phase.

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

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

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

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

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

  • Exception – events dt need have length of 10

resume() None

Resumes the state machine’s time and phase.

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 '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/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

ArticulationAction

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

ArticulationMotionPolicy

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

MotionPolicy

remove_obstacle(obstacle: <module 'omni.isaac.core.objects' from '/buildAgent/work/471f8e01c9575c12/_build/linux-x86_64/release/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

ArticulationAction

is_done() bool

[summary]

Returns

[description]

Return type

bool

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

[summary]

Parameters

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

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

Scene

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

Franka

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 temporarly 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

Scene

set_params(cube_position: Optional[numpy.ndarray] = None, cube_orientation: Optional[numpy.ndarray] = None, target_position: Optional[numpy.ndarray] = None) None

Changes the modifiable paramateres of the task

Raises

NotImplementedError – [description]

set_robot() omni.isaac.franka.franka.Franka

[summary]

Returns

[description]

Return type

Franka

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 temporarly 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

Scene

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

Franka

set_up_scene(scene: omni.isaac.core.scenes.scene.Scene) None

[summary]

Parameters

scene (Scene) – [description]