diff --git a/LICENSE b/LICENSE index 899c9b1..b241a5c 100644 --- a/LICENSE +++ b/LICENSE @@ -1,4 +1,4 @@ -Copyright [2024] [HangZhou YuShu TECHNOLOGY CO.,LTD. ("Unitree Robotics")] +Copyright [2025] [HangZhou YuShu TECHNOLOGY CO.,LTD. ("Unitree Robotics")] Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. @@ -27,5 +27,6 @@ This code builds upon following open-source code-bases. Please visit the URLs to 9) https://github.com/tonyzhaozh/act 10) https://github.com/facebookresearch/detr 11) https://github.com/Dingry/BunnyVisionPro +12) https://github.com/unitreerobotics/unitree_sdk2_python ------------------ diff --git a/README.md b/README.md index 8a1908b..6ea826d 100644 --- a/README.md +++ b/README.md @@ -31,7 +31,7 @@ Here are the robots that will be supported,
@@ -100,6 +101,8 @@ In the Ubuntu system's `~/.bashrc` file, the default configuration is: `PS1='${d (tv) unitree@Host:~$ pip install -e . ``` +> p.s. The [unitree_dds_wrapper](https://github.com/unitreerobotics/unitree_dds_wrapper) in the original h1_2 branch was a temporary version. It has now been fully migrated to the official Python-based control and communication library: [unitree_sdk2_python](https://github.com/unitreerobotics/unitree_sdk2_python). + # 2. ⚙️ TeleVision and Apple Vision Pro configuration @@ -179,13 +182,20 @@ Copy `image_server.py` in the `avp_teleoperate/teleop/image_server` directory to ```bash # p.s.1 You can transfer image_server.py to PC2 via the scp command and then use ssh to remotely login to PC2 to execute it. -# p.s.2 The image transfer program is currently configured for binocular rgb cameras. +# Assuming the IP address of the development computing unit PC2 is 192.168.123.164, the transmission process is as follows: +# log in to PC2 via SSH and create the folder for the image server +(tv) unitree@Host:~$ ssh unitree@192.168.123.164 "mkdir -p ~/image_server" +# Copy the local image_server.py to the ~/image_server directory on PC2 +(tv) unitree@Host:~$ scp ~/avp_teleoperate/teleop/image_server/image_server.py unitree@192.168.123.164:~/image_server/ + +# p.s.2 Currently, this image transmission program supports two methods for reading images: OpenCV and Realsense SDK. Please refer to the comments in the `ImageServer` class within `image_server.py` to configure your image transmission service according to your camera hardware. # Now located in Unitree Robot PC2 terminal unitree@PC2:~/image_server$ python image_server.py # You can see the terminal output as follows: -# Image server has started, waiting for client connections... -# Image Resolution: width is 640, height is 480 +# {'fps': 30, 'head_camera_type': 'opencv', 'head_camera_image_shape': [480, 1280], 'head_camera_id_numbers': [0]} +# [Image Server] Head camera 0 resolution: 480.0 x 1280.0 +# [Image Server] Image server has started, waiting for client connections... ``` After image service is started, you can use `image_client.py` **in the Host** terminal to test whether the communication is successful: @@ -196,7 +206,7 @@ After image service is started, you can use `image_client.py` **in the Host** te ## 3.2 ✋ Inspire hands Server (optional) -> Note: If the selected robot configuration does not use the Inspire dexterous hand, please ignore this section. +> Note: If the selected robot configuration does not use the Inspire dexterous hand (Gen1), please ignore this section. You can refer to [Dexterous Hand Development](https://support.unitree.com/home/zh/H1_developer/Dexterous_hand) to configure related environments and compile control programs. First, use [this URL](https://oss-global-cdn.unitree.com/static/0a8335f7498548d28412c31ea047d4be.zip) to download the dexterous hand control interface program. Copy it to **PC2** of Unitree robots. @@ -229,13 +239,33 @@ If two hands open and close continuously, it indicates success. Once successful, It's best to have two operators to run this program, referred to as **Operator A** and **Operator B**. -Now, **Operator B** execute the following command on **Host machine** : -```bash -(tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --record -``` -And then, **Operator A** +First, **Operator B** needs to perform the following steps: + +1. Modify the `img_config` image client configuration under the `if __name__ == '__main__':` section in `~/avp_teleoperate/teleop/teleop_hand_and_arm.py`. It should match the image server parameters you configured on PC2 in Section 3.1. + +2. Choose different launch parameters based on your robot configuration + + ```bash + # 1. G1 (29DoF) Robot + Dex3-1 Dexterous Hand (Note: G1_29 is the default value for --arm, so it can be omitted) + (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --arm=G1_29 --hand=dex3 + + # 2. G1 (29DoF) Robot only + (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py + + # 3. H1_2 Robot (Note: The first-generation Inspire Dexterous Hand is currently only supported in the H1_2 branch. Support for the Main branch will be added later.) + (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --arm=H1_2 + + # 4. If you want to enable data visualization + recording, you can add the --record option + (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --record + ``` + +3. If the program starts successfully, the terminal will pause at the final line displaying the message: "Please enter the start signal (enter 'r' to start the subsequent program):" + + + +And then, **Operator A** needs to perform the following steps: 1. Wear your Apple Vision Pro device. @@ -245,13 +275,19 @@ And then, **Operator A** 3. Click `Enter VR` and `Allow` to start the VR session. -When host terminal outputs "Please enter the start signal (enter 'r' to start the subsequent program):", **Operator B** can start teleoperation program by pressing the **r** key in the terminal. +4. You will see the robot's first-person perspective in the Apple Vision Pro. -At this time, **Operator A** can remotely control the robot's arms and dexterous hands. -Next, **Operator B** can press **s** key to begin recording data in the 'record image' window that opens, and press **s** again to stop. This can be repeated as necessary. -> p.s. Recorded data is stored in `avp_teleoperate/teleop/utils/data` by default, with usage instructions at this repo: [unitree_IL_lerobot](https://github.com/unitreerobotics/unitree_IL_lerobot/tree/main?tab=readme-ov-file#data-collection-and-conversion). +Next, **Operator B** can start teleoperation program by pressing the **r** key in the terminal. + +At this time, **Operator A** can remotely control the robot's arms (and dexterous hands). + +If the `--record` parameter is used, **Operator B** can press **s** key in the opened "record image" window to start recording data, and press **s** again to stop. This operation can be repeated as needed for multiple recordings. + +> p.s.1 Recorded data is stored in `avp_teleoperate/teleop/utils/data` by default, with usage instructions at this repo: [unitree_IL_lerobot](https://github.com/unitreerobotics/unitree_IL_lerobot/tree/main?tab=readme-ov-file#data-collection-and-conversion). +> +> p.s.2 Please pay attention to your disk space size during data recording. ## 3.4 🔚 Exit @@ -291,7 +327,6 @@ avp_teleoperate/ │ │ ├── weighted_moving_filter.py [For filtering joint data] │ │ │ │──teleop_hand_and_arm.py [Startup execution code for teleoperation] -| |——teleop_test_gym.py [Can be used to verify that the environment is installed correctly] ``` @@ -391,3 +426,4 @@ This code builds upon following open-source code-bases. Please visit the URLs to 9) https://github.com/tonyzhaozh/act 10) https://github.com/facebookresearch/detr 11) https://github.com/Dingry/BunnyVisionPro +12) https://github.com/unitreerobotics/unitree_sdk2_python diff --git a/README_ja-JP.md b/README_ja-JP.md index 6037d8d..416606d 100644 --- a/README_ja-JP.md +++ b/README_ja-JP.md @@ -20,38 +20,16 @@ # 0. 📖 イントロダクション このリポジトリは、**Apple Vision Pro** を使用して **Unitree ヒューマノイドロボット** を遠隔操作するためのものです。 -サポートされるロボットは以下の通りです。 +以下は、このリポジトリがサポートするロボットの種類です: -
| 🤖 ロボット | -⚪ ステータス | -📝 備考 | -
|---|---|---|
| G1 (29DoF) + Dex3-1 | -✅ 完了 | -- |
| H1 (アーム 4DoF) | -⏱ 進行中 | -このブランチのikを一時的に参照 | -
| H1_2 (アーム 7DoF) + Inspire | -✅ 完了 | -このブランチを参照 | -
| ··· | -··· | -··· | -
@@ -78,7 +56,7 @@ unitree@Host:~$ conda activate tv
(tv) unitree@Host:~$ pip install casadi
```
-> p.s. コマンドの前にあるすべての識別子は、**どのデバイスとディレクトリでコマンドを実行するべきか**を示すためのものです。
+> 注意:コマンドの前にあるすべての識別子は、**どのデバイスとディレクトリでコマンドを実行するべきか**を示すためのものです。
>
Ubuntu システムの `~/.bashrc` ファイルでは、デフォルトの設定は次の通りです: `PS1='${debian_chroot:+($debian_chroot)}\u@\h:\w\$ '`
>
@@ -100,6 +78,8 @@ Ubuntu システムの `~/.bashrc` ファイルでは、デフォルトの設定
(tv) unitree@Host:~$ pip install -e .
```
+> 注意:元の h1_2 ブランチの [unitree_dds_wrapper](https://github.com/unitreerobotics/unitree_dds_wrapper) は一時的なバージョンであり、現在は公式の Python 版制御通信ライブラリ [unitree_sdk2_python](https://github.com/unitreerobotics/unitree_sdk2_python) に完全に移行されています。
+
# 2. ⚙️ TeleVision と Apple Vision Pro の設定
@@ -158,34 +138,13 @@ Ubuntu システムの `~/.bashrc` ファイルでは、デフォルトの設定
設定 > アプリ > Safari > 高度な設定 > 機能フラグ > WebXR 関連機能を有効にします。
-## 2.3 🔎 テスト環境
-
-このステップは、環境が正しくインストールされているかを確認するためのものです。
-
-1. Isaac Gym をダウンロードします: https://developer.nvidia.com/isaac-gym/download
+> 注意:新しい Vision OS 2 システムでは、この手順が異なります。証明書を AirDrop 経由で Apple Vision Pro デバイスにコピーした後、設定アプリの左上のアカウント欄の下に証明書関連情報欄が表示されます。それをクリックして、証明書の信頼を有効にします。
- 現在のディレクトリに解凍し、`IsaacGym_Preview_4_Package/isaacgym/python` ディレクトリに移動して、次のコマンドを実行します:
+## 2.3 🔎 ユニットテスト
- ```bash
- (tv) unitree@Host:~/IsaacGym_Preview_4_Package/isaacgym/python$ pip install -e .
- ```
-
-2. 上記の手順に従ってローカルでストリーミングを設定した後、Isaac Gym で 2 つのロボットハンドを遠隔操作してみてください:
-
- ```bash
- (tv) unitree@Host:~/avp_teleoperate$ cd teleop
- (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_test_gym.py
- ```
-
-3. Apple Vision Pro デバイスを装着します。
-
-4. Apple Vision Pro で Safari を開き、次の URL にアクセスします: https://192.168.123.2:8012?ws=wss://192.168.123.2:8012
-
- > p.s. この IP アドレスは **ホストマシン** の IP アドレスと一致する必要があります。
-
-5. `Enter VR` をクリックし、`Allow` を選択して VR セッションを開始します。
+このステップは、環境が正しくインストールされているかを確認するためのものです。
-6. 3D で手を確認します!
+近日公開。
@@ -201,14 +160,20 @@ Ubuntu システムの `~/.bashrc` ファイルでは、デフォルトの設定
`avp_teleoperate/teleop/image_server` ディレクトリにある `image_server.py` を Unitree ロボット (G1/H1/H1_2 など) の **開発用コンピューティングユニット PC2** にコピーし、**PC2** で次のコマンドを実行します:
```bash
-# p.s.1 scp コマンドを使用して image_server.py を PC2 に転送し、ssh を使用して PC2 にリモートログインして実行できます。
-# p.s.2 画像転送プログラムは現在、双眼 RGB カメラ用に設定されています。
-
+# 注意1:scp コマンドを使用して image_server.py を PC2 に転送し、ssh を使用して PC2 にリモートログインして実行できます。
+# 開発用コンピューティングユニット PC2 の IP アドレスが 192.168.123.164 であると仮定すると、転送プロセスは以下のようになります:
+# まず ssh で PC2 にログインし、画像サーバーのフォルダを作成します
+(tv) unitree@Host:~$ ssh unitree@192.168.123.164 "mkdir -p ~/image_server"
+# ローカルの image_server.py を PC2 の ~/image_server ディレクトリにコピーします
+(tv) unitree@Host:~$ scp ~/avp_teleoperate/teleop/image_server/image_server.py unitree@192.168.123.164:~/image_server/
+
+# 注意2:現在、この画像転送プログラムは OpenCV と Realsense SDK の 2 つの画像読み取り方法をサポートしています。image_server.py の ImageServer クラスのコメントを読んで、カメラハードウェアに応じて画像転送サービスを設定してください。
# 現在、Unitree ロボット PC2 端末にいます
unitree@PC2:~/image_server$ python image_server.py
-# 端末に次のように出力されます:
-# Image server has started, waiting for client connections...
-# Image Resolution: width is 640, height is 480
+# 端末に次のように出力されます:
+# {'fps': 30, 'head_camera_type': 'opencv', 'head_camera_image_shape': [480, 1280], 'head_camera_id_numbers': [0]}
+# [Image Server] Head camera 0 resolution: 480.0 x 1280.0
+# [Image Server] Image server has started, waiting for client connections...
```
画像サービスが開始された後、**ホスト** 端末で `image_client.py` を使用して通信が成功したかどうかをテストできます:
@@ -252,13 +217,32 @@ unitree@PC2:~/h1_inspire_service/build$ ./h1_hand_example
このプログラムを実行するには、**オペレーター A** と **オペレーター B** と呼ばれる 2 人のオペレーターがいるのが最適です。
-今、**オペレーター B** は **ホストマシン** で次のコマンドを実行します:
+
+
+まず、**オペレーター B** は次の手順を実行する必要があります:
+
+1. `~/avp_teleoperate/teleop/teleop_hand_and_arm.py` の `if __name__ == '__main__':` コードの下にある `img_config` 画像クライアント設定を変更します。これは、3.1 節で PC2 に設定した画像サーバーパラメータと同じである必要があります。
+2. ロボット構成に応じて異なる起動パラメータを選択します
```bash
+# 1. G1(29自由度) ロボット + Dex3-1 デクスタラスハンド(実際には、G1_29 は --arm のデフォルトパラメータなので、省略可能)
+(tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --arm=G1_29 --hand=dex3
+
+# 2. G1(29自由度) ロボットのみ
+(tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py
+
+# 3. H1_2 ロボット(Inspire デクスタラスハンドは一時的に H1_2 ブランチでのみサポートされ、Main ブランチは後で更新されます)
+(tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --arm=H1_2
+
+# 4. データの可視化と記録を有効にする場合は、--record オプションを追加します
(tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --record
```
-そして、**オペレーター A** は
+3. プログラムが正常に起動すると、端末の最後の行に "Please enter the start signal (enter 'r' to start the subsequent program):" というメッセージが表示されます。
+
+
+
+次に、**オペレーター A** は次の手順を実行します:
1. Apple Vision Pro デバイスを装着します。
@@ -268,13 +252,19 @@ unitree@PC2:~/h1_inspire_service/build$ ./h1_hand_example
3. `Enter VR` をクリックし、`Allow` を選択して VR セッションを開始します。
-ホスト端末が "Please enter the start signal (enter 'r' to start the subsequent program):" と出力したら、**オペレーター B** は端末で **r** キーを押して遠隔操作プログラムを開始できます。
+4. Apple Vision Pro でロボットの一人称視点が表示されます。
+
-この時点で、**オペレーター A** はロボットのアームとデクスタラスハンドを遠隔操作できます。
-次に、**オペレーター B** は開いている "record image" ウィンドウで **s** キーを押してデータの記録を開始し、再度 **s** キーを押して停止できます。必要に応じてこれを繰り返すことができます。
+次に、**オペレーター B** は端末で **r** キーを押して遠隔操作プログラムを開始します。
-> p.s. 記録されたデータはデフォルトで `avp_teleoperate/teleop/utils/data` に保存されます。使用方法については、このリポジトリを参照してください: [unitree_IL_lerobot](https://github.com/unitreerobotics/unitree_IL_lerobot/tree/main?tab=readme-ov-file#data-collection-and-conversion)。
+この時点で、**オペレーター A** はロボットのアーム(およびデクスタラスハンド)を遠隔操作できます。
+
+`--record` パラメータを使用した場合、**オペレーター B** は開いている "record image" ウィンドウで **s** キーを押してデータの記録を開始し、再度 **s** キーを押して停止できます。必要に応じてこれを繰り返すことができます。
+
+> 注意1:記録されたデータはデフォルトで `avp_teleoperate/teleop/utils/data` に保存されます。使用方法については、このリポジトリを参照してください: [unitree_IL_lerobot](https://github.com/unitreerobotics/unitree_IL_lerobot/tree/main?tab=readme-ov-file#data-collection-and-conversion)。
+>
+> 注意2:データ記録時にはディスク容量に注意してください。
## 3.4 🔚 終了
@@ -314,7 +304,6 @@ avp_teleoperate/
│ │ ├── weighted_moving_filter.py [ジョイントデータをフィルタリングするため]
│ │
│ │──teleop_hand_and_arm.py [遠隔操作の起動実行コード]
-| |——teleop_test_gym.py [環境が正しくインストールされているかを確認するために使用できます]
```
@@ -414,3 +403,4 @@ avp_teleoperate/
9) https://github.com/tonyzhaozh/act
10) https://github.com/facebookresearch/detr
11) https://github.com/Dingry/BunnyVisionPro
+12) https://github.com/unitreerobotics/unitree_sdk2_python
diff --git a/README_zh-CN.md b/README_zh-CN.md
index 6d0fbfd..2019399 100644
--- a/README_zh-CN.md
+++ b/README_zh-CN.md
@@ -30,7 +30,7 @@
@@ -101,6 +102,8 @@ unitree@Host:~$ conda activate tv
(tv) unitree@Host:~$ pip install -e .
```
+> 提醒:原 h1_2 分支中的 [unitree_dds_wrapper](https://github.com/unitreerobotics/unitree_dds_wrapper) 为临时版本,现已全面转换到上述正式的 Python 版控制通信库:[unitree_sdk2_python](https://github.com/unitreerobotics/unitree_sdk2_python)
+
# 2. ⚙️ TeleVision 和 Apple Vision Pro 配置
@@ -179,13 +182,19 @@ unitree@Host:~$ conda activate tv
```bash
# 提醒1:可以通过scp命令将image_server.py传输到PC2,然后使用ssh远程登录PC2后执行它。
-# 提醒2:目前该图像传输程序是为双目RGB相机配置的。
+# 假设开发计算单元PC2的ip地址为192.168.123.164,那么传输过程示例如下:
+# 先ssh登录PC2,创建图像服务器的文件夹
+(tv) unitree@Host:~$ ssh unitree@192.168.123.164 "mkdir -p ~/image_server"
+# 将本地的image_server.py拷贝至PC2的~/image_server目录下
+(tv) unitree@Host:~$ scp ~/avp_teleoperate/teleop/image_server/image_server.py unitree@192.168.123.164:~/image_server/
+# 提醒2:目前该图像传输程序支持OpenCV和Realsense SDK两种读取图像的方式,请阅读image_server.py的ImageServer类的注释以便您根据自己的相机硬件来配置自己的图像传输服务。
# 现在位于宇树机器人 PC2 终端
unitree@PC2:~/image_server$ python image_server.py
# 您可以看到终端输出如下:
-# Image server has started, waiting for client connections...
-# Image Resolution: width is 640, height is 480
+# {'fps': 30, 'head_camera_type': 'opencv', 'head_camera_image_shape': [480, 1280], 'head_camera_id_numbers': [0]}
+# [Image Server] Head camera 0 resolution: 480.0 x 1280.0
+# [Image Server] Image server has started, waiting for client connections...
```
在图像服务启动后,您可以在 **主机** 终端上使用 `image_client.py` 测试通信是否成功:
@@ -196,7 +205,7 @@ unitree@PC2:~/image_server$ python image_server.py
## 3.2 ✋ Inspire 手部服务器(可选)
-> 注意:如果选择的机器人配置中没有使用 Inspire 灵巧手,那么请忽略本节内容。
+> 注意:如果选择的机器人配置中没有使用一代 Inspire 灵巧手,那么请忽略本节内容。
您可以参考 [灵巧手开发](https://support.unitree.com/home/zh/H1_developer/Dexterous_hand) 配置相关环境并编译控制程序。首先,使用 [此链接](https://oss-global-cdn.unitree.com/static/0a8335f7498548d28412c31ea047d4be.zip) 下载灵巧手控制接口程序,然后将其复制到宇树机器人的**PC2**。
@@ -226,13 +235,33 @@ unitree@PC2:~/h1_inspire_service/build$ ./h1_hand_example
最好有两名操作员来运行此程序,称为 **操作员 A** 和 **操作员 B**。
-现在,**操作员 B** 在 **主机** 上执行以下命令:
-```bash
-(tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --record
-```
-然后,**操作员 A**:
+首先,**操作员 B** 需要执行以下步骤:
+
+1. 修改 `~/avp_teleoperate/teleop/teleop_hand_and_arm.py` 中 `if __name__ == '__main__':` 代码下方的 `img_config` 图像客户端配置,它应该与 3.1 节中您在 PC2 配置的图像服务器参数相同。
+
+2. 根据您的机器人配置选择不同的启动参数
+
+ ```bash
+ # 1. G1(29DoF)机器人 + Dex3-1 灵巧手 (实际上,G1_29是--arm的默认参数,可以选择不填写)
+ (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --arm=G1_29 --hand=dex3
+
+ # 2. 仅G1(29DoF)机器人
+ (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py
+
+ # 3. H1_2机器人,(一代Inspire灵巧手暂时只在 H1_2 分支支持,Main分支将后续更新)
+ (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --arm=H1_2
+
+ # 4. 如果您想开启数据可视化+录制,还可以追加 --record 选项
+ (tv) unitree@Host:~/avp_teleoperate/teleop$ python teleop_hand_and_arm.py --record
+ ```
+
+3. 程序如果正常启动,终端最后一行将停留在 “Please enter the start signal (enter 'r' to start the subsequent program):” 的字符串输出。
+
+
+
+然后,**操作员 A** 需要执行以下步骤:
1. 戴上您的 Apple Vision Pro 设备。
@@ -242,13 +271,19 @@ unitree@PC2:~/h1_inspire_service/build$ ./h1_hand_example
3. 点击 `Enter VR` 并选择 `Allow` 以启动 VR 会话。
-当主机终端输出“Please enter the start signal (enter 'r' to start the subsequent program):”时,**操作员 B** 可以在终端中按下 **r** 键以启动远程操作程序。
+4. 您将会在Apple Vision Pro中看到机器人的第一人称视野。
+
-此时,**操作员 A** 可以远程控制机器人的手臂和灵巧手。
-接下来,**操作员 B** 可以在打开的“record image”窗口中按 **s** 键开始录制数据,再次按 **s** 键停止。可以根据需要重复此操作进行多次录制。
+接下来,**操作员 B** 可以在终端中按下 **r** 键以启动远程操作程序。
-> 注意:录制的数据默认存储在 `avp_teleoperate/teleop/utils/data` 中,使用说明见此仓库: [unitree_IL_lerobot](https://github.com/unitreerobotics/unitree_IL_lerobot/blob/main/README_zh.md#%E6%95%B0%E6%8D%AE%E9%87%87%E9%9B%86%E4%B8%8E%E8%BD%AC%E6%8D%A2)。
+此时,**操作员 A** 可以远程控制机器人的手臂(和灵巧手)。
+
+如果使用了`--record`参数,那么**操作员 B** 可以在打开的“record image”窗口中按 **s** 键开始录制数据,再次按 **s** 键停止。可以根据需要重复此操作进行多次录制。
+
+> 注意1:录制的数据默认存储在 `avp_teleoperate/teleop/utils/data` 中,使用说明见此仓库: [unitree_IL_lerobot](https://github.com/unitreerobotics/unitree_IL_lerobot/blob/main/README_zh.md#%E6%95%B0%E6%8D%AE%E9%87%87%E9%9B%86%E4%B8%8E%E8%BD%AC%E6%8D%A2)。
+>
+> 注意2:请在录制数据时注意您的硬盘空间大小。
## 3.4 🔚 退出
@@ -288,7 +323,6 @@ avp_teleoperate/
│ │ ├── weighted_moving_filter.py [用于过滤关节数据的滤波器]
│ │
│ │──teleop_hand_and_arm.py [遥操作的启动执行代码]
-| |——teleop_test_gym.py [可用于验证环境是否正确安装]
```
@@ -389,3 +423,4 @@ avp_teleoperate/
9. https://github.com/tonyzhaozh/act
10. https://github.com/facebookresearch/detr
11. https://github.com/Dingry/BunnyVisionPro
+12. https://github.com/unitreerobotics/unitree_sdk2_python
diff --git a/requirements.txt b/requirements.txt
index 36c9e5f..cce9de0 100644
--- a/requirements.txt
+++ b/requirements.txt
@@ -3,7 +3,6 @@ aiohttp_cors==0.7.0
aiortc==1.8.0
av==11.0.0
dex_retargeting==0.1.1
-dynamixel_sdk==3.7.31
einops==0.8.0
h5py==3.11.0
ipython==8.12.3
@@ -22,6 +21,5 @@ seaborn==0.13.2
setuptools==69.5.1
torch==2.3.0
torchvision==0.18.0
-tqdm==4.66.4
vuer==0.0.32rc7
-wandb==0.17.3
+rerun-sdk==0.20.1
diff --git a/teleop/teleop_test_gym.py b/teleop/teleop_test_gym.py
deleted file mode 100644
index 252a9b7..0000000
--- a/teleop/teleop_test_gym.py
+++ /dev/null
@@ -1,247 +0,0 @@
-# TODO: this file need to be fixed.
-from isaacgym import gymapi
-from isaacgym import gymtorch
-import math
-import numpy as np
-import torch
-import time
-from pytransform3d import rotations
-
-import os
-import sys
-current_dir = os.path.dirname(os.path.abspath(__file__))
-parent_dir = os.path.dirname(current_dir)
-sys.path.append(parent_dir)
-
-from teleop.open_television.tv_wrapper import TeleVisionWrapper
-from multiprocessing import Process, shared_memory, Array
-from teleop.robot_control.robot_hand_unitree import Dex3_1_Controller
-
-class Sim:
- def __init__(self,
- print_freq=False):
- self.print_freq = print_freq
-
- # initialize gym
- self.gym = gymapi.acquire_gym()
-
- # configure sim
- sim_params = gymapi.SimParams()
- sim_params.dt = 1 / 60
- sim_params.substeps = 2
- sim_params.up_axis = gymapi.UP_AXIS_Z
- sim_params.gravity = gymapi.Vec3(0.0, 0.0, -9.81)
- sim_params.physx.solver_type = 1
- sim_params.physx.num_position_iterations = 4
- sim_params.physx.num_velocity_iterations = 1
- sim_params.physx.max_gpu_contact_pairs = 8388608
- sim_params.physx.contact_offset = 0.002
- sim_params.physx.friction_offset_threshold = 0.001
- sim_params.physx.friction_correlation_distance = 0.0005
- sim_params.physx.rest_offset = 0.0
- sim_params.physx.use_gpu = True
- sim_params.use_gpu_pipeline = False
-
- self.sim = self.gym.create_sim(0, 0, gymapi.SIM_PHYSX, sim_params)
- if self.sim is None:
- print("*** Failed to create sim")
- quit()
-
- plane_params = gymapi.PlaneParams()
- plane_params.distance = 0.0
- plane_params.normal = gymapi.Vec3(0.0, 0.0, 1.0)
- self.gym.add_ground(self.sim, plane_params)
-
- # load table asset
- table_asset_options = gymapi.AssetOptions()
- table_asset_options.disable_gravity = True
- table_asset_options.fix_base_link = True
- table_asset = self.gym.create_box(self.sim, 0.8, 0.8, 0.1, table_asset_options)
-
- # load cube asset
- cube_asset_options = gymapi.AssetOptions()
- cube_asset_options.density = 10
- cube_asset = self.gym.create_box(self.sim, 0.05, 0.05, 0.05, cube_asset_options)
-
- asset_root = "../assets"
- left_asset_path = "unitree_hand/unitree_dex3_left.urdf"
- right_asset_path = "unitree_hand/unitree_dex3_right.urdf"
- asset_options = gymapi.AssetOptions()
- asset_options.fix_base_link = True
- asset_options.default_dof_drive_mode = gymapi.DOF_MODE_POS
- left_asset = self.gym.load_asset(self.sim, asset_root, left_asset_path, asset_options)
- right_asset = self.gym.load_asset(self.sim, asset_root, right_asset_path, asset_options)
- self.dof = self.gym.get_asset_dof_count(left_asset)
- print(f"dof: {self.dof}")
- # set up the env grid
- num_envs = 1
- num_per_row = int(math.sqrt(num_envs))
- env_spacing = 1.25
- env_lower = gymapi.Vec3(-env_spacing, 0.0, -env_spacing)
- env_upper = gymapi.Vec3(env_spacing, env_spacing, env_spacing)
- np.random.seed(0)
- self.env = self.gym.create_env(self.sim, env_lower, env_upper, num_per_row)
-
- # table
- pose = gymapi.Transform()
- pose.p = gymapi.Vec3(0, 0, 1.2)
- pose.r = gymapi.Quat(0, 0, 0, 1)
- table_handle = self.gym.create_actor(self.env, table_asset, pose, 'table', 0)
- color = gymapi.Vec3(0.5, 0.5, 0.5)
- self.gym.set_rigid_body_color(self.env, table_handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, color)
-
- # cube
- pose = gymapi.Transform()
- pose.p = gymapi.Vec3(0, 0, 1.25)
- pose.r = gymapi.Quat(0, 0, 0, 1)
- cube_handle = self.gym.create_actor(self.env, cube_asset, pose, 'cube', 0)
- color = gymapi.Vec3(1, 0.5, 0.5)
- self.gym.set_rigid_body_color(self.env, cube_handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, color)
-
- # left_hand
- pose = gymapi.Transform()
- pose.p = gymapi.Vec3(-0.6, 0, 1.6)
- pose.r = gymapi.Quat(0, 0, 0, 1)
- self.left_handle = self.gym.create_actor(self.env, left_asset, pose, 'left', 1, 1)
- self.gym.set_actor_dof_states(self.env, self.left_handle, np.zeros(self.dof, gymapi.DofState.dtype),
- gymapi.STATE_ALL)
- left_idx = self.gym.get_actor_index(self.env, self.left_handle, gymapi.DOMAIN_SIM)
-
- # right_hand
- pose = gymapi.Transform()
- pose.p = gymapi.Vec3(-0.6, 0, 1.6)
- pose.r = gymapi.Quat(0, 0, 0, 1)
- self.right_handle = self.gym.create_actor(self.env, right_asset, pose, 'right', 1, 1)
- self.gym.set_actor_dof_states(self.env, self.right_handle, np.zeros(self.dof, gymapi.DofState.dtype),
- gymapi.STATE_ALL)
- right_idx = self.gym.get_actor_index(self.env, self.right_handle, gymapi.DOMAIN_SIM)
-
- self.root_state_tensor = self.gym.acquire_actor_root_state_tensor(self.sim)
- self.gym.refresh_actor_root_state_tensor(self.sim)
- self.root_states = gymtorch.wrap_tensor(self.root_state_tensor)
- self.left_root_states = self.root_states[left_idx]
- self.right_root_states = self.root_states[right_idx]
-
- # create default viewer
- self.viewer = self.gym.create_viewer(self.sim, gymapi.CameraProperties())
- if self.viewer is None:
- print("*** Failed to create viewer")
- quit()
- cam_pos = gymapi.Vec3(1, 1, 2)
- cam_target = gymapi.Vec3(0, 0, 1)
- self.gym.viewer_camera_look_at(self.viewer, None, cam_pos, cam_target)
-
- self.cam_lookat_offset = np.array([1, 0, 0])
- self.left_cam_offset = np.array([0, 0.033, 0])
- self.right_cam_offset = np.array([0, -0.033, 0])
- self.cam_pos = np.array([-0.6, 0, 1.6])
-
- # create left 1st preson viewer
- camera_props = gymapi.CameraProperties()
- camera_props.width = 1280
- camera_props.height = 720
- self.left_camera_handle = self.gym.create_camera_sensor(self.env, camera_props)
- self.gym.set_camera_location(self.left_camera_handle,
- self.env,
- gymapi.Vec3(*(self.cam_pos + self.left_cam_offset)),
- gymapi.Vec3(*(self.cam_pos + self.left_cam_offset + self.cam_lookat_offset)))
-
- # create right 1st preson viewer
- camera_props = gymapi.CameraProperties()
- camera_props.width = 1280
- camera_props.height = 720
- self.right_camera_handle = self.gym.create_camera_sensor(self.env, camera_props)
- self.gym.set_camera_location(self.right_camera_handle,
- self.env,
- gymapi.Vec3(*(self.cam_pos + self.right_cam_offset)),
- gymapi.Vec3(*(self.cam_pos + self.right_cam_offset + self.cam_lookat_offset)))
-
- def step(self, head_rmat, left_pose, right_pose, left_qpos, right_qpos):
-
- if self.print_freq:
- start = time.time()
-
- self.left_root_states[0:7] = torch.tensor(left_pose, dtype=float)
- self.right_root_states[0:7] = torch.tensor(right_pose, dtype=float)
- self.gym.set_actor_root_state_tensor(self.sim, gymtorch.unwrap_tensor(self.root_states))
-
- left_states = np.zeros(self.dof, dtype=gymapi.DofState.dtype)
- left_states['pos'] = left_qpos
- self.gym.set_actor_dof_states(self.env, self.left_handle, left_states, gymapi.STATE_POS)
-
- right_states = np.zeros(self.dof, dtype=gymapi.DofState.dtype)
- right_states['pos'] = right_qpos
- self.gym.set_actor_dof_states(self.env, self.right_handle, right_states, gymapi.STATE_POS)
-
- # step the physics
- self.gym.simulate(self.sim)
- self.gym.fetch_results(self.sim, True)
- self.gym.step_graphics(self.sim)
- self.gym.render_all_camera_sensors(self.sim)
- self.gym.refresh_actor_root_state_tensor(self.sim)
-
- curr_lookat_offset = self.cam_lookat_offset @ head_rmat.T
- curr_left_offset = self.left_cam_offset @ head_rmat.T
- curr_right_offset = self.right_cam_offset @ head_rmat.T
-
- self.gym.set_camera_location(self.left_camera_handle,
- self.env,
- gymapi.Vec3(*(self.cam_pos + curr_left_offset)),
- gymapi.Vec3(*(self.cam_pos + curr_left_offset + curr_lookat_offset)))
- self.gym.set_camera_location(self.right_camera_handle,
- self.env,
- gymapi.Vec3(*(self.cam_pos + curr_right_offset)),
- gymapi.Vec3(*(self.cam_pos + curr_right_offset + curr_lookat_offset)))
- left_image = self.gym.get_camera_image(self.sim, self.env, self.left_camera_handle, gymapi.IMAGE_COLOR)
- right_image = self.gym.get_camera_image(self.sim, self.env, self.right_camera_handle, gymapi.IMAGE_COLOR)
- left_image = left_image.reshape(left_image.shape[0], -1, 4)[..., :3]
- right_image = right_image.reshape(right_image.shape[0], -1, 4)[..., :3]
-
- self.gym.draw_viewer(self.viewer, self.sim, True)
- self.gym.sync_frame_time(self.sim)
-
- if self.print_freq:
- end = time.time()
- print('Frequency:', 1 / (end - start))
-
- return left_image, right_image
-
- def end(self):
- self.gym.destroy_viewer(self.viewer)
- self.gym.destroy_sim(self.sim)
-
-
-if __name__ == '__main__':
- # image and television
- img_shape = (720, 2560, 3)
- img_shm = shared_memory.SharedMemory(create=True, size=np.prod(img_shape) * np.uint8().itemsize)
- img_array = np.ndarray(img_shape, dtype=np.uint8, buffer=img_shm.buf)
- tv_wrapper = TeleVisionWrapper(img_shape, img_shm.name)
- # hand
- left_hand_array = Array('d', 75, lock=True)
- right_hand_array = Array('d', 75, lock=True)
- lr_hand_state_array = Array('d', 14, lock=True) # current left, right hand state data
- lr_hand_aciton_array = Array('d', 14, lock=True) # current left and right hand action data to be controlled
- hand_ctrl = Dex3_1_Controller(lr_hand_state_array, lr_hand_aciton_array)
- hand_control_process = Process(target=hand_ctrl.control_process, args=(left_hand_array, right_hand_array))
- hand_control_process.daemon = True
- hand_control_process.start()
- simulator = Sim()
-
- try:
- while True:
- user_input = input("Please enter the start signal (enter 's' to start the subsequent program):")
- if user_input.lower() == 's':
- while True:
- head_rmat, left_wrist, right_wrist, left_hand, right_hand = tv_wrapper.get_data()
- left_pose = np.concatenate([left_wrist[:3, 3] + np.array([-0.6, 0, 1.6]),
- rotations.quaternion_from_matrix(left_wrist[:3, :3])[[1, 2, 3, 0]]])
- right_pose = np.concatenate([right_wrist[:3, 3] + np.array([-0.6, 0, 1.6]),
- rotations.quaternion_from_matrix(right_wrist[:3, :3])[[1, 2, 3, 0]]])
- left_hand_array[:] = left_hand.flatten()
- right_hand_array[:] = right_hand.flatten()
- left_img, right_img = simulator.step(head_rmat, left_pose, right_pose, lr_hand_aciton_array[:7], lr_hand_aciton_array[-7:])
- np.copyto(img_array, np.hstack((left_img, right_img)))
- except KeyboardInterrupt:
- simulator.end()
- exit(0)
G1 (29自由度) + Dex3-1
✅ 完成
-
+ main分支
H1 (手臂4自由度)
@@ -40,7 +40,7 @@
H1_2 (手臂7自由度) + Inspire
✅ 完成
- 可参考该分支
+ 原h1_2分支变为陈旧分支,原g1分支重命名为main分支,main分支现已同时支持g1和h1_2
···
@@ -50,6 +50,7 @@
+
以下是需要的设备和接线示意图: