Manipulators [omni.isaac.manipulators]
Single Manipulator
- class SingleManipulator(prim_path: str, end_effector_prim_name: str, name: str = 'single_manipulator', position: Optional[Sequence[float]] = None, translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None, scale: Optional[Sequence[float]] = None, visible: Optional[bool] = None, gripper: Optional[omni.isaac.manipulators.grippers.gripper.Gripper] = None)
Provides high level functions to set/ get properties and actions of a manipulator with a single end effector and optionally a gripper.
- Parameters
prim_path (str) – prim path of the Prim to encapsulate or create.
end_effector_prim_name (str) – end effector prim name to be used to track the rigid body that corresponds to the end effector.
name (str, optional) – shortname to be used as a key by Scene class. Note: needs to be unique if the object is added to the Scene. Defaults to “single_manipulator”.
position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.
translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.
orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world/ local frame of the prim (depends if translation or position is specified). quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.
scale (Optional[Sequence[float]], optional) – local scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.
visible (Optional[bool], optional) – set to false for an invisible prim in the stage while rendering. Defaults to True.
gripper (Gripper, optional) – Gripper to be used with the manipulator. Defaults to None.
- apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None
[summary]
- Parameters
control_actions (ArticulationAction) – actions to be applied for next physics step.
indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.
- Raises
Exception – [description]
- apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None
Used to apply visual material to the held prim and optionally its descendants.
- Parameters
visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.
weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.
- property articulation_handle: int
[summary]
- Returns
[description]
- Return type
int
- disable_gravity() None
Keep gravity from affecting the robot
- property dof_names: List[str]
List of prim names for each DOF.
- Returns
prim names
- Return type
list(string)
- property dof_properties: numpy.ndarray
[summary]
- Returns
[description]
- Return type
np.ndarray
- enable_gravity() None
Gravity will affect the robot
- property end_effector: omni.isaac.core.prims.rigid_prim.RigidPrim
Returns: RigidPrim: end effector of the manipulator (can be used to get its world pose, angular velocity..etc).
- get_angular_velocity() numpy.ndarray
[summary]
- Returns
[description]
- Return type
np.ndarray
- get_applied_action() omni.isaac.core.utils.types.ArticulationAction
[summary]
- Raises
Exception – [description]
- Returns
[description]
- Return type
- 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
- 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
- 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
- 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_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray
Deprecated function. Please use get_applied_joint_efforts instead.
- Parameters
joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.
- Raises
Exception – _description_
- Returns
_description_
- Return type
np.ndarray
- 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
- get_joints_state() omni.isaac.core.utils.types.JointsState
[summary]
- Returns
[description]
- Return type
- 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_sleep_threshold() float
[summary]
- Returns
[description]
- Return type
float
- get_solver_position_iteration_count() int
[summary]
- Returns
[description]
- Return type
int
- get_solver_velocity_iteration_count() int
[summary]
- Returns
[description]
- Return type
int
- get_stabilization_threshold() float
[summary]
- Returns
[description]
- Return type
float
- get_visibility() bool
- Returns
true if the prim is visible in stage. false otherwise.
- Return type
bool
- get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]
Gets prim’s pose with respect to the world’s frame.
- Returns
- first index is position in the world frame of the prim. shape is (3, ).
second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).
- Return type
Tuple[np.ndarray, np.ndarray]
- get_world_scale() numpy.ndarray
Gets prim’s scale with respect to the world’s frame.
- Returns
scale applied to the prim’s dimensions in the world frame. shape is (3, ).
- Return type
np.ndarray
- property gripper: omni.isaac.manipulators.grippers.gripper.Gripper
Returns: Gripper: gripper of the manipulator (can be used to open or close the gripper, get its world pose or angular velocity..etc).
- property handles_initialized: bool
[summary]
- Returns
[description]
- Return type
bool
- initialize(physics_sim_view: Optional[omni.physics.tensors.SimulationView] = None) None
- Create a physics simulation view if not passed and creates an articulation view using physX tensor api.
This needs to be called after each hard reset (i.e stop + play on the timeline) before interacting with any of the functions of this class.
- Parameters
physics_sim_view (omni.physics.tensors.SimulationView, optional) – current physics simulation view. Defaults to None.
- is_valid() bool
- Returns
True is the current prim path corresponds to a valid prim in stage. False otherwise.
- Return type
bool
- is_visual_material_applied() bool
- Returns
True if there is a visual material applied. False otherwise.
- Return type
bool
- property name: Optional[str]
Returns: str: name given to the prim when instantiating it. Otherwise None.
- property non_root_articulation_link: bool
_summary_
- Returns
_description_
- Return type
bool
- property num_dof: int
[summary]
- Returns
[description]
- Return type
int
- post_reset() None
Resets the manipulator, the end effector and the gripper to its default state.
- property prim: pxr.Usd.Prim
Returns: Usd.Prim: USD Prim object that this object holds.
- property prim_path: str
Returns: str: prim path in the stage.
- set_angular_velocity(velocity: numpy.ndarray) None
[summary]
- Parameters
velocity (np.ndarray) – [description]
- set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None
Sets the default state of the prim (position and orientation), that will be used after each reset.
- Parameters
position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.
orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.
- set_enabled_self_collisions(flag: bool) None
[summary]
- Parameters
flag (bool) – [description]
- set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None
[summary]
- Parameters
efforts (np.ndarray) – [description]
joint_indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.
- Raises
Exception – [description]
- set_joint_positions(positions: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None
[summary]
- Parameters
positions (np.ndarray) – [description]
indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.
- Raises
Exception – [description]
- set_joint_velocities(velocities: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None
[summary]
- Parameters
velocities (np.ndarray) – [description]
indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.
- Raises
Exception – [description]
- set_joints_default_state(positions: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.ndarray] = None) None
[summary]
- Parameters
positions (Optional[np.ndarray], optional) – [description]. Defaults to None.
velocities (Optional[np.ndarray], optional) – [description]. Defaults to None.
efforts (Optional[np.ndarray], optional) – [description]. Defaults to None.
- set_linear_velocity(velocity: numpy.ndarray)
Sets the linear velocity of the prim in stage.
- Parameters
velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).
- set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None
Sets prim’s pose with respect to the local frame (the prim’s parent frame).
- Parameters
translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.
orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.
- set_local_scale(scale: Optional[Sequence[float]]) None
Sets prim’s scale with respect to the local frame (the prim’s parent frame).
- Parameters
scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.
- set_sleep_threshold(threshold: float) None
[summary]
- Parameters
threshold (float) – [description]
- set_solver_position_iteration_count(count: int) None
[summary]
- Parameters
count (int) – [description]
- set_solver_velocity_iteration_count(count: int)
[summary]
- Parameters
count (int) – [description]
- set_stabilization_threshold(threshold: float) None
[summary]
- Parameters
threshold (float) – [description]
- set_visibility(visible: bool) None
Sets the visibility of the prim in stage.
- Parameters
visible (bool) – flag to set the visibility of the usd prim in stage.
- set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None
Sets prim’s pose with respect to the world’s frame.
- Parameters
position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.
orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.