spacemouse ok
This commit is contained in:
@@ -1,7 +1,16 @@
|
||||
# Copyright (c) 2024, MindRobot Project
|
||||
# SPDX-License-Identifier: BSD-3-Clause
|
||||
|
||||
"""Configuration for MindRobot dual-arm robot."""
|
||||
"""Configuration for MindRobot dual-arm robot.
|
||||
|
||||
Arms are RealMan RM-65 (6-DOF, 5kg payload, 7.2kg self-weight, 610mm reach).
|
||||
Reference: https://develop.realman-robotics.com/robot4th/robotParameter/RM65OntologyParameters/
|
||||
|
||||
The following configurations are available:
|
||||
|
||||
* :obj:`MINDBOT_CFG`: Base configuration with gravity enabled (general purpose).
|
||||
* :obj:`MINDBOT_HIGH_PD_CFG`: Gravity disabled, stiffer PD for IK task-space control.
|
||||
"""
|
||||
|
||||
import isaaclab.sim as sim_utils
|
||||
from isaaclab.actuators import ImplicitActuatorCfg
|
||||
@@ -9,113 +18,119 @@ from isaaclab.assets import ArticulationCfg
|
||||
|
||||
from mindbot.utils.assets import MINDBOT_ASSETS_DIR
|
||||
|
||||
##
|
||||
# ✅ 使用你的本地 USD 绝对路径
|
||||
##
|
||||
|
||||
MINDBOT_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/robots/mindbot/mindbot_cd2.usd",
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
max_depenetration_velocity=1.0,
|
||||
linear_damping=0.5,
|
||||
angular_damping=0.5,
|
||||
max_depenetration_velocity=5.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
# Allow root to be affected by physics (gravity) so robot won't hover
|
||||
fix_root_link=False,
|
||||
enabled_self_collisions=False,
|
||||
solver_position_iteration_count=16,
|
||||
solver_velocity_iteration_count=8,
|
||||
stabilization_threshold=1e-6,
|
||||
),
|
||||
collision_props=sim_utils.CollisionPropertiesCfg(
|
||||
collision_enabled=True,
|
||||
contact_offset=0.0005,
|
||||
rest_offset=0,
|
||||
enabled_self_collisions=True,
|
||||
solver_position_iteration_count=8,
|
||||
solver_velocity_iteration_count=0,
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
joint_pos={
|
||||
# ====== 左臂关节(主控臂)======
|
||||
"l_joint1": 2.3562, # 135°
|
||||
"l_joint2": -1.2217, # -70°
|
||||
"l_joint3": -1.5708, # -90°
|
||||
"l_joint4": 1.5708, # 90°
|
||||
"l_joint5": 1.5708, # 90°
|
||||
"l_joint6": -1.2217, # -70°
|
||||
# ====== 右臂关节(静止)======
|
||||
"r_joint1": 0.0,
|
||||
"r_joint2": 0.0,
|
||||
"r_joint3": 0.0,
|
||||
"r_joint4": 0.0,
|
||||
"r_joint5": 0.0,
|
||||
"r_joint6": 0.0,
|
||||
# ====== 左手夹爪 ======
|
||||
"left_hand_joint_left": 0.0, # 0.0=打开, -0.03=闭合
|
||||
"left_hand_joint_right": 0.0, # 0.0=打开, 0.03=闭合
|
||||
# ====== 右手夹爪 ======
|
||||
# ====== 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,
|
||||
# ====== Grippers (0=open) ======
|
||||
"left_hand_joint_left": 0.0,
|
||||
"left_hand_joint_right": 0.0,
|
||||
"right_hand_joint_left": 0.0,
|
||||
"right_hand_joint_right": 0.0,
|
||||
# ====== 躯干 ======
|
||||
# ====== Trunk & Head ======
|
||||
"PrismaticJoint": 0.26,
|
||||
# ====== 头部 ======
|
||||
"head_revoluteJoint": 0.0,
|
||||
},
|
||||
# Lower the spawn height to sit on the ground (was 0.05m above ground)
|
||||
pos=(0.0, 0.0, 0.0),
|
||||
),
|
||||
actuators={
|
||||
"left_arm": ImplicitActuatorCfg(
|
||||
joint_names_expr=["l_joint[1-6]"],
|
||||
effort_limit_sim=100.0,
|
||||
velocity_limit_sim=100.0,
|
||||
# ✅ IK 控制需要高刚度
|
||||
stiffness=10000.0,
|
||||
damping=1000.0,
|
||||
# RM-65 J1-J3: shoulder/elbow — max 180°/s ≈ 3.14 rad/s
|
||||
"left_arm_shoulder": ImplicitActuatorCfg(
|
||||
joint_names_expr=["l_joint[1-3]"],
|
||||
effort_limit_sim=50.0,
|
||||
velocity_limit_sim=3.14,
|
||||
stiffness=80.0,
|
||||
damping=4.0,
|
||||
),
|
||||
"right_arm": ImplicitActuatorCfg(
|
||||
joint_names_expr=["r_joint[1-6]"],
|
||||
effort_limit_sim=100.0,
|
||||
velocity_limit_sim=100.0,
|
||||
stiffness=10000.0,
|
||||
damping=1000.0,
|
||||
# RM-65 J4-J6: wrist — max 225°/s ≈ 3.93 rad/s
|
||||
"left_arm_wrist": ImplicitActuatorCfg(
|
||||
joint_names_expr=["l_joint[4-6]"],
|
||||
effort_limit_sim=20.0,
|
||||
velocity_limit_sim=3.93,
|
||||
stiffness=80.0,
|
||||
damping=4.0,
|
||||
),
|
||||
"right_arm_shoulder": ImplicitActuatorCfg(
|
||||
joint_names_expr=["r_joint[1-3]"],
|
||||
effort_limit_sim=50.0,
|
||||
velocity_limit_sim=3.14,
|
||||
stiffness=80.0,
|
||||
damping=4.0,
|
||||
),
|
||||
"right_arm_wrist": ImplicitActuatorCfg(
|
||||
joint_names_expr=["r_joint[4-6]"],
|
||||
effort_limit_sim=20.0,
|
||||
velocity_limit_sim=3.93,
|
||||
stiffness=80.0,
|
||||
damping=4.0,
|
||||
),
|
||||
"head": ImplicitActuatorCfg(
|
||||
joint_names_expr=["head_revoluteJoint"],
|
||||
stiffness=10000.0,
|
||||
damping=1000.0,
|
||||
effort_limit_sim=12.0,
|
||||
stiffness=80.0,
|
||||
damping=4.0,
|
||||
),
|
||||
"trunk": ImplicitActuatorCfg(
|
||||
joint_names_expr=["PrismaticJoint"],
|
||||
stiffness=40000.0,
|
||||
damping=4000.0,
|
||||
effort_limit_sim=10000.0,
|
||||
effort_limit_sim=200.0,
|
||||
velocity_limit_sim=0.2,
|
||||
stiffness=1000.0,
|
||||
damping=100.0,
|
||||
),
|
||||
"wheels": ImplicitActuatorCfg(
|
||||
joint_names_expr=[".*_revolute_Joint"],
|
||||
effort_limit_sim=200.0,
|
||||
stiffness=0.0,
|
||||
damping=100.0,
|
||||
effort_limit_sim=200.0,
|
||||
velocity_limit_sim=50.0,
|
||||
),
|
||||
# ✅ 夹爪:高刚度确保精准控制
|
||||
"grippers": ImplicitActuatorCfg(
|
||||
joint_names_expr=[".*_hand_joint.*"],
|
||||
stiffness=10000.0,
|
||||
damping=1000.0,
|
||||
effort_limit_sim=50.0,
|
||||
velocity_limit_sim=50.0,
|
||||
effort_limit_sim=200.0,
|
||||
stiffness=2e3,
|
||||
damping=1e2,
|
||||
),
|
||||
},
|
||||
soft_joint_pos_limit_factor=1.0,
|
||||
)
|
||||
"""Base configuration for MindRobot. Gravity enabled, low PD gains."""
|
||||
|
||||
##
|
||||
# ✅ 专用于 IK 控制的高 PD 版本(可选但推荐)
|
||||
##
|
||||
|
||||
MINDBOT_HIGH_PD_CFG = MINDBOT_CFG.copy()
|
||||
MINDBOT_HIGH_PD_CFG.actuators["left_arm"].stiffness = 40000.0
|
||||
MINDBOT_HIGH_PD_CFG.actuators["left_arm"].damping = 4000.0
|
||||
MINDBOT_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True
|
||||
MINDBOT_HIGH_PD_CFG.actuators["left_arm_shoulder"].stiffness = 400.0
|
||||
MINDBOT_HIGH_PD_CFG.actuators["left_arm_shoulder"].damping = 80.0
|
||||
MINDBOT_HIGH_PD_CFG.actuators["left_arm_wrist"].stiffness = 400.0
|
||||
MINDBOT_HIGH_PD_CFG.actuators["left_arm_wrist"].damping = 80.0
|
||||
MINDBOT_HIGH_PD_CFG.actuators["right_arm_shoulder"].stiffness = 400.0
|
||||
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."""
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
|
||||
from __future__ import annotations
|
||||
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR
|
||||
import torch
|
||||
|
||||
import isaaclab.sim as sim_utils
|
||||
from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg
|
||||
@@ -118,15 +119,15 @@ class MindRobotTeleopActionsCfg:
|
||||
arm_action = DifferentialInverseKinematicsActionCfg(
|
||||
asset_name="robot",
|
||||
joint_names=["l_joint[1-6]"],
|
||||
body_name="Link_6", # Last link of left arm
|
||||
body_name="left_hand_body",
|
||||
controller=DifferentialIKControllerCfg(
|
||||
command_type="pose",
|
||||
use_relative_mode=True,
|
||||
ik_method="dls",
|
||||
),
|
||||
scale=0.5,
|
||||
scale=1,
|
||||
body_offset=DifferentialInverseKinematicsActionCfg.OffsetCfg(
|
||||
pos=[0.0, 0.0, 0.0]
|
||||
pos=[0.0, 0.0, 0.0],
|
||||
),
|
||||
)
|
||||
|
||||
@@ -190,12 +191,10 @@ class MindRobotTeleopTerminationsCfg:
|
||||
# Events Configuration
|
||||
# =====================================================================
|
||||
|
||||
|
||||
@configclass
|
||||
class MindRobotTeleopEventsCfg:
|
||||
"""Reset events for teleoperation: R键重置时将场景恢复到初始状态。"""
|
||||
|
||||
# 重置所有场景实体(机器人、物体)到其 init_state 定义的初始位置/姿态
|
||||
reset_scene = EventTerm(
|
||||
func=mdp.reset_scene_to_default,
|
||||
mode="reset",
|
||||
@@ -253,8 +252,13 @@ class MindRobotLeftArmIKEnvCfg(ManagerBasedRLEnvCfg):
|
||||
self.sim.dt = 0.01 # 100Hz
|
||||
self.sim.render_interval = 2
|
||||
|
||||
# Set MindRobot
|
||||
self.scene.robot = MINDBOT_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
|
||||
# Set MindRobot with FIXED root for teleoperation
|
||||
# The original MINDBOT_HIGH_PD_CFG has fix_root_link=False (mobile base).
|
||||
# For teleoperation, the base MUST be fixed to prevent the whole robot
|
||||
# from sliding/tipping when IK applies torques to the arm joints.
|
||||
robot_cfg = MINDBOT_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
|
||||
robot_cfg.spawn.articulation_props.fix_root_link = True
|
||||
self.scene.robot = robot_cfg
|
||||
|
||||
# Configure end-effector frame transformer
|
||||
marker_cfg = FRAME_MARKER_CFG.copy()
|
||||
@@ -266,7 +270,7 @@ class MindRobotLeftArmIKEnvCfg(ManagerBasedRLEnvCfg):
|
||||
visualizer_cfg=marker_cfg,
|
||||
target_frames=[
|
||||
FrameTransformerCfg.FrameCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Robot/rm_65_fb_left/Link_6",
|
||||
prim_path="{ENV_REGEX_NS}/Robot/rm_65_fb_left/l_hand_01/left_hand_body",
|
||||
name="end_effector",
|
||||
offset=OffsetCfg(
|
||||
pos=[0.0, 0.0, 0.0],
|
||||
@@ -275,6 +279,7 @@ class MindRobotLeftArmIKEnvCfg(ManagerBasedRLEnvCfg):
|
||||
],
|
||||
)
|
||||
|
||||
|
||||
# Configure teleoperation devices
|
||||
self.teleop_devices = DevicesCfg(
|
||||
devices={
|
||||
|
||||
Reference in New Issue
Block a user