烘箱和unitree
This commit is contained in:
@@ -27,10 +27,27 @@ optional arguments:
|
||||
# Standard library imports
|
||||
import argparse
|
||||
import contextlib
|
||||
import os
|
||||
import sys
|
||||
import traceback
|
||||
|
||||
# Isaac Lab AppLauncher
|
||||
from isaaclab.app import AppLauncher
|
||||
|
||||
# Ensure local workspace packages are importable before any mindbot imports.
|
||||
# The repository contains the Python package under source/mindbot, while this
|
||||
# script lives under scripts/tools. Without adding these paths early, Python may
|
||||
# resolve to an older installed mindbot package that still uses the legacy G1
|
||||
# tri-hand joint names (for example: left_hand_index_0_joint).
|
||||
_REPO_ROOT = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
|
||||
_LOCAL_IMPORT_PATHS = (
|
||||
os.path.join(_REPO_ROOT, "source", "mindbot"),
|
||||
_REPO_ROOT,
|
||||
)
|
||||
for _path in reversed(_LOCAL_IMPORT_PATHS):
|
||||
if _path not in sys.path:
|
||||
sys.path.insert(0, _path)
|
||||
|
||||
# add argparse arguments
|
||||
parser = argparse.ArgumentParser(description="Record demonstrations for Isaac Lab environments.")
|
||||
parser.add_argument("--task", type=str, required=True, help="Name of the task.")
|
||||
@@ -91,8 +108,6 @@ simulation_app = app_launcher.app
|
||||
|
||||
# Third-party imports
|
||||
import logging
|
||||
import os
|
||||
import sys
|
||||
import time
|
||||
|
||||
import gymnasium as gym
|
||||
@@ -107,9 +122,13 @@ from isaaclab.devices.teleop_device_factory import create_teleop_device
|
||||
import isaaclab_mimic.envs # noqa: F401
|
||||
from isaaclab_mimic.ui.instruction_display import InstructionDisplay, show_subtask_instructions
|
||||
|
||||
# if args_cli.enable_pinocchio:
|
||||
# import isaaclab_tasks.manager_based.locomanipulation.pick_place # noqa: F401
|
||||
# import isaaclab_tasks.manager_based.manipulation.pick_place # noqa: F401
|
||||
if args_cli.enable_pinocchio:
|
||||
import isaaclab_tasks.manager_based.locomanipulation.pick_place # noqa: F401
|
||||
import isaaclab_tasks.manager_based.manipulation.pick_place # noqa: F401
|
||||
import mindbot.tasks.manager_based.il.locomanipulation.pick_place # noqa: F401
|
||||
import mindbot.tasks.manager_based.il.manipulation.pick_place # noqa: F401
|
||||
|
||||
|
||||
from collections.abc import Callable
|
||||
|
||||
@@ -118,11 +137,6 @@ from isaaclab.envs.mdp.recorders.recorders_cfg import ActionStateRecorderManager
|
||||
from isaaclab.envs.ui import EmptyWindow
|
||||
from isaaclab.managers import DatasetExportMode
|
||||
|
||||
# Add workspace root to sys.path so mindrobot_keyboard is importable as a package path.
|
||||
# record_demos.py lives at scripts/tools/, workspace root is three levels up.
|
||||
_ws_root = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
|
||||
if _ws_root not in sys.path:
|
||||
sys.path.insert(0, _ws_root)
|
||||
from scripts.environments.teleoperation.mindrobot_keyboard import MindRobotCombinedKeyboard # noqa: E402
|
||||
|
||||
import isaaclab_tasks # noqa: F401
|
||||
@@ -265,6 +279,7 @@ def create_environment(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg) -> gym.En
|
||||
return env
|
||||
except Exception as e:
|
||||
logger.error(f"Failed to create environment: {e}")
|
||||
traceback.print_exc()
|
||||
exit(1)
|
||||
|
||||
|
||||
|
||||
@@ -3,21 +3,29 @@ from isaaclab.actuators import ImplicitActuatorCfg
|
||||
from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg
|
||||
from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR
|
||||
from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg
|
||||
from isaaclab.sim.schemas.schemas_cfg import (
|
||||
RigidBodyPropertiesCfg,
|
||||
CollisionPropertiesCfg,
|
||||
)
|
||||
# from isaaclab.sim.schemas.schemas_cfg import (
|
||||
# RigidBodyPropertiesCfg,
|
||||
# CollisionPropertiesCfg,
|
||||
# )
|
||||
from mindbot.utils.assets import MINDBOT_ASSETS_DIR
|
||||
|
||||
DRYINGBOX_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/devices/DryingBox/Equipment_BB_13.usd",
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/devices/Collected_Equipment_BB_13(1)/Collected_Equipment_BB_13/Equipment_BB_13.usd",
|
||||
activate_contact_sensors=False,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
max_depenetration_velocity=1.0
|
||||
max_depenetration_velocity=100.0, # 增大:穿透后更快弹出
|
||||
linear_damping=0.5,
|
||||
angular_damping=0.5,
|
||||
),
|
||||
collision_props=sim_utils.CollisionPropertiesCfg(
|
||||
collision_enabled=True,
|
||||
contact_offset=0.01, # 增大到10mm:提前检测接触,避免高速漏检
|
||||
rest_offset=0.001, # 略小于 contact_offset
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
fix_root_link=False,
|
||||
# fix_root_link=True, # 固定烘箱根节点,防止碰撞时整体位移加剧穿透
|
||||
enabled_self_collisions=False,
|
||||
solver_position_iteration_count=32,
|
||||
solver_velocity_iteration_count=16,
|
||||
@@ -27,15 +35,28 @@ DRYINGBOX_CFG = ArticulationCfg(
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=[1.95, -0.45, 0.9], rot=[-0.7071, 0.0, 0.0, 0.7071]
|
||||
),
|
||||
# actuators={}
|
||||
actuators={
|
||||
"passive_damper": ImplicitActuatorCfg(
|
||||
# ".*" 表示匹配该USD文件内的所有关节(无论是轮子、屏幕转轴还是其他)
|
||||
joint_names_expr=["RevoluteJoint"],
|
||||
stiffness=10000.0,
|
||||
damping=1000.0,
|
||||
effort_limit_sim=10000.0,
|
||||
velocity_limit_sim=100.0,
|
||||
"door_joint": ImplicitActuatorCfg(
|
||||
joint_names_expr=["door_revoluteJoint"],
|
||||
damping=0.5,
|
||||
stiffness=0.0, # 初始被动;teleop 主循环触发后锁定
|
||||
effort_limit_sim=200.0,
|
||||
),
|
||||
"hand_joint": ImplicitActuatorCfg(
|
||||
joint_names_expr=["hand_revoluteJoint"],
|
||||
stiffness=0.0, # 初始被动;event term 动态切换到 1000.0 触发锁定
|
||||
damping=0.5,
|
||||
effort_limit_sim=200.0, # 锁定时 stiffness=1000 需要足够的驱动力
|
||||
),
|
||||
},
|
||||
# actuators={
|
||||
# "passive_damper": ImplicitActuatorCfg(
|
||||
# # ".*" 表示匹配该USD文件内的所有关节(无论是轮子、屏幕转轴还是其他)
|
||||
# joint_names_expr=["RevoluteJoint"],
|
||||
# stiffness=2e3,
|
||||
# damping=1e2,
|
||||
# effort_limit_sim=200.0,
|
||||
# velocity_limit_sim=20.0,
|
||||
# ),
|
||||
# },
|
||||
)
|
||||
|
||||
612
source/mindbot/mindbot/robot/unitree.py
Normal file
612
source/mindbot/mindbot/robot/unitree.py
Normal file
@@ -0,0 +1,612 @@
|
||||
# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
|
||||
# All rights reserved.
|
||||
#
|
||||
# SPDX-License-Identifier: BSD-3-Clause
|
||||
|
||||
"""Configuration for Unitree robots.
|
||||
|
||||
The following configurations are available:
|
||||
|
||||
* :obj:`UNITREE_A1_CFG`: Unitree A1 robot with DC motor model for the legs
|
||||
* :obj:`UNITREE_GO1_CFG`: Unitree Go1 robot with actuator net model for the legs
|
||||
* :obj:`UNITREE_GO2_CFG`: Unitree Go2 robot with DC motor model for the legs
|
||||
* :obj:`H1_CFG`: H1 humanoid robot
|
||||
* :obj:`H1_MINIMAL_CFG`: H1 humanoid robot with minimal collision bodies
|
||||
* :obj:`G1_CFG`: G1 humanoid robot
|
||||
* :obj:`G1_MINIMAL_CFG`: G1 humanoid robot with minimal collision bodies
|
||||
* :obj:`G1_29DOF_CFG`: G1 humanoid robot configured for locomanipulation tasks
|
||||
* :obj:`G1_INSPIRE_FTP_CFG`: G1 29DOF humanoid robot with Inspire 5-finger hand
|
||||
|
||||
Reference: https://github.com/unitreerobotics/unitree_ros
|
||||
"""
|
||||
|
||||
import isaaclab.sim as sim_utils
|
||||
from isaaclab.actuators import ActuatorNetMLPCfg, DCMotorCfg, ImplicitActuatorCfg
|
||||
from isaaclab.assets.articulation import ArticulationCfg
|
||||
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR
|
||||
from mindbot.utils.assets import MINDBOT_ASSETS_DIR
|
||||
|
||||
##
|
||||
# Configuration - Actuators.
|
||||
##
|
||||
|
||||
GO1_ACTUATOR_CFG = ActuatorNetMLPCfg(
|
||||
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
|
||||
network_file=f"{ISAACLAB_NUCLEUS_DIR}/ActuatorNets/Unitree/unitree_go1.pt",
|
||||
pos_scale=-1.0,
|
||||
vel_scale=1.0,
|
||||
torque_scale=1.0,
|
||||
input_order="pos_vel",
|
||||
input_idx=[0, 1, 2],
|
||||
effort_limit=23.7, # taken from spec sheet
|
||||
velocity_limit=30.0, # taken from spec sheet
|
||||
saturation_effort=23.7, # same as effort limit
|
||||
)
|
||||
"""Configuration of Go1 actuators using MLP model.
|
||||
|
||||
Actuator specifications: https://shop.unitree.com/products/go1-motor
|
||||
|
||||
This model is taken from: https://github.com/Improbable-AI/walk-these-ways
|
||||
"""
|
||||
|
||||
|
||||
##
|
||||
# Configuration
|
||||
##
|
||||
|
||||
|
||||
UNITREE_A1_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/A1/a1.usd",
|
||||
activate_contact_sensors=True,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
retain_accelerations=False,
|
||||
linear_damping=0.0,
|
||||
angular_damping=0.0,
|
||||
max_linear_velocity=1000.0,
|
||||
max_angular_velocity=1000.0,
|
||||
max_depenetration_velocity=1.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 0.42),
|
||||
joint_pos={
|
||||
".*L_hip_joint": 0.1,
|
||||
".*R_hip_joint": -0.1,
|
||||
"F[L,R]_thigh_joint": 0.8,
|
||||
"R[L,R]_thigh_joint": 1.0,
|
||||
".*_calf_joint": -1.5,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
),
|
||||
soft_joint_pos_limit_factor=0.9,
|
||||
actuators={
|
||||
"base_legs": DCMotorCfg(
|
||||
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
|
||||
effort_limit=33.5,
|
||||
saturation_effort=33.5,
|
||||
velocity_limit=21.0,
|
||||
stiffness=25.0,
|
||||
damping=0.5,
|
||||
friction=0.0,
|
||||
),
|
||||
},
|
||||
)
|
||||
"""Configuration of Unitree A1 using DC motor.
|
||||
|
||||
Note: Specifications taken from: https://www.trossenrobotics.com/a1-quadruped#specifications
|
||||
"""
|
||||
|
||||
|
||||
UNITREE_GO1_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/Go1/go1.usd",
|
||||
activate_contact_sensors=True,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
retain_accelerations=False,
|
||||
linear_damping=0.0,
|
||||
angular_damping=0.0,
|
||||
max_linear_velocity=1000.0,
|
||||
max_angular_velocity=1000.0,
|
||||
max_depenetration_velocity=1.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 0.4),
|
||||
joint_pos={
|
||||
".*L_hip_joint": 0.1,
|
||||
".*R_hip_joint": -0.1,
|
||||
"F[L,R]_thigh_joint": 0.8,
|
||||
"R[L,R]_thigh_joint": 1.0,
|
||||
".*_calf_joint": -1.5,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
),
|
||||
soft_joint_pos_limit_factor=0.9,
|
||||
actuators={
|
||||
"base_legs": GO1_ACTUATOR_CFG,
|
||||
},
|
||||
)
|
||||
"""Configuration of Unitree Go1 using MLP-based actuator model."""
|
||||
|
||||
|
||||
UNITREE_GO2_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/Go2/go2.usd",
|
||||
activate_contact_sensors=True,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
retain_accelerations=False,
|
||||
linear_damping=0.0,
|
||||
angular_damping=0.0,
|
||||
max_linear_velocity=1000.0,
|
||||
max_angular_velocity=1000.0,
|
||||
max_depenetration_velocity=1.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 0.4),
|
||||
joint_pos={
|
||||
".*L_hip_joint": 0.1,
|
||||
".*R_hip_joint": -0.1,
|
||||
"F[L,R]_thigh_joint": 0.8,
|
||||
"R[L,R]_thigh_joint": 1.0,
|
||||
".*_calf_joint": -1.5,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
),
|
||||
soft_joint_pos_limit_factor=0.9,
|
||||
actuators={
|
||||
"base_legs": DCMotorCfg(
|
||||
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
|
||||
effort_limit=23.5,
|
||||
saturation_effort=23.5,
|
||||
velocity_limit=30.0,
|
||||
stiffness=25.0,
|
||||
damping=0.5,
|
||||
friction=0.0,
|
||||
),
|
||||
},
|
||||
)
|
||||
"""Configuration of Unitree Go2 using DC-Motor actuator model."""
|
||||
|
||||
|
||||
H1_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1/h1.usd",
|
||||
activate_contact_sensors=True,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
retain_accelerations=False,
|
||||
linear_damping=0.0,
|
||||
angular_damping=0.0,
|
||||
max_linear_velocity=1000.0,
|
||||
max_angular_velocity=1000.0,
|
||||
max_depenetration_velocity=1.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=4
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 1.05),
|
||||
joint_pos={
|
||||
".*_hip_yaw": 0.0,
|
||||
".*_hip_roll": 0.0,
|
||||
".*_hip_pitch": -0.28, # -16 degrees
|
||||
".*_knee": 0.79, # 45 degrees
|
||||
".*_ankle": -0.52, # -30 degrees
|
||||
"torso": 0.0,
|
||||
".*_shoulder_pitch": 0.28,
|
||||
".*_shoulder_roll": 0.0,
|
||||
".*_shoulder_yaw": 0.0,
|
||||
".*_elbow": 0.52,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
),
|
||||
soft_joint_pos_limit_factor=0.9,
|
||||
actuators={
|
||||
"legs": ImplicitActuatorCfg(
|
||||
joint_names_expr=[".*_hip_yaw", ".*_hip_roll", ".*_hip_pitch", ".*_knee", "torso"],
|
||||
effort_limit_sim=300,
|
||||
stiffness={
|
||||
".*_hip_yaw": 150.0,
|
||||
".*_hip_roll": 150.0,
|
||||
".*_hip_pitch": 200.0,
|
||||
".*_knee": 200.0,
|
||||
"torso": 200.0,
|
||||
},
|
||||
damping={
|
||||
".*_hip_yaw": 5.0,
|
||||
".*_hip_roll": 5.0,
|
||||
".*_hip_pitch": 5.0,
|
||||
".*_knee": 5.0,
|
||||
"torso": 5.0,
|
||||
},
|
||||
),
|
||||
"feet": ImplicitActuatorCfg(
|
||||
joint_names_expr=[".*_ankle"],
|
||||
effort_limit_sim=100,
|
||||
stiffness={".*_ankle": 20.0},
|
||||
damping={".*_ankle": 4.0},
|
||||
),
|
||||
"arms": ImplicitActuatorCfg(
|
||||
joint_names_expr=[".*_shoulder_pitch", ".*_shoulder_roll", ".*_shoulder_yaw", ".*_elbow"],
|
||||
effort_limit_sim=300,
|
||||
stiffness={
|
||||
".*_shoulder_pitch": 40.0,
|
||||
".*_shoulder_roll": 40.0,
|
||||
".*_shoulder_yaw": 40.0,
|
||||
".*_elbow": 40.0,
|
||||
},
|
||||
damping={
|
||||
".*_shoulder_pitch": 10.0,
|
||||
".*_shoulder_roll": 10.0,
|
||||
".*_shoulder_yaw": 10.0,
|
||||
".*_elbow": 10.0,
|
||||
},
|
||||
),
|
||||
},
|
||||
)
|
||||
"""Configuration for the Unitree H1 Humanoid robot."""
|
||||
|
||||
|
||||
H1_MINIMAL_CFG = H1_CFG.copy()
|
||||
H1_MINIMAL_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1/h1_minimal.usd"
|
||||
"""Configuration for the Unitree H1 Humanoid robot with fewer collision meshes.
|
||||
|
||||
This configuration removes most collision meshes to speed up simulation.
|
||||
"""
|
||||
|
||||
|
||||
G1_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/G1/g1.usd",
|
||||
activate_contact_sensors=True,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
retain_accelerations=False,
|
||||
linear_damping=0.0,
|
||||
angular_damping=0.0,
|
||||
max_linear_velocity=1000.0,
|
||||
max_angular_velocity=1000.0,
|
||||
max_depenetration_velocity=1.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
enabled_self_collisions=False, solver_position_iteration_count=8, solver_velocity_iteration_count=4
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 0.74),
|
||||
joint_pos={
|
||||
".*_hip_pitch_joint": -0.20,
|
||||
".*_knee_joint": 0.42,
|
||||
".*_ankle_pitch_joint": -0.23,
|
||||
".*_elbow_pitch_joint": 0.87,
|
||||
"left_shoulder_roll_joint": 0.16,
|
||||
"left_shoulder_pitch_joint": 0.35,
|
||||
"right_shoulder_roll_joint": -0.16,
|
||||
"right_shoulder_pitch_joint": 0.35,
|
||||
"left_one_joint": 1.0,
|
||||
"right_one_joint": -1.0,
|
||||
"left_two_joint": 0.52,
|
||||
"right_two_joint": -0.52,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
),
|
||||
soft_joint_pos_limit_factor=0.9,
|
||||
actuators={
|
||||
"legs": ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_hip_yaw_joint",
|
||||
".*_hip_roll_joint",
|
||||
".*_hip_pitch_joint",
|
||||
".*_knee_joint",
|
||||
"torso_joint",
|
||||
],
|
||||
effort_limit_sim=300,
|
||||
stiffness={
|
||||
".*_hip_yaw_joint": 150.0,
|
||||
".*_hip_roll_joint": 150.0,
|
||||
".*_hip_pitch_joint": 200.0,
|
||||
".*_knee_joint": 200.0,
|
||||
"torso_joint": 200.0,
|
||||
},
|
||||
damping={
|
||||
".*_hip_yaw_joint": 5.0,
|
||||
".*_hip_roll_joint": 5.0,
|
||||
".*_hip_pitch_joint": 5.0,
|
||||
".*_knee_joint": 5.0,
|
||||
"torso_joint": 5.0,
|
||||
},
|
||||
armature={
|
||||
".*_hip_.*": 0.01,
|
||||
".*_knee_joint": 0.01,
|
||||
"torso_joint": 0.01,
|
||||
},
|
||||
),
|
||||
"feet": ImplicitActuatorCfg(
|
||||
effort_limit_sim=20,
|
||||
joint_names_expr=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"],
|
||||
stiffness=20.0,
|
||||
damping=2.0,
|
||||
armature=0.01,
|
||||
),
|
||||
"arms": ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_shoulder_pitch_joint",
|
||||
".*_shoulder_roll_joint",
|
||||
".*_shoulder_yaw_joint",
|
||||
".*_elbow_pitch_joint",
|
||||
".*_elbow_roll_joint",
|
||||
".*_five_joint",
|
||||
".*_three_joint",
|
||||
".*_six_joint",
|
||||
".*_four_joint",
|
||||
".*_zero_joint",
|
||||
".*_one_joint",
|
||||
".*_two_joint",
|
||||
],
|
||||
effort_limit_sim=300,
|
||||
stiffness=40.0,
|
||||
damping=10.0,
|
||||
armature={
|
||||
".*_shoulder_.*": 0.01,
|
||||
".*_elbow_.*": 0.01,
|
||||
".*_five_joint": 0.001,
|
||||
".*_three_joint": 0.001,
|
||||
".*_six_joint": 0.001,
|
||||
".*_four_joint": 0.001,
|
||||
".*_zero_joint": 0.001,
|
||||
".*_one_joint": 0.001,
|
||||
".*_two_joint": 0.001,
|
||||
},
|
||||
),
|
||||
},
|
||||
)
|
||||
"""Configuration for the Unitree G1 Humanoid robot."""
|
||||
|
||||
|
||||
G1_MINIMAL_CFG = G1_CFG.copy()
|
||||
G1_MINIMAL_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/G1/g1_minimal.usd"
|
||||
"""Configuration for the Unitree G1 Humanoid robot with fewer collision meshes.
|
||||
|
||||
This configuration removes most collision meshes to speed up simulation.
|
||||
"""
|
||||
|
||||
|
||||
G1_29DOF_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Unitree/G1/g1.usd",
|
||||
activate_contact_sensors=False,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
retain_accelerations=False,
|
||||
linear_damping=0.0,
|
||||
angular_damping=0.0,
|
||||
max_linear_velocity=1000.0,
|
||||
max_angular_velocity=1000.0,
|
||||
max_depenetration_velocity=1.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
enabled_self_collisions=False,
|
||||
fix_root_link=False, # Configurable - can be set to True for fixed base
|
||||
solver_position_iteration_count=8,
|
||||
solver_velocity_iteration_count=4,
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 0.75),
|
||||
rot=(0.7071, 0, 0, 0.7071),
|
||||
joint_pos={
|
||||
".*_hip_pitch_joint": -0.10,
|
||||
".*_knee_joint": 0.30,
|
||||
".*_ankle_pitch_joint": -0.20,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
),
|
||||
soft_joint_pos_limit_factor=0.9,
|
||||
actuators={
|
||||
"legs": DCMotorCfg(
|
||||
joint_names_expr=[
|
||||
".*_hip_yaw_joint",
|
||||
".*_hip_roll_joint",
|
||||
".*_hip_pitch_joint",
|
||||
".*_knee_joint",
|
||||
],
|
||||
effort_limit={
|
||||
".*_hip_yaw_joint": 88.0,
|
||||
".*_hip_roll_joint": 88.0,
|
||||
".*_hip_pitch_joint": 88.0,
|
||||
".*_knee_joint": 139.0,
|
||||
},
|
||||
velocity_limit={
|
||||
".*_hip_yaw_joint": 32.0,
|
||||
".*_hip_roll_joint": 32.0,
|
||||
".*_hip_pitch_joint": 32.0,
|
||||
".*_knee_joint": 20.0,
|
||||
},
|
||||
stiffness={
|
||||
".*_hip_yaw_joint": 100.0,
|
||||
".*_hip_roll_joint": 100.0,
|
||||
".*_hip_pitch_joint": 100.0,
|
||||
".*_knee_joint": 200.0,
|
||||
},
|
||||
damping={
|
||||
".*_hip_yaw_joint": 2.5,
|
||||
".*_hip_roll_joint": 2.5,
|
||||
".*_hip_pitch_joint": 2.5,
|
||||
".*_knee_joint": 5.0,
|
||||
},
|
||||
armature={
|
||||
".*_hip_.*": 0.03,
|
||||
".*_knee_joint": 0.03,
|
||||
},
|
||||
saturation_effort=180.0,
|
||||
),
|
||||
"feet": DCMotorCfg(
|
||||
joint_names_expr=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"],
|
||||
stiffness={
|
||||
".*_ankle_pitch_joint": 20.0,
|
||||
".*_ankle_roll_joint": 20.0,
|
||||
},
|
||||
damping={
|
||||
".*_ankle_pitch_joint": 0.2,
|
||||
".*_ankle_roll_joint": 0.1,
|
||||
},
|
||||
effort_limit={
|
||||
".*_ankle_pitch_joint": 50.0,
|
||||
".*_ankle_roll_joint": 50.0,
|
||||
},
|
||||
velocity_limit={
|
||||
".*_ankle_pitch_joint": 37.0,
|
||||
".*_ankle_roll_joint": 37.0,
|
||||
},
|
||||
armature=0.03,
|
||||
saturation_effort=80.0,
|
||||
),
|
||||
"waist": ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
"waist_.*_joint",
|
||||
],
|
||||
effort_limit={
|
||||
"waist_yaw_joint": 88.0,
|
||||
"waist_roll_joint": 50.0,
|
||||
"waist_pitch_joint": 50.0,
|
||||
},
|
||||
velocity_limit={
|
||||
"waist_yaw_joint": 32.0,
|
||||
"waist_roll_joint": 37.0,
|
||||
"waist_pitch_joint": 37.0,
|
||||
},
|
||||
stiffness={
|
||||
"waist_yaw_joint": 5000.0,
|
||||
"waist_roll_joint": 5000.0,
|
||||
"waist_pitch_joint": 5000.0,
|
||||
},
|
||||
damping={
|
||||
"waist_yaw_joint": 5.0,
|
||||
"waist_roll_joint": 5.0,
|
||||
"waist_pitch_joint": 5.0,
|
||||
},
|
||||
armature=0.001,
|
||||
),
|
||||
"arms": ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_shoulder_pitch_joint",
|
||||
".*_shoulder_roll_joint",
|
||||
".*_shoulder_yaw_joint",
|
||||
".*_elbow_joint",
|
||||
".*_wrist_.*_joint",
|
||||
],
|
||||
effort_limit=300,
|
||||
velocity_limit=100,
|
||||
stiffness=3000.0,
|
||||
damping=10.0,
|
||||
armature={
|
||||
".*_shoulder_.*": 0.001,
|
||||
".*_elbow_.*": 0.001,
|
||||
".*_wrist_.*_joint": 0.001,
|
||||
},
|
||||
),
|
||||
"hands": ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_index_.*",
|
||||
".*_middle_.*",
|
||||
".*_thumb_.*",
|
||||
],
|
||||
effort_limit=300,
|
||||
velocity_limit=100,
|
||||
stiffness=20,
|
||||
damping=2,
|
||||
armature=0.001,
|
||||
),
|
||||
},
|
||||
prim_path="/World/envs/env_.*/Robot",
|
||||
)
|
||||
"""Configuration for the Unitree G1 Humanoid robot for locomanipulation tasks.
|
||||
|
||||
This configuration sets up the G1 humanoid robot for locomanipulation tasks,
|
||||
allowing both locomotion and manipulation capabilities. The robot can be configured
|
||||
for either fixed base or mobile scenarios by modifying the fix_root_link parameter.
|
||||
|
||||
Key features:
|
||||
- Configurable base (fixed or mobile) via fix_root_link parameter
|
||||
- Optimized actuator parameters for locomanipulation tasks
|
||||
- Enhanced hand and arm configurations for manipulation
|
||||
|
||||
Usage examples:
|
||||
# For fixed base scenarios (upper body manipulation only)
|
||||
fixed_base_cfg = G1_29DOF_CFG.copy()
|
||||
fixed_base_cfg.spawn.articulation_props.fix_root_link = True
|
||||
|
||||
# For mobile scenarios (locomotion + manipulation)
|
||||
mobile_cfg = G1_29DOF_CFG.copy()
|
||||
mobile_cfg.spawn.articulation_props.fix_root_link = False
|
||||
"""
|
||||
|
||||
"""
|
||||
Configuration for the Unitree G1 Humanoid robot with Inspire 5fingers hand.
|
||||
The Unitree G1 URDF can be found here: https://github.com/unitreerobotics/unitree_ros/tree/master/robots/g1_description/g1_29dof_with_hand_rev_1_0.urdf
|
||||
The Inspire hand URDF is available at: https://github.com/unitreerobotics/xr_teleoperate/tree/main/assets/inspire_hand
|
||||
The merging code for the hand and robot can be found here: https://github.com/unitreerobotics/unitree_ros/blob/master/robots/g1_description/merge_g1_29dof_and_inspire_hand.ipynb,
|
||||
Necessary modifications should be made to ensure the correct parent–child relationship.
|
||||
"""
|
||||
# Inherit PD settings from G1_29DOF_CFG, with minor adjustments for grasping task
|
||||
G1_INSPIRE_FTP_CFG = G1_29DOF_CFG.copy()
|
||||
G1_INSPIRE_FTP_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/G1/g1_29dof_inspire_hand.usd"
|
||||
G1_INSPIRE_FTP_CFG.spawn.activate_contact_sensors = True
|
||||
G1_INSPIRE_FTP_CFG.spawn.rigid_props.disable_gravity = True
|
||||
G1_INSPIRE_FTP_CFG.spawn.articulation_props.fix_root_link = True
|
||||
G1_INSPIRE_FTP_CFG.init_state = ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 1.0),
|
||||
joint_pos={".*": 0.0},
|
||||
joint_vel={".*": 0.0},
|
||||
)
|
||||
# Actuator configuration for arms (stability focused for manipulation)
|
||||
# Increased damping improves stability of arm movements
|
||||
G1_INSPIRE_FTP_CFG.actuators["arms"] = ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_shoulder_pitch_joint",
|
||||
".*_shoulder_roll_joint",
|
||||
".*_shoulder_yaw_joint",
|
||||
".*_elbow_joint",
|
||||
".*_wrist_.*_joint",
|
||||
],
|
||||
effort_limit=300,
|
||||
velocity_limit=100,
|
||||
stiffness=3000.0,
|
||||
damping=100.0,
|
||||
armature={
|
||||
".*_shoulder_.*": 0.001,
|
||||
".*_elbow_.*": 0.001,
|
||||
".*_wrist_.*_joint": 0.001,
|
||||
},
|
||||
)
|
||||
# Actuator configuration for hands (flexibility focused for grasping)
|
||||
# Lower stiffness and damping to improve finger flexibility when grasping objects
|
||||
G1_INSPIRE_FTP_CFG.actuators["hands"] = ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_index_.*",
|
||||
".*_middle_.*",
|
||||
".*_thumb_.*",
|
||||
".*_ring_.*",
|
||||
".*_pinky_.*",
|
||||
],
|
||||
effort_limit_sim=30.0,
|
||||
velocity_limit_sim=10.0,
|
||||
stiffness=10.0,
|
||||
damping=0.2,
|
||||
armature=0.001,
|
||||
)
|
||||
313
source/mindbot/mindbot/robot/unitree_brainco.py
Normal file
313
source/mindbot/mindbot/robot/unitree_brainco.py
Normal file
@@ -0,0 +1,313 @@
|
||||
# Copyright (c) 2022-2026, The Isaac Lab Project Developers.
|
||||
# All rights reserved.
|
||||
#
|
||||
# SPDX-License-Identifier: BSD-3-Clause
|
||||
|
||||
"""Configuration for the Unitree G1 robot with BrainCo hands.
|
||||
|
||||
Available configurations:
|
||||
|
||||
* :obj:`G1_BRAINCO_29DOF_CFG`: Mobile-base BrainCo G1 for locomanipulation tasks.
|
||||
* :obj:`G1_BRAINCO_CFG`: Alias of :obj:`G1_BRAINCO_29DOF_CFG`.
|
||||
* :obj:`G1_BRAINCO_FTP_CFG`: Fixed-base variant for teleoperation / demo collection.
|
||||
"""
|
||||
|
||||
import isaaclab.sim as sim_utils
|
||||
from isaaclab.actuators import DCMotorCfg, ImplicitActuatorCfg
|
||||
from isaaclab.assets.articulation import ArticulationCfg
|
||||
|
||||
from mindbot.utils.assets import MINDBOT_ASSETS_DIR
|
||||
|
||||
|
||||
G1_BRAINCO_ASSET_DIR = f"{MINDBOT_ASSETS_DIR}/robots/g1_with_brainco_hand"
|
||||
"""Asset directory for the rewritten BrainCo-hand G1 robot."""
|
||||
|
||||
|
||||
G1_BRAINCO_USD_PATH = f"{G1_BRAINCO_ASSET_DIR}/g1_29dof_mode_15_brainco_hand.usd"
|
||||
"""Default USD path for the BrainCo-hand G1 asset."""
|
||||
|
||||
|
||||
G1_BRAINCO_URDF_PATH = f"{G1_BRAINCO_ASSET_DIR}/g1_29dof_mode_15_brainco_hand.urdf"
|
||||
"""URDF path used by Pinocchio / Pink IK for the BrainCo-hand G1 asset."""
|
||||
|
||||
|
||||
G1_BRAINCO_URDF_MESH_DIR = G1_BRAINCO_ASSET_DIR
|
||||
"""Root mesh directory for resolving relative URDF mesh paths."""
|
||||
|
||||
|
||||
G1_BRAINCO_LEFT_HAND_JOINT_NAMES = [
|
||||
"left_index_proximal_joint",
|
||||
"left_middle_proximal_joint",
|
||||
"left_ring_proximal_joint",
|
||||
"left_pinky_proximal_joint",
|
||||
"left_thumb_metacarpal_joint",
|
||||
"left_thumb_proximal_joint",
|
||||
]
|
||||
"""Actuated left-hand joints in the rewritten BrainCo asset."""
|
||||
|
||||
|
||||
G1_BRAINCO_RIGHT_HAND_JOINT_NAMES = [
|
||||
"right_index_proximal_joint",
|
||||
"right_middle_proximal_joint",
|
||||
"right_ring_proximal_joint",
|
||||
"right_pinky_proximal_joint",
|
||||
"right_thumb_metacarpal_joint",
|
||||
"right_thumb_proximal_joint",
|
||||
]
|
||||
"""Actuated right-hand joints in the rewritten BrainCo asset."""
|
||||
|
||||
|
||||
G1_BRAINCO_HAND_JOINT_NAMES = G1_BRAINCO_LEFT_HAND_JOINT_NAMES + G1_BRAINCO_RIGHT_HAND_JOINT_NAMES
|
||||
"""Ordered actuated hand joints used by teleoperation and Pink IK action terms."""
|
||||
|
||||
|
||||
G1_BRAINCO_HAND_JOINT_PATTERNS = [
|
||||
".*_index_proximal_joint",
|
||||
".*_middle_proximal_joint",
|
||||
".*_ring_proximal_joint",
|
||||
".*_pinky_proximal_joint",
|
||||
".*_thumb_metacarpal_joint",
|
||||
".*_thumb_proximal_joint",
|
||||
]
|
||||
"""Regex patterns that match actuated BrainCo finger joints in the rewritten USD."""
|
||||
|
||||
|
||||
G1_BRAINCO_29DOF_CFG = ArticulationCfg(
|
||||
spawn=sim_utils.UsdFileCfg(
|
||||
usd_path=G1_BRAINCO_USD_PATH,
|
||||
activate_contact_sensors=True,
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(
|
||||
disable_gravity=False,
|
||||
retain_accelerations=False,
|
||||
linear_damping=0.0,
|
||||
angular_damping=0.0,
|
||||
max_linear_velocity=1000.0,
|
||||
max_angular_velocity=1000.0,
|
||||
max_depenetration_velocity=1.0,
|
||||
),
|
||||
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
|
||||
enabled_self_collisions=False,
|
||||
fix_root_link=False,
|
||||
solver_position_iteration_count=8,
|
||||
solver_velocity_iteration_count=4,
|
||||
),
|
||||
),
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 0.75),
|
||||
rot=(0.7071, 0.0, 0.0, 0.7071),
|
||||
joint_pos={
|
||||
".*_hip_pitch_joint": -0.10,
|
||||
".*_knee_joint": 0.30,
|
||||
".*_ankle_pitch_joint": -0.20,
|
||||
".*_shoulder_pitch_joint": 0.35,
|
||||
"left_shoulder_roll_joint": 0.16,
|
||||
"right_shoulder_roll_joint": -0.16,
|
||||
".*_elbow_joint": 0.50,
|
||||
# ".*": 0.0,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
),
|
||||
soft_joint_pos_limit_factor=0.9,
|
||||
actuators={
|
||||
"legs": DCMotorCfg(
|
||||
joint_names_expr=[
|
||||
".*_hip_yaw_joint",
|
||||
".*_hip_roll_joint",
|
||||
".*_hip_pitch_joint",
|
||||
".*_knee_joint",
|
||||
],
|
||||
effort_limit={
|
||||
".*_hip_yaw_joint": 88.0,
|
||||
".*_hip_roll_joint": 139.0,
|
||||
".*_hip_pitch_joint": 88.0,
|
||||
".*_knee_joint": 139.0,
|
||||
},
|
||||
velocity_limit={
|
||||
".*_hip_yaw_joint": 32.0,
|
||||
".*_hip_roll_joint": 32.0,
|
||||
".*_hip_pitch_joint": 32.0,
|
||||
".*_knee_joint": 20.0,
|
||||
},
|
||||
stiffness={
|
||||
".*_hip_yaw_joint": 150.4769,
|
||||
".*_hip_roll_joint": 62.1413,
|
||||
".*_hip_pitch_joint": 24.8449,
|
||||
".*_knee_joint": 230.0900,
|
||||
},
|
||||
damping={
|
||||
".*_hip_yaw_joint": 0.0602,
|
||||
".*_hip_roll_joint": 0.0249,
|
||||
".*_hip_pitch_joint": 0.0099,
|
||||
".*_knee_joint": 0.0920,
|
||||
},
|
||||
armature={
|
||||
".*_hip_.*": 0.03,
|
||||
".*_knee_joint": 0.03,
|
||||
},
|
||||
saturation_effort=180.0,
|
||||
),
|
||||
"feet": DCMotorCfg(
|
||||
joint_names_expr=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"],
|
||||
effort_limit={
|
||||
".*_ankle_pitch_joint": 50.0,
|
||||
".*_ankle_roll_joint": 50.0,
|
||||
},
|
||||
velocity_limit={
|
||||
".*_ankle_pitch_joint": 37.0,
|
||||
".*_ankle_roll_joint": 37.0,
|
||||
},
|
||||
stiffness={
|
||||
".*_ankle_pitch_joint": 64.9368,
|
||||
".*_ankle_roll_joint": 2.3020,
|
||||
},
|
||||
damping={
|
||||
".*_ankle_pitch_joint": 0.0260,
|
||||
".*_ankle_roll_joint": 0.0009,
|
||||
},
|
||||
armature=0.03,
|
||||
saturation_effort=80.0,
|
||||
),
|
||||
"waist": ImplicitActuatorCfg(
|
||||
joint_names_expr=["waist_.*_joint"],
|
||||
effort_limit={
|
||||
"waist_yaw_joint": 88.0,
|
||||
"waist_roll_joint": 50.0,
|
||||
"waist_pitch_joint": 50.0,
|
||||
},
|
||||
velocity_limit={
|
||||
"waist_yaw_joint": 32.0,
|
||||
"waist_roll_joint": 37.0,
|
||||
"waist_pitch_joint": 37.0,
|
||||
},
|
||||
stiffness={
|
||||
"waist_yaw_joint": 27.7928,
|
||||
"waist_roll_joint": 54.2666,
|
||||
"waist_pitch_joint": 53.3254,
|
||||
},
|
||||
damping={
|
||||
"waist_yaw_joint": 0.0111,
|
||||
"waist_roll_joint": 0.0217,
|
||||
"waist_pitch_joint": 0.0213,
|
||||
},
|
||||
armature=0.001,
|
||||
),
|
||||
"arms": ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_shoulder_pitch_joint",
|
||||
".*_shoulder_roll_joint",
|
||||
".*_shoulder_yaw_joint",
|
||||
".*_elbow_joint",
|
||||
".*_wrist_.*_joint",
|
||||
],
|
||||
effort_limit={
|
||||
".*_shoulder_pitch_joint": 25.0,
|
||||
".*_shoulder_roll_joint": 25.0,
|
||||
".*_shoulder_yaw_joint": 25.0,
|
||||
".*_elbow_joint": 25.0,
|
||||
".*_wrist_roll_joint": 25.0,
|
||||
".*_wrist_pitch_joint": 5.0,
|
||||
".*_wrist_yaw_joint": 5.0,
|
||||
},
|
||||
velocity_limit=100.0,
|
||||
stiffness={
|
||||
".*_shoulder_pitch_joint": 168.7152,
|
||||
".*_shoulder_roll_joint": 151.6808,
|
||||
".*_shoulder_yaw_joint": 141.6967,
|
||||
".*_elbow_joint": 88.9802,
|
||||
".*_wrist_roll_joint": 66.6865,
|
||||
".*_wrist_pitch_joint": 26.5734,
|
||||
".*_wrist_yaw_joint": 16.3066,
|
||||
},
|
||||
damping={
|
||||
".*_shoulder_pitch_joint": 0.0675,
|
||||
".*_shoulder_roll_joint": 0.0607,
|
||||
".*_shoulder_yaw_joint": 0.0567,
|
||||
".*_elbow_joint": 0.0356,
|
||||
".*_wrist_roll_joint": 0.0267,
|
||||
".*_wrist_pitch_joint": 0.0106,
|
||||
".*_wrist_yaw_joint": 0.0065,
|
||||
},
|
||||
armature={
|
||||
".*_shoulder_.*": 0.001,
|
||||
".*_elbow_.*": 0.001,
|
||||
".*_wrist_.*_joint": 0.001,
|
||||
},
|
||||
),
|
||||
"hands": ImplicitActuatorCfg(
|
||||
joint_names_expr=G1_BRAINCO_HAND_JOINT_PATTERNS,
|
||||
effort_limit_sim=30.0,
|
||||
velocity_limit_sim=10.0,
|
||||
stiffness={
|
||||
".*_(index|middle|ring|pinky)_proximal_joint": 0.25,
|
||||
".*_thumb_metacarpal_joint": 0.31,
|
||||
".*_thumb_proximal_joint": 0.13,
|
||||
},
|
||||
damping={
|
||||
".*_(index|middle|ring|pinky)_proximal_joint": 0.0001,
|
||||
".*_thumb_metacarpal_joint": 0.0001,
|
||||
".*_thumb_proximal_joint": 0.00005,
|
||||
},
|
||||
armature=0.001,
|
||||
),
|
||||
},
|
||||
prim_path="/World/envs/env_.*/Robot",
|
||||
)
|
||||
"""Mobile-base BrainCo G1 configuration for locomotion + manipulation tasks."""
|
||||
|
||||
|
||||
G1_BRAINCO_CFG = G1_BRAINCO_29DOF_CFG
|
||||
"""Backward-compatible alias used by task configuration files."""
|
||||
|
||||
|
||||
G1_BRAINCO_FTP_CFG = G1_BRAINCO_29DOF_CFG.copy()
|
||||
G1_BRAINCO_FTP_CFG.spawn.activate_contact_sensors = True
|
||||
G1_BRAINCO_FTP_CFG.spawn.articulation_props.fix_root_link = True
|
||||
G1_BRAINCO_FTP_CFG.init_state = ArticulationCfg.InitialStateCfg(
|
||||
pos=(0.0, 0.0, 1.0),
|
||||
joint_pos={
|
||||
".*_hip_pitch_joint": -0.10,
|
||||
".*_knee_joint": 0.30,
|
||||
".*_ankle_pitch_joint": -0.20,
|
||||
".*_shoulder_pitch_joint": 0.35,
|
||||
"left_shoulder_roll_joint": 0.16,
|
||||
"right_shoulder_roll_joint": -0.16,
|
||||
".*_elbow_joint": 0.50,
|
||||
".*": 0.0,
|
||||
},
|
||||
joint_vel={".*": 0.0},
|
||||
)
|
||||
G1_BRAINCO_FTP_CFG.actuators["arms"] = ImplicitActuatorCfg(
|
||||
joint_names_expr=[
|
||||
".*_shoulder_pitch_joint",
|
||||
".*_shoulder_roll_joint",
|
||||
".*_shoulder_yaw_joint",
|
||||
".*_elbow_joint",
|
||||
".*_wrist_.*_joint",
|
||||
],
|
||||
effort_limit={
|
||||
".*_shoulder_pitch_joint": 25.0,
|
||||
".*_shoulder_roll_joint": 25.0,
|
||||
".*_shoulder_yaw_joint": 25.0,
|
||||
".*_elbow_joint": 25.0,
|
||||
".*_wrist_roll_joint": 25.0,
|
||||
".*_wrist_pitch_joint": 5.0,
|
||||
".*_wrist_yaw_joint": 5.0,
|
||||
},
|
||||
velocity_limit=100.0,
|
||||
stiffness=3000.0,
|
||||
damping=100.0,
|
||||
armature={
|
||||
".*_shoulder_.*": 0.001,
|
||||
".*_elbow_.*": 0.001,
|
||||
".*_wrist_.*_joint": 0.001,
|
||||
},
|
||||
)
|
||||
G1_BRAINCO_FTP_CFG.actuators["hands"] = ImplicitActuatorCfg(
|
||||
joint_names_expr=G1_BRAINCO_HAND_JOINT_PATTERNS,
|
||||
effort_limit_sim=30.0,
|
||||
velocity_limit_sim=10.0,
|
||||
stiffness=10.0,
|
||||
damping=0.2,
|
||||
armature=0.001,
|
||||
)
|
||||
"""Fixed-base BrainCo G1 configuration suited for teleoperation and demo recording."""
|
||||
@@ -51,7 +51,8 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
prim_path="/World/envs/env_.*/PackingTable",
|
||||
init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.55, -0.1], rot=[1.0, 0.0, 0.0, 0.0]),
|
||||
spawn=UsdFileCfg(
|
||||
usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd",
|
||||
# usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd",
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/PackingTable/packing_table_v2.usd",
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
|
||||
),
|
||||
)
|
||||
@@ -67,14 +68,14 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
dryingbox = DRYINGBOX_CFG.replace(
|
||||
prim_path="{ENV_REGEX_NS}/Dryingbox",
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=[0.0, 0.45, 0.90],
|
||||
pos=[-0.05, 0.65, 0.90],
|
||||
rot=[1.0, 0.0, 0.0, 0.0],
|
||||
# joint_pos={"RevoluteJoint": -1.7453}, # -100°
|
||||
),
|
||||
)
|
||||
rack= RigidObjectCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Rack",
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.4,0.4,0.8996],rot=[1,0,0,0]),
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.5,0.4,0.8996],rot=[1,0,0,0]),
|
||||
spawn=UsdFileCfg(
|
||||
# usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Test_Tube_Rack (2)/tube.usd",
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Test_Tube_Rack (2)/Test_Tube_Rack_AA_01.usdc",
|
||||
@@ -84,7 +85,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
)
|
||||
tube= RigidObjectCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Tube",
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.42374,0.32415,0.912],rot=[1,0,0,0]),
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.52374,0.32415,0.912],rot=[1,0,0,0]),
|
||||
spawn=UsdFileCfg(
|
||||
# usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Test_Tube_Rack (2)/tube.usd",
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Collected_Test_Tube_AA_01/Test_Tube_AA_01.usdc",
|
||||
@@ -96,7 +97,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
beaker = RigidObjectCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Beaker",
|
||||
init_state=RigidObjectCfg.InitialStateCfg(
|
||||
pos=[-0.20, 0.324, 0.93], # 根据你的天平中心位置微调
|
||||
pos=[-0.30, 0.324, 0.93], # 根据你的天平中心位置微调
|
||||
rot=[1, 0, 0, 0]
|
||||
),
|
||||
spawn=UsdFileCfg(
|
||||
@@ -129,7 +130,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
"right_shoulder_pitch_joint": 0.0,
|
||||
"right_shoulder_roll_joint": 0.0,
|
||||
"right_shoulder_yaw_joint": 0.0,
|
||||
"right_elbow_pitch_joint": -1.5708,
|
||||
"right_elbow_pitch_joint": 0.0,#-1.5708
|
||||
"right_wrist_yaw_joint": 0.0,
|
||||
"right_wrist_roll_joint": 0.0,
|
||||
"right_wrist_pitch_joint": 0.0,
|
||||
@@ -137,7 +138,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
"left_shoulder_pitch_joint": 0.0,
|
||||
"left_shoulder_roll_joint": 0.0,
|
||||
"left_shoulder_yaw_joint": 0.0,
|
||||
"left_elbow_pitch_joint": -1.5708,
|
||||
"left_elbow_pitch_joint": 0.0,#-1.5708
|
||||
"left_wrist_yaw_joint": 0.0,
|
||||
"left_wrist_roll_joint": 0.0,
|
||||
"left_wrist_pitch_joint": 0.0,
|
||||
|
||||
@@ -49,9 +49,10 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
# Table
|
||||
packing_table = AssetBaseCfg(
|
||||
prim_path="/World/envs/env_.*/PackingTable",
|
||||
init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.55, -0.1], rot=[1.0, 0.0, 0.0, 0.0]),
|
||||
init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.55, 0.0], rot=[1.0, 0.0, 0.0, 0.0]),
|
||||
spawn=UsdFileCfg(
|
||||
usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd",
|
||||
# usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd",
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/PackingTable/packing_table_v2.usd",
|
||||
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
|
||||
),
|
||||
)
|
||||
@@ -67,14 +68,14 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
dryingoven = DRYINGOVEN_CFG.replace(
|
||||
prim_path="{ENV_REGEX_NS}/Dryingoven",
|
||||
init_state=ArticulationCfg.InitialStateCfg(
|
||||
pos=[0.0, 0.45, 0.90],
|
||||
pos=[0.0, 0.5, 1.0],
|
||||
rot=[1.0, 0.0, 0.0, 0.0],
|
||||
# joint_pos={"RevoluteJoint": -1.7453}, # -100°
|
||||
),
|
||||
)
|
||||
rack= RigidObjectCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Rack",
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.4,0.4,0.8996],rot=[1,0,0,0]),
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.4,0.4,0.9996],rot=[1,0,0,0]),
|
||||
spawn=UsdFileCfg(
|
||||
# usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Test_Tube_Rack (2)/tube.usd",
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Test_Tube_Rack (2)/Test_Tube_Rack_AA_01.usdc",
|
||||
@@ -84,7 +85,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
)
|
||||
tube= RigidObjectCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Tube",
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.42374,0.32415,0.912],rot=[1,0,0,0]),
|
||||
init_state=RigidObjectCfg.InitialStateCfg(pos=[-0.42374,0.32415,1.012],rot=[1,0,0,0]),
|
||||
spawn=UsdFileCfg(
|
||||
# usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Test_Tube_Rack (2)/tube.usd",
|
||||
usd_path=f"{MINDBOT_ASSETS_DIR}/laboratory_equipment/Collected_Test_Tube_AA_01/Test_Tube_AA_01.usdc",
|
||||
@@ -96,7 +97,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
|
||||
beaker = RigidObjectCfg(
|
||||
prim_path="{ENV_REGEX_NS}/Beaker",
|
||||
init_state=RigidObjectCfg.InitialStateCfg(
|
||||
pos=[-0.20, 0.324, 0.93], # 根据你的天平中心位置微调
|
||||
pos=[-0.20, 0.324, 1.03], # 根据你的天平中心位置微调
|
||||
rot=[1, 0, 0, 0]
|
||||
),
|
||||
spawn=UsdFileCfg(
|
||||
|
||||
Reference in New Issue
Block a user