dual arm XR teleoperation: env cfg, shared client, joint locking
- Add MindRobotDualArmIKAbsEnvCfg: standalone dual-arm env inheriting ManagerBasedRLEnvCfg directly (no single-arm dependency), 20D action space (left_arm7 | wheel4 | left_gripper1 | right_arm7 | right_gripper1) - Add local mdp/ with parameterized gripper_pos(joint_names) to support independent left/right gripper observations without modifying IsaacLab - Update teleop_xr_agent.py for dual-arm mode: shared XrClient to avoid SDK double-init crash, root-frame IK command caching so arm joints are locked when grip not pressed (EEF world pos still tracks chassis) - Tune mindrobot_cfg.py initial poses with singularity-avoiding offsets - Add CLAUDE.md project instructions and debug_action_assembly.py Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
This commit is contained in:
@@ -46,4 +46,14 @@ gym.register(
|
||||
"robomimic_bc_cfg_entry_point": f"{__name__}.agents:robomimic/bc_rnn_low_dim.json",
|
||||
},
|
||||
disable_env_checker=True,
|
||||
)
|
||||
|
||||
gym.register(
|
||||
id="Isaac-MindRobot-DualArm-IK-Abs-v0",
|
||||
entry_point="isaaclab.envs:ManagerBasedRLEnv",
|
||||
kwargs={
|
||||
"env_cfg_entry_point": f"{__name__}.mindrobot_dual_arm_ik_env_cfg:MindRobotDualArmIKAbsEnvCfg",
|
||||
"robomimic_bc_cfg_entry_point": f"{__name__}.agents:robomimic/bc_rnn_low_dim.json",
|
||||
},
|
||||
disable_env_checker=True,
|
||||
)
|
||||
@@ -0,0 +1,9 @@
|
||||
# Copyright (c) 2024, MindRobot Project
|
||||
# SPDX-License-Identifier: BSD-3-Clause
|
||||
|
||||
"""MDP functions specific to the open_drybox teleoperation environments."""
|
||||
|
||||
from isaaclab.envs.mdp import * # noqa: F401, F403
|
||||
from isaaclab_tasks.manager_based.manipulation.stack.mdp import * # noqa: F401, F403
|
||||
|
||||
from .observations import * # noqa: F401, F403
|
||||
@@ -0,0 +1,48 @@
|
||||
# Copyright (c) 2024, MindRobot Project
|
||||
# SPDX-License-Identifier: BSD-3-Clause
|
||||
|
||||
"""Custom observation functions for open_drybox teleoperation environments."""
|
||||
|
||||
from __future__ import annotations
|
||||
|
||||
from typing import TYPE_CHECKING
|
||||
|
||||
import torch
|
||||
|
||||
from isaaclab.managers import SceneEntityCfg
|
||||
|
||||
if TYPE_CHECKING:
|
||||
from isaaclab.envs import ManagerBasedRLEnv
|
||||
|
||||
|
||||
def gripper_pos(
|
||||
env: ManagerBasedRLEnv,
|
||||
robot_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
|
||||
joint_names: list[str] = None,
|
||||
) -> torch.Tensor:
|
||||
"""Return the opening state of a parallel gripper specified by joint names.
|
||||
|
||||
Unlike the built-in ``gripper_pos`` which reads from ``env.cfg.gripper_joint_names``,
|
||||
this version accepts ``joint_names`` directly so the same function can be used
|
||||
for both left and right grippers in a dual-arm setup.
|
||||
|
||||
Args:
|
||||
robot_cfg: Scene entity config for the robot articulation.
|
||||
joint_names: List of exactly 2 joint names ``[joint_open_positive, joint_open_negative]``.
|
||||
The first joint increases with opening, the second decreases.
|
||||
|
||||
Returns:
|
||||
Tensor of shape ``(num_envs, 2)`` with the joint positions (sign-corrected).
|
||||
"""
|
||||
if joint_names is None:
|
||||
raise ValueError("joint_names must be specified")
|
||||
|
||||
robot = env.scene[robot_cfg.name]
|
||||
ids, _ = robot.find_joints(joint_names)
|
||||
|
||||
if len(ids) != 2:
|
||||
raise ValueError(f"Expected exactly 2 gripper joints, got {len(ids)} for {joint_names}")
|
||||
|
||||
j1 = robot.data.joint_pos[:, ids[0]].clone().unsqueeze(1)
|
||||
j2 = -1.0 * robot.data.joint_pos[:, ids[1]].clone().unsqueeze(1)
|
||||
return torch.cat((j1, j2), dim=1)
|
||||
@@ -36,20 +36,20 @@ MINDBOT_CFG = ArticulationCfg(
|
||||
joint_pos={
|
||||
# ====== Left arm (RM-65) — away from singularities ======
|
||||
# Elbow singularity: q3=0; Wrist singularity: q5=0.
|
||||
# The pose below keeps q3≠0 and q5≠0.
|
||||
"l_joint1": 1.5708, # 135°
|
||||
"l_joint2": -1.5708, # -70°
|
||||
"l_joint3": -1.5708, # -90° (away from elbow singularity q3=0)
|
||||
"l_joint4": 1.5708, # 90°
|
||||
"l_joint5": 1.5708, # 90° (away from wrist singularity q5=0)
|
||||
"l_joint6": -1.5708, # -70°
|
||||
# ====== Right arm (RM-65) ======
|
||||
"r_joint1": -2.3562,
|
||||
"r_joint2": -1.2217,
|
||||
"r_joint3": 1.5708,
|
||||
"r_joint4": -1.5708,
|
||||
"r_joint5": -1.5708,
|
||||
"r_joint6": 1.2217,
|
||||
# Small offsets on q2/q4/q6 to avoid exact 90° Jacobian symmetry.
|
||||
"l_joint1": 1.5708, # 90°
|
||||
"l_joint2": -1.2217, # -70° (offset from -90° for better elbow workspace)
|
||||
"l_joint3": -1.5708, # -90° (away from elbow singularity q3=0)
|
||||
"l_joint4": 1.3963, # 80° (offset from 90° to break wrist symmetry)
|
||||
"l_joint5": 1.5708, # 90° (away from wrist singularity q5=0)
|
||||
"l_joint6": -1.3963, # -80° (offset from -90° to break wrist symmetry)
|
||||
# ====== Right arm (RM-65) — same joint values as left (verified visually) ======
|
||||
"r_joint1": 1.5708, # 90°
|
||||
"r_joint2": -1.2217, # -70°
|
||||
"r_joint3": -1.5708, # -90° (away from elbow singularity q3=0)
|
||||
"r_joint4": 1.3963, # 80°
|
||||
"r_joint5": 1.5708, # 90° (away from wrist singularity q5=0)
|
||||
"r_joint6": 1.3963, # -80°
|
||||
# ====== Grippers (0=open) ======
|
||||
"left_hand_joint_left": 0.0,
|
||||
"left_hand_joint_right": 0.0,
|
||||
@@ -139,3 +139,31 @@ MINDBOT_HIGH_PD_CFG.actuators["right_arm_shoulder"].damping = 80.0
|
||||
MINDBOT_HIGH_PD_CFG.actuators["right_arm_wrist"].stiffness = 400.0
|
||||
MINDBOT_HIGH_PD_CFG.actuators["right_arm_wrist"].damping = 80.0
|
||||
"""IK task-space control configuration. Gravity disabled, stiffer PD for tracking."""
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Robot Body / Joint Name Constants
|
||||
# Keep all robot-specific strings here so env cfgs stay robot-agnostic.
|
||||
# =====================================================================
|
||||
|
||||
# Joint name patterns (regex, for use in action/actuator configs)
|
||||
MINDBOT_LEFT_ARM_JOINTS = "l_joint[1-6]"
|
||||
MINDBOT_RIGHT_ARM_JOINTS = "r_joint[1-6]"
|
||||
MINDBOT_LEFT_GRIPPER_JOINTS = ["left_hand_joint_left", "left_hand_joint_right"]
|
||||
MINDBOT_RIGHT_GRIPPER_JOINTS = ["right_hand_joint_left", "right_hand_joint_right"]
|
||||
MINDBOT_WHEEL_JOINTS = [
|
||||
"right_b_revolute_Joint",
|
||||
"left_b_revolute_Joint",
|
||||
"left_f_revolute_Joint",
|
||||
"right_f_revolute_Joint",
|
||||
]
|
||||
|
||||
# EEF body names (as defined in the USD asset)
|
||||
MINDBOT_LEFT_EEF_BODY = "left_hand_body"
|
||||
MINDBOT_RIGHT_EEF_BODY = "right_hand_body"
|
||||
|
||||
# Prim paths relative to the Robot prim (i.e. after "{ENV_REGEX_NS}/Robot/")
|
||||
MINDBOT_LEFT_ARM_PRIM_ROOT = "rm_65_fb_left"
|
||||
MINDBOT_RIGHT_ARM_PRIM_ROOT = "rm_65_b_right"
|
||||
MINDBOT_LEFT_EEF_PRIM = "rm_65_fb_left/l_hand_01/left_hand_body"
|
||||
MINDBOT_RIGHT_EEF_PRIM = "rm_65_b_right/r_hand/right_hand_body"
|
||||
|
||||
@@ -0,0 +1,343 @@
|
||||
# Copyright (c) 2024, MindRobot Project
|
||||
# SPDX-License-Identifier: BSD-3-Clause
|
||||
|
||||
"""MindRobot dual-arm IK absolute environment config for XR teleoperation."""
|
||||
|
||||
from __future__ import annotations
|
||||
|
||||
import torch
|
||||
|
||||
import isaaclab.sim as sim_utils
|
||||
from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg
|
||||
from isaaclab.controllers.differential_ik_cfg import DifferentialIKControllerCfg
|
||||
from isaaclab.devices import DevicesCfg
|
||||
from isaaclab.devices.keyboard import Se3KeyboardCfg
|
||||
from isaaclab.devices.spacemouse import Se3SpaceMouseCfg
|
||||
from isaaclab.devices.gamepad import Se3GamepadCfg
|
||||
from isaaclab.devices.openxr import XrCfg
|
||||
from isaaclab.envs import ManagerBasedRLEnvCfg
|
||||
from isaaclab.envs.mdp.actions.actions_cfg import (
|
||||
BinaryJointPositionActionCfg,
|
||||
DifferentialInverseKinematicsActionCfg,
|
||||
JointVelocityActionCfg,
|
||||
)
|
||||
from isaaclab.managers import EventTermCfg as EventTerm
|
||||
from isaaclab.managers import ObservationGroupCfg as ObsGroup
|
||||
from isaaclab.managers import ObservationTermCfg as ObsTerm
|
||||
from isaaclab.managers import SceneEntityCfg
|
||||
from isaaclab.managers import TerminationTermCfg as DoneTerm
|
||||
from isaaclab.markers.config import FRAME_MARKER_CFG
|
||||
from isaaclab.scene import InteractiveSceneCfg
|
||||
from isaaclab.sensors.frame_transformer.frame_transformer_cfg import FrameTransformerCfg, OffsetCfg
|
||||
from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg
|
||||
from isaaclab.sim.spawners.from_files.from_files_cfg import GroundPlaneCfg
|
||||
from isaaclab.utils import configclass
|
||||
|
||||
from . import mdp
|
||||
|
||||
from .mindrobot_cfg import (
|
||||
MINDBOT_HIGH_PD_CFG,
|
||||
MINDBOT_LEFT_ARM_JOINTS,
|
||||
MINDBOT_RIGHT_ARM_JOINTS,
|
||||
MINDBOT_LEFT_EEF_BODY,
|
||||
MINDBOT_RIGHT_EEF_BODY,
|
||||
MINDBOT_LEFT_GRIPPER_JOINTS,
|
||||
MINDBOT_RIGHT_GRIPPER_JOINTS,
|
||||
MINDBOT_WHEEL_JOINTS,
|
||||
MINDBOT_LEFT_ARM_PRIM_ROOT,
|
||||
MINDBOT_RIGHT_ARM_PRIM_ROOT,
|
||||
MINDBOT_LEFT_EEF_PRIM,
|
||||
MINDBOT_RIGHT_EEF_PRIM,
|
||||
)
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Scene Configuration
|
||||
# =====================================================================
|
||||
|
||||
@configclass
|
||||
class MindRobotDualArmSceneCfg(InteractiveSceneCfg):
|
||||
"""Scene for MindRobot dual-arm teleoperation."""
|
||||
|
||||
plane = AssetBaseCfg(
|
||||
prim_path="/World/GroundPlane",
|
||||
init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.0, 0.0]),
|
||||
spawn=GroundPlaneCfg(),
|
||||
)
|
||||
|
||||
cube = RigidObjectCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Cube",
|
||||
spawn=sim_utils.CuboidCfg(
|
||||
size=(0.04, 0.04, 0.04),
|
||||
rigid_props=RigidBodyPropertiesCfg(),
|
||||
mass_props=sim_utils.MassPropertiesCfg(mass=0.1),
|
||||
collision_props=sim_utils.CollisionPropertiesCfg(),
|
||||
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0)),
|
||||
),
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=(0.5, 0.0, 0.45)),
|
||||
)
|
||||
|
||||
robot: ArticulationCfg = MINDBOT_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
|
||||
|
||||
light = AssetBaseCfg(
|
||||
prim_path="/World/light",
|
||||
spawn=sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=3000.0),
|
||||
)
|
||||
|
||||
# EEF frame transformers — set in __post_init__
|
||||
ee_frame: FrameTransformerCfg = None
|
||||
ee_frame_right: FrameTransformerCfg = None
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Actions Configuration
|
||||
# =====================================================================
|
||||
|
||||
@configclass
|
||||
class MindRobotDualArmActionsCfg:
|
||||
"""Actions for MindRobot dual-arm IK teleoperation (absolute mode).
|
||||
|
||||
Action vector layout (total 20D):
|
||||
left_arm_action (7D): [x, y, z, qw, qx, qy, qz] absolute EEF pose, root frame
|
||||
wheel_action (4D): [right_b, left_b, left_f, right_f] wheel vel (rad/s)
|
||||
left_gripper_action (1D): +1=open, -1=close
|
||||
right_arm_action (7D): [x, y, z, qw, qx, qy, qz] absolute EEF pose, root frame
|
||||
right_gripper_action(1D): +1=open, -1=close
|
||||
"""
|
||||
|
||||
left_arm_action = DifferentialInverseKinematicsActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=[MINDBOT_LEFT_ARM_JOINTS],
|
||||
body_name=MINDBOT_LEFT_EEF_BODY,
|
||||
controller=DifferentialIKControllerCfg(
|
||||
command_type="pose",
|
||||
use_relative_mode=False,
|
||||
ik_method="dls",
|
||||
),
|
||||
scale=1,
|
||||
body_offset=DifferentialInverseKinematicsActionCfg.OffsetCfg(pos=[0.0, 0.0, 0.0]),
|
||||
)
|
||||
|
||||
wheel_action = JointVelocityActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=MINDBOT_WHEEL_JOINTS,
|
||||
scale=1.0,
|
||||
)
|
||||
|
||||
left_gripper_action = BinaryJointPositionActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=MINDBOT_LEFT_GRIPPER_JOINTS,
|
||||
open_command_expr={"left_hand_joint_left": 0.0, "left_hand_joint_right": 0.0},
|
||||
close_command_expr={"left_hand_joint_left": -0.03, "left_hand_joint_right": 0.03},
|
||||
)
|
||||
|
||||
right_arm_action = DifferentialInverseKinematicsActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=[MINDBOT_RIGHT_ARM_JOINTS],
|
||||
body_name=MINDBOT_RIGHT_EEF_BODY,
|
||||
controller=DifferentialIKControllerCfg(
|
||||
command_type="pose",
|
||||
use_relative_mode=False,
|
||||
ik_method="dls",
|
||||
),
|
||||
scale=1,
|
||||
body_offset=DifferentialInverseKinematicsActionCfg.OffsetCfg(pos=[0.0, 0.0, 0.0]),
|
||||
)
|
||||
|
||||
right_gripper_action = BinaryJointPositionActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=MINDBOT_RIGHT_GRIPPER_JOINTS,
|
||||
open_command_expr={"right_hand_joint_left": 0.0, "right_hand_joint_right": 0.0},
|
||||
close_command_expr={"right_hand_joint_left": -0.03, "right_hand_joint_right": 0.03},
|
||||
)
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Observations Configuration
|
||||
# =====================================================================
|
||||
|
||||
@configclass
|
||||
class MindRobotDualArmObsCfg:
|
||||
"""Observations for dual-arm teleoperation."""
|
||||
|
||||
@configclass
|
||||
class PolicyCfg(ObsGroup):
|
||||
actions = ObsTerm(func=mdp.last_action)
|
||||
joint_pos = ObsTerm(func=mdp.joint_pos_rel)
|
||||
joint_vel = ObsTerm(func=mdp.joint_vel_rel)
|
||||
# Left arm EEF
|
||||
eef_pos_left = ObsTerm(func=mdp.ee_frame_pos)
|
||||
eef_quat_left = ObsTerm(func=mdp.ee_frame_quat)
|
||||
# Left gripper (2 joints)
|
||||
left_gripper_pos = ObsTerm(
|
||||
func=mdp.gripper_pos,
|
||||
params={"joint_names": MINDBOT_LEFT_GRIPPER_JOINTS},
|
||||
)
|
||||
# Right arm EEF
|
||||
eef_pos_right = ObsTerm(
|
||||
func=mdp.ee_frame_pos,
|
||||
params={"ee_frame_cfg": SceneEntityCfg("ee_frame_right")},
|
||||
)
|
||||
eef_quat_right = ObsTerm(
|
||||
func=mdp.ee_frame_quat,
|
||||
params={"ee_frame_cfg": SceneEntityCfg("ee_frame_right")},
|
||||
)
|
||||
# Right gripper (2 joints)
|
||||
right_gripper_pos = ObsTerm(
|
||||
func=mdp.gripper_pos,
|
||||
params={"joint_names": MINDBOT_RIGHT_GRIPPER_JOINTS},
|
||||
)
|
||||
|
||||
def __post_init__(self):
|
||||
self.enable_corruption = False
|
||||
self.concatenate_terms = False
|
||||
|
||||
policy: PolicyCfg = PolicyCfg()
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Terminations Configuration
|
||||
# =====================================================================
|
||||
|
||||
@configclass
|
||||
class MindRobotDualArmTerminationsCfg:
|
||||
time_out = DoneTerm(func=mdp.time_out, time_out=True)
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Events Configuration
|
||||
# =====================================================================
|
||||
|
||||
def _disable_arm_gravity(env, env_ids: torch.Tensor):
|
||||
"""Disable gravity for both arm subtrees at startup."""
|
||||
import isaaclab.sim.schemas as schemas
|
||||
|
||||
arm_cfg = RigidBodyPropertiesCfg(disable_gravity=True)
|
||||
for env_id in range(env.num_envs):
|
||||
for arm_path in [
|
||||
f"/World/envs/env_{env_id}/Robot/{MINDBOT_LEFT_ARM_PRIM_ROOT}",
|
||||
f"/World/envs/env_{env_id}/Robot/{MINDBOT_RIGHT_ARM_PRIM_ROOT}",
|
||||
]:
|
||||
schemas.modify_rigid_body_properties(arm_path, arm_cfg)
|
||||
|
||||
|
||||
@configclass
|
||||
class MindRobotDualArmEventsCfg:
|
||||
disable_arm_gravity = EventTerm(
|
||||
func=_disable_arm_gravity,
|
||||
mode="startup",
|
||||
)
|
||||
reset_scene = EventTerm(
|
||||
func=mdp.reset_scene_to_default,
|
||||
mode="reset",
|
||||
)
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Empty placeholder configs
|
||||
# =====================================================================
|
||||
|
||||
@configclass
|
||||
class EmptyCfg:
|
||||
pass
|
||||
|
||||
|
||||
# =====================================================================
|
||||
# Main Environment Configuration
|
||||
# =====================================================================
|
||||
|
||||
@configclass
|
||||
class MindRobotDualArmIKAbsEnvCfg(ManagerBasedRLEnvCfg):
|
||||
"""MindRobot 双臂 IK-Abs 遥操作环境配置(XR 控制器)。"""
|
||||
|
||||
scene: MindRobotDualArmSceneCfg = MindRobotDualArmSceneCfg(
|
||||
num_envs=1,
|
||||
env_spacing=2.5,
|
||||
)
|
||||
|
||||
observations: MindRobotDualArmObsCfg = MindRobotDualArmObsCfg()
|
||||
actions: MindRobotDualArmActionsCfg = MindRobotDualArmActionsCfg()
|
||||
terminations: MindRobotDualArmTerminationsCfg = MindRobotDualArmTerminationsCfg()
|
||||
events: MindRobotDualArmEventsCfg = MindRobotDualArmEventsCfg()
|
||||
|
||||
commands: EmptyCfg = EmptyCfg()
|
||||
rewards: EmptyCfg = EmptyCfg()
|
||||
curriculum: EmptyCfg = EmptyCfg()
|
||||
|
||||
xr: XrCfg = XrCfg(
|
||||
anchor_pos=(-0.1, -0.5, -1.05),
|
||||
anchor_rot=(0.866, 0, 0, -0.5),
|
||||
)
|
||||
|
||||
def __post_init__(self):
|
||||
super().__post_init__()
|
||||
|
||||
self.decimation = 2
|
||||
self.episode_length_s = 50.0
|
||||
self.sim.dt = 0.01 # 100 Hz
|
||||
self.sim.render_interval = 2
|
||||
|
||||
# Mobile base — root link not fixed
|
||||
robot_cfg = MINDBOT_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
|
||||
robot_cfg.spawn.articulation_props.fix_root_link = False
|
||||
self.scene.robot = robot_cfg
|
||||
|
||||
# Left arm EEF frame transformer
|
||||
marker_cfg = FRAME_MARKER_CFG.copy()
|
||||
marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
|
||||
marker_cfg.prim_path = "/Visuals/FrameTransformerLeft"
|
||||
self.scene.ee_frame = FrameTransformerCfg(
|
||||
prim_path=f"{{ENV_REGEX_NS}}/Robot/{MINDBOT_LEFT_ARM_PRIM_ROOT}/base_link",
|
||||
debug_vis=False,
|
||||
visualizer_cfg=marker_cfg,
|
||||
target_frames=[
|
||||
FrameTransformerCfg.FrameCfg(
|
||||
prim_path=f"{{ENV_REGEX_NS}}/Robot/{MINDBOT_LEFT_EEF_PRIM}",
|
||||
name="end_effector",
|
||||
offset=OffsetCfg(pos=[0.0, 0.0, 0.0]),
|
||||
),
|
||||
],
|
||||
)
|
||||
|
||||
# Right arm EEF frame transformer
|
||||
marker_cfg_right = FRAME_MARKER_CFG.copy()
|
||||
marker_cfg_right.markers["frame"].scale = (0.1, 0.1, 0.1)
|
||||
marker_cfg_right.prim_path = "/Visuals/FrameTransformerRight"
|
||||
self.scene.ee_frame_right = FrameTransformerCfg(
|
||||
prim_path=f"{{ENV_REGEX_NS}}/Robot/{MINDBOT_RIGHT_ARM_PRIM_ROOT}/base_link",
|
||||
debug_vis=False,
|
||||
visualizer_cfg=marker_cfg_right,
|
||||
target_frames=[
|
||||
FrameTransformerCfg.FrameCfg(
|
||||
prim_path=f"{{ENV_REGEX_NS}}/Robot/{MINDBOT_RIGHT_EEF_PRIM}",
|
||||
name="end_effector",
|
||||
offset=OffsetCfg(pos=[0.0, 0.0, 0.0]),
|
||||
),
|
||||
],
|
||||
)
|
||||
|
||||
# Teleoperation devices
|
||||
self.teleop_devices = DevicesCfg(
|
||||
devices={
|
||||
"keyboard": Se3KeyboardCfg(
|
||||
pos_sensitivity=0.05,
|
||||
rot_sensitivity=0.05,
|
||||
sim_device=self.sim.device,
|
||||
),
|
||||
"spacemouse": Se3SpaceMouseCfg(
|
||||
pos_sensitivity=0.05,
|
||||
rot_sensitivity=0.05,
|
||||
sim_device=self.sim.device,
|
||||
),
|
||||
"gamepad": Se3GamepadCfg(
|
||||
pos_sensitivity=0.1,
|
||||
rot_sensitivity=0.1,
|
||||
sim_device=self.sim.device,
|
||||
),
|
||||
}
|
||||
)
|
||||
|
||||
# Gripper params (left gripper for single-arm compat; dual-arm uses obs directly)
|
||||
self.gripper_joint_names = MINDBOT_LEFT_GRIPPER_JOINTS
|
||||
self.gripper_open_val = 0.0
|
||||
self.gripper_threshold = 0.005
|
||||
@@ -37,7 +37,16 @@ from isaaclab.devices.openxr import XrCfg
|
||||
from isaaclab_tasks.manager_based.manipulation.stack import mdp
|
||||
|
||||
# 导入 MindRobot 资产
|
||||
from .mindrobot_cfg import MINDBOT_HIGH_PD_CFG
|
||||
from .mindrobot_cfg import (
|
||||
MINDBOT_HIGH_PD_CFG,
|
||||
MINDBOT_LEFT_ARM_JOINTS,
|
||||
MINDBOT_LEFT_EEF_BODY,
|
||||
MINDBOT_LEFT_GRIPPER_JOINTS,
|
||||
MINDBOT_WHEEL_JOINTS,
|
||||
MINDBOT_LEFT_ARM_PRIM_ROOT,
|
||||
MINDBOT_LEFT_EEF_PRIM,
|
||||
MINDBOT_RIGHT_ARM_PRIM_ROOT,
|
||||
)
|
||||
|
||||
# 在文件开头添加
|
||||
import isaaclab.utils.assets as assets_utils
|
||||
@@ -119,8 +128,8 @@ class MindRobotTeleopActionsCfg:
|
||||
# Left arm IK control
|
||||
arm_action = DifferentialInverseKinematicsActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=["l_joint[1-6]"],
|
||||
body_name="left_hand_body",
|
||||
joint_names=[MINDBOT_LEFT_ARM_JOINTS],
|
||||
body_name=MINDBOT_LEFT_EEF_BODY,
|
||||
controller=DifferentialIKControllerCfg(
|
||||
command_type="pose",
|
||||
use_relative_mode=True,
|
||||
@@ -134,24 +143,17 @@ class MindRobotTeleopActionsCfg:
|
||||
|
||||
# Wheel velocity control for differential drive (skid-steer).
|
||||
# Joint order in articulation: right_b, left_b, left_f, right_f
|
||||
# (from terminal joint index listing: [2],[3],[4],[5]).
|
||||
# Action vector: [right_b_vel, left_b_vel, left_f_vel, right_f_vel] in rad/s.
|
||||
wheel_action = JointVelocityActionCfg(
|
||||
asset_name="robot",
|
||||
# joint_names=[".*_revolute_Joint"],
|
||||
joint_names=[
|
||||
"right_b_revolute_Joint",
|
||||
"left_b_revolute_Joint",
|
||||
"left_f_revolute_Joint",
|
||||
"right_f_revolute_Joint",
|
||||
],
|
||||
joint_names=MINDBOT_WHEEL_JOINTS,
|
||||
scale=1.0,
|
||||
)
|
||||
|
||||
# Left gripper control (binary: open/close)
|
||||
gripper_action = BinaryJointPositionActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=["left_hand_joint_left", "left_hand_joint_right"],
|
||||
joint_names=MINDBOT_LEFT_GRIPPER_JOINTS,
|
||||
open_command_expr={
|
||||
"left_hand_joint_left": 0.0,
|
||||
"left_hand_joint_right": 0.0,
|
||||
@@ -225,8 +227,8 @@ def _disable_arm_gravity(env, env_ids: torch.Tensor):
|
||||
arm_cfg = RigidBodyPropertiesCfg(disable_gravity=True)
|
||||
for env_id in range(env.num_envs):
|
||||
for arm_path in [
|
||||
f"/World/envs/env_{env_id}/Robot/rm_65_fb_left",
|
||||
f"/World/envs/env_{env_id}/Robot/rm_65_b_right",
|
||||
f"/World/envs/env_{env_id}/Robot/{MINDBOT_LEFT_ARM_PRIM_ROOT}",
|
||||
f"/World/envs/env_{env_id}/Robot/{MINDBOT_RIGHT_ARM_PRIM_ROOT}",
|
||||
]:
|
||||
schemas.modify_rigid_body_properties(arm_path, arm_cfg)
|
||||
|
||||
@@ -309,16 +311,14 @@ class MindRobotLeftArmIKEnvCfg(ManagerBasedRLEnvCfg):
|
||||
marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
|
||||
marker_cfg.prim_path = "/Visuals/FrameTransformer"
|
||||
self.scene.ee_frame = FrameTransformerCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Robot/rm_65_fb_left/base_link",
|
||||
prim_path=f"{{ENV_REGEX_NS}}/Robot/{MINDBOT_LEFT_ARM_PRIM_ROOT}/base_link",
|
||||
debug_vis=False,
|
||||
visualizer_cfg=marker_cfg,
|
||||
target_frames=[
|
||||
FrameTransformerCfg.FrameCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Robot/rm_65_fb_left/l_hand_01/left_hand_body",
|
||||
prim_path=f"{{ENV_REGEX_NS}}/Robot/{MINDBOT_LEFT_EEF_PRIM}",
|
||||
name="end_effector",
|
||||
offset=OffsetCfg(
|
||||
pos=[0.0, 0.0, 0.0],
|
||||
),
|
||||
offset=OffsetCfg(pos=[0.0, 0.0, 0.0]),
|
||||
),
|
||||
],
|
||||
)
|
||||
@@ -346,7 +346,7 @@ class MindRobotLeftArmIKEnvCfg(ManagerBasedRLEnvCfg):
|
||||
)
|
||||
|
||||
# Gripper parameters for status checking
|
||||
self.gripper_joint_names = ["left_hand_joint_left", "left_hand_joint_right"]
|
||||
self.gripper_joint_names = MINDBOT_LEFT_GRIPPER_JOINTS
|
||||
self.gripper_open_val = 0.0
|
||||
self.gripper_threshold = 0.005
|
||||
|
||||
|
||||
@@ -20,6 +20,6 @@ import os
|
||||
##
|
||||
MINDBOT_ASSETS_DIR: str = os.environ.get(
|
||||
"MINDBOT_ASSETS_DIR",
|
||||
# "/home/tangger/DataDisk/maic_usd_assets_moudle",
|
||||
"/home/maic/LYT/maic_usd_assets_moudle",
|
||||
"/home/tangger/LYT/maic_usd_assets_moudle",
|
||||
# "/home/maic/LYT/maic_usd_assets_moudle",
|
||||
)
|
||||
|
||||
Reference in New Issue
Block a user