Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion source/extensions/omni.isaac.orbit/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.2.5"
version = "0.2.6"

# Description
title = "ORBIT framework for Robot Learning"
Expand Down
16 changes: 16 additions & 0 deletions source/extensions/omni.isaac.orbit/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,22 @@
Changelog
---------

0.2.6 (2023-03-16)
~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added the :class:`CollisionPropertiesCfg` to rigid/articulated object and robot base classes.
* Added the :class:`PhysicsMaterialCfg` to the :class:`SingleArm` class for tool sites.

Changed
^^^^^^^

* Changed the default control mode of the :obj:`PANDA_HAND_MIMIC_GROUP_CFG` to be from ``"v_abs"`` to ``"p_abs"``.
Using velocity control for the mimic group can cause the hand to move in a jerky manner.


0.2.5 (2023-03-08)
~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
PANDA_HAND_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
dof_names=["panda_finger_joint[1-2]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=0.2, torque_limit=200),
control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
control_cfg=ActuatorControlCfg(command_types=["p_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
mimic_multiplier={"panda_finger_joint.*": 1.0},
speed=0.1,
open_dof_pos=0.04,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,8 @@ def __init__(self, cfg: GripperActuatorGroupCfg, view: ArticulationView):

# create buffers
self._previous_dof_targets = torch.zeros(self.num_articulation, self.num_actuators, device=self.device)
# constants
self._ALL_INDICES = torch.arange(self.view.count, device=self.view._device, dtype=torch.long)

def __str__(self) -> str:
"""String representation of the actuator group."""
Expand Down Expand Up @@ -109,18 +111,25 @@ def _format_command(self, command: torch.Tensor) -> torch.Tensor:

We consider the following convention:

* Positive command -> open grippers
* Negative command -> close grippers
* Non-negative command (includes 0): open grippers
* Negative command: close grippers

Returns:
torch.Tensor: The target joint commands for the gripper.
"""
# FIXME: mimic joint positions -- Gazebo plugin seems to do this.
# The following is commented out because Isaac Sim doesn't support setting joint positions
# of particular dof indices properly. It sets joint positions and joint position targets for
# the whole robot, i.e. all previous position targets is lost.
# mimic_dof_pos = self._dof_pos[:, 0] * self._mimic_multiplier
# self.view.set_joint_positions(mimic_dof_pos, joint_indices=self.dof_indices)
# The following is commented out because Isaac Sim doesn't support setting joint positions
# of particular dof indices properly. It sets joint positions and joint position targets for
# the whole robot, i.e. all previous position targets is lost. This affects resetting the robot
# to a particular joint position.
# self.view._physics_sim_view.enable_warnings(False)
# # get current joint positions
# new_dof_pos = self.view._physics_view.get_dof_positions()
# # set joint positions of the mimic joints
# new_dof_pos[:, self.dof_indices] = self._dof_pos[:, 0].unsqueeze(1) * self._mimic_multiplier
# # set joint positions to the physics view
# self.view.set_joint_positions(new_dof_pos, self._ALL_INDICES)
# self.view._physics_sim_view.enable_warnings(True)

# process actions
if self.control_mode == "velocity":
Expand All @@ -134,7 +143,7 @@ def _format_command(self, command: torch.Tensor) -> torch.Tensor:
return dof_vel_targets
else:
# compute new command
dof_pos_targets = torch.where(command > 0, self._open_dof_pos, self._close_dof_pos)
dof_pos_targets = torch.where(command >= 0, self._open_dof_pos, self._close_dof_pos)
dof_pos_targets = dof_pos_targets * self._mimic_multiplier
# store new command
self._previous_dof_targets[:] = dof_pos_targets
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,23 +132,11 @@ def spawn(self, prim_path: str, translation: Sequence[float] = None, orientation

# TODO: What if prim already exists in the stage and spawn isn't called?
# apply rigid body properties
kit_utils.set_nested_rigid_body_properties(
prim_path,
linear_damping=self.cfg.rigid_props.linear_damping,
angular_damping=self.cfg.rigid_props.angular_damping,
max_linear_velocity=self.cfg.rigid_props.max_linear_velocity,
max_angular_velocity=self.cfg.rigid_props.max_angular_velocity,
max_depenetration_velocity=self.cfg.rigid_props.max_depenetration_velocity,
disable_gravity=self.cfg.rigid_props.disable_gravity,
retain_accelerations=self.cfg.rigid_props.retain_accelerations,
)
kit_utils.set_nested_rigid_body_properties(prim_path, **self.cfg.rigid_props.to_dict())
# apply collision properties
kit_utils.set_nested_collision_properties(prim_path, **self.cfg.collision_props.to_dict())
# articulation root settings
kit_utils.set_articulation_properties(
prim_path,
enable_self_collisions=self.cfg.articulation_props.enable_self_collisions,
solver_position_iteration_count=self.cfg.articulation_props.solver_position_iteration_count,
solver_velocity_iteration_count=self.cfg.articulation_props.solver_velocity_iteration_count,
)
kit_utils.set_articulation_properties(prim_path, **self.cfg.articulation_props.to_dict())

def initialize(self, prim_paths_expr: Optional[str] = None):
"""Initializes the PhysX handles and internal buffers.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,16 +33,32 @@ class RigidBodyPropertiesCfg:
angular_damping: Optional[float] = None
"""Angular damping coefficient."""
max_linear_velocity: Optional[float] = 1000.0
"""Maximum linear velocity for rigid bodies. Defaults to 1000.0."""
"""Maximum linear velocity for rigid bodies (in m/s). Defaults to 1000.0."""
max_angular_velocity: Optional[float] = 1000.0
"""Maximum angular velocity for rigid bodies. Defaults to 1000.0."""
"""Maximum angular velocity for rigid bodies (in rad/s). Defaults to 1000.0."""
max_depenetration_velocity: Optional[float] = 10.0
"""Maximum depenetration velocity permitted to be introduced by the solver. Defaults to 10.0."""
"""Maximum depenetration velocity permitted to be introduced by the solver (in m/s).
Defaults to 10.0."""
disable_gravity: Optional[bool] = False
"""Disable gravity for the actor. Defaults to False."""
retain_accelerations: Optional[bool] = None
"""Carries over forces/accelerations over sub-steps."""

@configclass
class CollisionPropertiesCfg:
"""Properties to apply to all collisions in the articulation."""

collision_enabled: Optional[bool] = None
"""Whether to enable or disable collisions."""
contact_offset: Optional[float] = None
"""Contact offset for the collision shape."""
rest_offset: Optional[float] = None
"""Rest offset for the collision shape."""
torsional_patch_radius: Optional[float] = None
"""Radius of the contact patch for applying torsional friction."""
min_torsional_patch_radius: Optional[float] = None
"""Minimum radius of the contact patch for applying torsional friction."""

@configclass
class ArticulationRootPropertiesCfg:
"""Properties to apply to articulation."""
Expand Down Expand Up @@ -85,5 +101,7 @@ class InitialStateCfg:
"""Initial state of the articulated object."""
rigid_props: RigidBodyPropertiesCfg = RigidBodyPropertiesCfg()
"""Properties to apply to all rigid bodies in the articulation."""
collision_props: CollisionPropertiesCfg = CollisionPropertiesCfg()
"""Properties to apply to all collisions in the articulation."""
articulation_props: ArticulationRootPropertiesCfg = ArticulationRootPropertiesCfg()
"""Properties to apply to articulation."""
Original file line number Diff line number Diff line change
Expand Up @@ -110,13 +110,9 @@ def spawn(self, prim_path: str, translation: Sequence[float] = None, orientation
# apply rigid body properties API
RigidPrim(prim_path=prim_path)
# -- set rigid body properties
kit_utils.set_nested_rigid_body_properties(
prim_path,
max_linear_velocity=self.cfg.rigid_props.max_linear_velocity,
max_angular_velocity=self.cfg.rigid_props.max_angular_velocity,
max_depenetration_velocity=self.cfg.rigid_props.max_depenetration_velocity,
disable_gravity=self.cfg.rigid_props.disable_gravity,
)
kit_utils.set_nested_rigid_body_properties(prim_path, **self.cfg.rigid_props.to_dict())
# apply collision properties
kit_utils.set_nested_collision_properties(prim_path, **self.cfg.collision_props.to_dict())
# create physics material
if self.cfg.physics_material is not None:
# -- resolve material path
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,35 @@ class MetaInfoCfg:
class RigidBodyPropertiesCfg:
"""Properties to apply to the rigid body."""

solver_position_iteration_count: Optional[int] = None
"""Solver position iteration counts for the body."""
solver_velocity_iteration_count: Optional[int] = None
"""Solver position iteration counts for the body."""
max_linear_velocity: Optional[float] = 1000.0
"""Maximum linear velocity for rigid bodies. Defaults to 1000.0."""
"""Maximum linear velocity for rigid bodies (in m/s). Defaults to 1000.0."""
max_angular_velocity: Optional[float] = 1000.0
"""Maximum angular velocity for rigid bodies. Defaults to 1000.0."""
"""Maximum angular velocity for rigid bodies (in rad/s). Defaults to 1000.0."""
max_depenetration_velocity: Optional[float] = 10.0
"""Maximum depenetration velocity permitted to be introduced by the solver. Defaults to 10.0."""
"""Maximum depenetration velocity permitted to be introduced by the solver (in m/s).
Defaults to 10.0."""
disable_gravity: Optional[bool] = False
"""Disable gravity for the actor. Defaults to False."""

@configclass
class CollisionPropertiesCfg:
"""Properties to apply to all collisions in the articulation."""

collision_enabled: Optional[bool] = None
"""Whether to enable or disable collisions."""
contact_offset: Optional[float] = None
"""Contact offset for the collision shape."""
rest_offset: Optional[float] = None
"""Rest offset for the collision shape."""
torsional_patch_radius: Optional[float] = None
"""Radius of the contact patch for applying torsional friction."""
min_torsional_patch_radius: Optional[float] = None
"""Minimum radius of the contact patch for applying torsional friction."""

@configclass
class PhysicsMaterialCfg:
"""Physics material applied to the rigid object."""
Expand Down Expand Up @@ -79,6 +99,8 @@ class InitialStateCfg:
"""Initial state of the rigid object."""
rigid_props: RigidBodyPropertiesCfg = RigidBodyPropertiesCfg()
"""Properties to apply to all rigid bodies in the object."""
collision_props: CollisionPropertiesCfg = CollisionPropertiesCfg()
"""Properties to apply to all collisions in the articulation."""
physics_material: Optional[PhysicsMaterialCfg] = PhysicsMaterialCfg()
"""Settings for the physics material to apply to the rigid object.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,10 @@ def euler_rpy_apply(rpy, xyz, degrees=False):
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
collision_props=LeggedRobotCfg.CollisionPropertiesCfg(
contact_offset=0.02,
rest_offset=0.0,
),
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
),
Expand Down Expand Up @@ -141,6 +145,10 @@ def euler_rpy_apply(rpy, xyz, degrees=False):
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
collision_props=LeggedRobotCfg.CollisionPropertiesCfg(
contact_offset=0.02,
rest_offset=0.0,
),
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,23 @@
"panda_joint5": 0.0,
"panda_joint6": 3.037,
"panda_joint7": 0.741,
"panda_finger_joint*": 0.035,
"panda_finger_joint*": 0.04,
},
dof_vel={".*": 0.0},
),
ee_info=SingleArmManipulatorCfg.EndEffectorFrameCfg(
body_name="panda_hand", pos_offset=(0.0, 0.0, 0.1034), rot_offset=(1.0, 0.0, 0.0, 0.0)
),
rigid_props=SingleArmManipulatorCfg.RigidBodyPropertiesCfg(
max_depenetration_velocity=5.0,
),
collision_props=SingleArmManipulatorCfg.CollisionPropertiesCfg(
contact_offset=0.005,
rest_offset=0.0,
),
articulation_props=SingleArmManipulatorCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True,
),
actuator_groups={
"panda_shoulder": ActuatorGroupCfg(
dof_names=["panda_joint[1-4]"],
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
collision_props=LeggedRobotCfg.CollisionPropertiesCfg(
contact_offset=0.02,
rest_offset=0.0,
),
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,6 @@ def feet_names(self) -> Sequence[str]:
def spawn(self, prim_path: str, translation: Sequence[float] = None, orientation: Sequence[float] = None):
# spawn the robot and set its location
super().spawn(prim_path, translation, orientation)
# alter physics collision properties
kit_utils.set_nested_collision_properties(prim_path, contact_offset=0.02, rest_offset=0.0)
# add physics material to the feet bodies!
if self.cfg.physics_material is not None:
# -- resolve material path
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def count(self) -> int:
@property
def device(self) -> str:
"""Memory device for computation."""
return self.articulations._device
return self.articulations._device # noqa: W0212

@property
def body_names(self) -> List[str]:
Expand Down Expand Up @@ -132,23 +132,11 @@ def spawn(self, prim_path: str, translation: Sequence[float] = None, orientation
carb.log_warn(f"A prim already exists at prim path: '{prim_path}'. Skipping...")

# apply rigid body properties
kit_utils.set_nested_rigid_body_properties(
prim_path,
linear_damping=self.cfg.rigid_props.linear_damping,
angular_damping=self.cfg.rigid_props.angular_damping,
max_linear_velocity=self.cfg.rigid_props.max_linear_velocity,
max_angular_velocity=self.cfg.rigid_props.max_angular_velocity,
max_depenetration_velocity=self.cfg.rigid_props.max_depenetration_velocity,
disable_gravity=self.cfg.rigid_props.disable_gravity,
retain_accelerations=self.cfg.rigid_props.retain_accelerations,
)
kit_utils.set_nested_rigid_body_properties(prim_path, **self.cfg.rigid_props.to_dict())
# apply collision properties
kit_utils.set_nested_collision_properties(prim_path, **self.cfg.collision_props.to_dict())
# articulation root settings
kit_utils.set_articulation_properties(
prim_path,
enable_self_collisions=self.cfg.articulation_props.enable_self_collisions,
solver_position_iteration_count=self.cfg.articulation_props.solver_position_iteration_count,
solver_velocity_iteration_count=self.cfg.articulation_props.solver_velocity_iteration_count,
)
kit_utils.set_articulation_properties(prim_path, **self.cfg.articulation_props.to_dict())
# set spawned to true
self._is_spawned = True

Expand Down Expand Up @@ -204,6 +192,7 @@ def reset_buffers(self, env_ids: Optional[Sequence[int]] = None):
# reset history
self._previous_dof_vel[env_ids] = 0
# TODO: Reset other cached variables.
self.articulations.set_joint_efforts(self._ZERO_JOINT_EFFORT, indices=self._ALL_INDICES)
# reset actuators
for group in self.actuator_groups.values():
group.reset(env_ids)
Expand All @@ -220,11 +209,6 @@ def apply_action(self, actions: torch.Tensor):
# slice actions per actuator group
group_actions_dims = [group.control_dim for group in self.actuator_groups.values()]
all_group_actions = torch.split(actions, group_actions_dims, dim=-1)
# silence the physics sim for warnings that make no sense :)
self.articulations._physics_sim_view.enable_warnings(False)
# note (18.08.2022): Saw a difference of up to 5 ms per step when using Isaac Sim
# interfaces compared to direct PhysX calls. Thus, this function is optimized.
# acquire tensors for whole robot
# note: we use internal buffers to deal with the resets() as the buffers aren't forwarded
# unit the next simulation step.
dof_pos = self._data.dof_pos
Expand All @@ -250,6 +234,11 @@ def apply_action(self, actions: torch.Tensor):
self._data.gear_ratio[:, group.dof_indices] = group.gear_ratio
if group.velocity_limit is not None:
self._data.soft_dof_vel_limits[:, group.dof_indices] = group.velocity_limit
# silence the physics sim for warnings that make no sense :)
# note (18.08.2022): Saw a difference of up to 5 ms per step when using Isaac Sim
# ArticulationView.apply_action() method compared to direct PhysX calls. Thus,
# this function is optimized to apply actions for the whole robot.
self.articulations._physics_sim_view.enable_warnings(False)
# apply actions into sim
if self.sim_dof_control_modes["position"]:
self.articulations._physics_view.set_dof_position_targets(self._data.dof_pos_targets, self._ALL_INDICES)
Expand Down Expand Up @@ -472,6 +461,7 @@ def _create_buffers(self):
self._previous_dof_vel = torch.zeros(self.count, self.num_dof, dtype=torch.float, device=self.device)
# constants
self._ALL_INDICES = torch.arange(self.count, dtype=torch.long, device=self.device)
self._ZERO_JOINT_EFFORT = torch.zeros(self.count, self.num_dof, dtype=torch.float, device=self.device)

# -- frame states
self._data.root_state_w = torch.zeros(self.count, 13, dtype=torch.float, device=self.device)
Expand Down
Loading