isaac-sim / IsaacLab

Unified framework for robot learning built on NVIDIA Isaac Sim
https://isaac-sim.github.io/IsaacLab
Other
1.84k stars 689 forks source link

[Question] Changing Target Pose in Reaching Environments #567

Closed DJT777 closed 2 months ago

DJT777 commented 2 months ago

Hello!

I'd like to change the target post in the reaching environments, such as in the UR10 environment using RSL-RL.

Currently we are able to reach towards the locations on the table in "front" of the robot. However, I'd like to modify it so that it can reach towards locations 360 degrees around the robot.

Are there any limits I would have to adjust?

Currently I am working with modifying the pose ranges here by modifying the x coordinate range to come from a list of tuples. Ideally I'd like to expand this towards having more ranges for the y and z coordinates.

However, I'm running into issues with convergence and getting a good general policy with these modifications in place. My understanding is that just operating on the other side of the axis shouldn't be a big deal with negative values in the pos_x.

Given that Isaac Lab is quite complex, I'm wondering if there are any other parts of Isaac Lab that would need adjusted such as DOF limits or something else?

CODE

source\extensions\omni.isaac.lab_tasks\omni\isaac\lab_tasks\manager_based\manipulation\reach\reach_env_cfg.py

@configclass
class CommandsCfg:
    """Command terms for the MDP."""

    ee_pose = mdp.UniformPoseCommandCfg(
        asset_name="robot",
        body_name=MISSING,
        resampling_time_range=(4.0, 4.0),
        debug_vis=True,
        ranges=mdp.UniformPoseCommandCfg.Ranges(
            pos_x=[(0.35, 0.65), (-0.65, -0.35)],
            pos_y=(-0.2, 0.2),
            pos_z=(0.15, 0.5),
            roll=(0.0, 0.0),
            pitch=MISSING,  # depends on end-effector axis
            yaw=(-3.14, 3.14),
        ),
    )

and made it so that the pose command takes a list of tuples for the x-coordinates.

source\extensions\omni.isaac.lab\omni\isaac\lab\envs\mdp\commands\pose_command.py

   def _resample_command(self, env_ids: Sequence[int]):
        # sample new pose targets
        # -- position
        r = torch.empty(len(env_ids), device=self.device)

        # Position ranges
        pos_x_range = self.cfg.ranges.pos_x
        pos_y_range = self.cfg.ranges.pos_y
        pos_z_range = self.cfg.ranges.pos_z

        # Check if pos_x_range is a list of tuples
        if isinstance(pos_x_range, list):
            # Randomly choose one tuple from the list
            chosen_range = random.choice(pos_x_range)
        else:
            chosen_range = pos_x_range  # Use the single tuple range

        self.pose_command_b[env_ids, 0] = r.uniform_(*chosen_range)
        self.pose_command_b[env_ids, 1] = r.uniform_(*self.cfg.ranges.pos_y)
        self.pose_command_b[env_ids, 2] = r.uniform_(*self.cfg.ranges.pos_z)
        # -- orientation
        euler_angles = torch.zeros_like(self.pose_command_b[env_ids, :3])
        euler_angles[:, 0].uniform_(*self.cfg.ranges.roll)
        euler_angles[:, 1].uniform_(*self.cfg.ranges.pitch)
        euler_angles[:, 2].uniform_(*self.cfg.ranges.yaw)
        quat = quat_from_euler_xyz(euler_angles[:, 0], euler_angles[:, 1], euler_angles[:, 2])
        # make sure the quaternion has real part as positive
        self.pose_command_b[env_ids, 3:] = quat_unique(quat) if self.cfg.make_quat_unique else quat
DJT777 commented 2 months ago

Would the modification of this file be appropriate?

# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configuration for the Franka Emika robots.

The following configurations are available:

* :obj:`FRANKA_PANDA_CFG`: Franka Emika Panda robot with Panda hand
* :obj:`FRANKA_PANDA_HIGH_PD_CFG`: Franka Emika Panda robot with Panda hand with stiffer PD control

Reference: https://github.com/frankaemika/franka_ros
"""

import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.actuators import ImplicitActuatorCfg
from omni.isaac.lab.assets.articulation import ArticulationCfg
from omni.isaac.lab.utils.assets import ISAACLAB_NUCLEUS_DIR

##
# Configuration
##

UR10_CFG_FRANKA = ArticulationCfg(
    spawn=sim_utils.UsdFileCfg(
        usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/UniversalRobots/UR10/ur10_instanceable.usd",
        activate_contact_sensors=False,
        rigid_props=sim_utils.RigidBodyPropertiesCfg(
            disable_gravity=False,
            max_depenetration_velocity=5.0,
        ),
        articulation_props=sim_utils.ArticulationRootPropertiesCfg(
            enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=0
        ),
        # collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
    ),
    init_state=ArticulationCfg.InitialStateCfg(
        joint_pos={
            "shoulder_pan_joint": 0.0,
            "shoulder_lift_joint": -1.712,
            "elbow_joint": 1.712,
            "wrist_1_joint": 0.0,
            "wrist_2_joint": 0.0,
            "wrist_3_joint": 0.0,
        },
        pos=(0.0, 0.0, 1), rot=(0,1,0,0)
    ),
    actuators={
        "arm": ImplicitActuatorCfg(
            joint_names_expr=[".*"],
            velocity_limit=100.0,
            effort_limit=87.0,
            stiffness=800.0,
            damping=40.0,
        ),

    },
    soft_joint_pos_limit_factor=1.0,
)