diff --git a/LICENSE b/LICENSE
index a8ff93b..899c9b1 100644
--- a/LICENSE
+++ b/LICENSE
@@ -26,5 +26,6 @@ This code builds upon following open-source code-bases. Please visit the URLs to
8) https://github.com/unitreerobotics/unitree_dds_wrapper
9) https://github.com/tonyzhaozh/act
10) https://github.com/facebookresearch/detr
+11) https://github.com/Dingry/BunnyVisionPro
------------------
diff --git a/README.md b/README.md
index 5dd493a..f81257c 100644
--- a/README.md
+++ b/README.md
@@ -1,13 +1,38 @@
-# Video Demo
+# πΊ Video Demo
-# Introduction
-This repository implements teleoperation of the humanoid robot Unitree H1_2 using Apple Vision Pro.
-
-
-
-# Prerequisites
+# 0. π Introduction
+This repository implements teleoperation of the **Unitree humanoid robot** using **Apple Vision Pro**.
+
+Here are the robots that will be supported,
+
+
+
+ 🤖 Robot
+ ⚪ Status
+
+
+ G1(29DoF) + Dex3-1
+ ✅ Completed
+
+
+ G1(23DoF)
+ ⏱ In Progress
+
+
+ H1(Arm 4DoF)
+ ⏱ In Progress
+
+
+ H1_2(Arm 7DoF) + Inspire
+ ⏱ In Progress
+
+
+
+
+
+# 1. π¦ Prerequisites
We tested our code on Ubuntu 20.04 and Ubuntu 22.04, other operating systems may be configured differently.
@@ -15,7 +40,7 @@ For more information, you can refer to [Official Documentation ](https://support
-## inverse kinematics
+## 1.1 π¦Ύ inverse kinematics
```bash
conda create -n tv python=3.8
@@ -26,7 +51,7 @@ pip install meshcat
pip install casadi
```
-## unitree_dds_wrapper
+## 1.2 πΉοΈ unitree_dds_wrapper
```bash
# Install the Python version of the unitree_dds_wrapper.
@@ -35,11 +60,13 @@ cd unitree_dds_wrapper/python
pip install -e .
```
+> p.s. This is a temporary version, and it will be replaced with [unitree_sdk2_python](https://github.com/unitreerobotics/unitree_sdk2_python) in the future.
-## TeleVision and Apple Vision Pro configuration
-### basic
+# 2. π οΈ TeleVision and Apple Vision Pro configuration
+
+## 2.1 π₯ basic
```bash
cd ~
@@ -49,13 +76,7 @@ pip install -r requirements.txt
cd act/detr && pip install -e .
```
-### Isaac Gym
-
-If you want to try teleoperation example in a simulated environment (`teleop_hand.py`):
-1. Download Isaac Gym: https://developer.nvidia.com/isaac-gym/download
-2. Extracting to the current directory, go to the `IsaacGym_Preview_4_Package/isaacgym/python` directory and execute the command: `pip install -e .`
-
-### Local streaming
+## 2.2 π Local streaming
**Apple** does not allow WebXR on non-https connections. To test the application locally, we need to create a self-signed certificate and install it on the client. You need a ubuntu machine and a router. Connect the VisionPro and the ubuntu machine to the same router.
@@ -66,7 +87,9 @@ If you want to try teleoperation example in a simulated environment (`teleop_han
ifconfig | grep inet
```
-Suppose the local ip address of the ubuntu machine is `192.168.123.2`
+Suppose the local ip address of the **Host machine** is `192.168.123.2`
+
+> p.s. you can use `ifconfig` command to check your **Host machine** ip address.
3. create certificate:
@@ -96,44 +119,70 @@ Copy the `rootCA.pem` via AirDrop to VisionPro and install it.
Settings > General > About > Certificate Trust Settings. Under "Enable full trust for root certificates", turn on trust for the certificate.
-settings > Apps > Safari > Advanced > Feature Flags > Enable WebXR Related Features
+Settings > Apps > Safari > Advanced > Feature Flags > Enable WebXR Related Features.
-6. open the browser on Safari on VisionPro and go to https://192.168.123.2:8012?ws=wss://192.168.123.2:8012
+## 2.3 π Test environment
-7. Click `Enter VR` and `Allow` to start the VR session.
+This step is to verify that the environment is installed correctly.
-### Simulation Teleoperation Example
-1. After setup up streaming with either local or network streaming following the above instructions, you can try teleoperating two robot hands in Issac Gym:
+1. Download Isaac Gym: https://developer.nvidia.com/isaac-gym/download
+
+ Extracting to the current directory, go to the `IsaacGym_Preview_4_Package/isaacgym/python` directory and execute the command:
```bash
- cd teleop && python teleop_hand.py
+ pip install -e .
```
-2. Go to your vuer site on VisionPro, click `Enter VR` and `Allow` to enter immersive environment.
+2. After setup up streaming with local following the above instructions, you can try teleoperating two robot hands in Issac Gym:
-3. See your hands in 3D!
+ ```bash
+ cd teleop
+ python teleop_test_gym.py
+ ```
+
+3. Wear your Apple Vision Pro device.
+
+4. Open Safari on Apple Vision Pro and visit: https://192.168.123.2:8012?ws=wss://192.168.123.2:8012
+
+ > p.s. This IP address should match the IP address of your **Host machine**.
+
+5. Click `Enter VR` and `Allow` to start the VR session.
+
+6. See your hands in 3D!
+# 3. π Usage
+
+Please read the [Official Documentation ](https://support.unitree.com/home/zh/Teleoperation) at least once before starting this program.
+## 3.1 πΌοΈ Image Server
-
+Copy `image_server.py` in the `avp_teleoperate/teleop/image_server` directory to the **PC2** of Unitree Robot (G1/H1/H1_2/etc.), and execute the following command **in the PC2**:
+```bash
+# Now located in Unitree Robot PC2
+python image_server.py
+# You can see the terminal output as follows:
+# Image server has started, waiting for client connections...
+# Image Resolution: width is x, height is x
+```
+After image service is started, you can use `image_client.py` **in the Host** terminal to test whether the communication is successful:
-# Usage
+```bash
+python image_client.py
+```
-Please read the [Official Documentation ](https://support.unitree.com/home/zh/Teleoperation) at least once before starting this program.
+## 3.2 β Inspire hands Server (optional)
-## Dexterous hands service
+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 PC of Unitree H1_2.
-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 and copy it to PC of Unitree H1_2. On Unitree H1_2's PC, execute command:
+On Unitree H1_2's PC, execute command:
```bash
sudo apt install libboost-all-dev libspdlog-dev
@@ -149,59 +198,82 @@ sudo ./inspire_hand -s /dev/ttyUSB0
If two hands open and close continuously, it indicates success. Once successful, close the `./h1_hand_example` program in Terminal 2.
+## 3.3 π Start
+
+> 
+>
+> 1. Everyone must keep a safe distance from the robot to prevent any potential danger!
+>
+> 2. Please make sure to read the [Official Documentation](https://support.unitree.com/home/zh/Teleoperation) at least once before running this program.
-## Image Server
+It's best to have two operators to run this program, referred to as **Operator A** and **Operator B**.
-Copy `image_server.py` in the `avp_teleoperate/teleop/image_server` directory to the PC of Unitree H1_2, and execute the following command **in the PC**:
+Now, **Operator B** execute the following command on **Host machine** :
```bash
-sudo python image_server.py
+python teleop_hand_and_arm.py
```
-After image service is started, you can use `image_client.py` **in the Host** terminal to test whether the communication is successful:
+And then, **Operator A**
-```bash
-python image_client.py
-```
+1. Wear your Apple Vision Pro device.
-## Start
+2. Open Safari on Apple Vision Pro and visit : https://192.168.123.2:8012?ws=wss://192.168.123.2:8012
-> Warning : All persons must maintain an adequate safety distance from the robot to avoid danger!
+ > p.s. This IP address should match the IP address of your **Host machine**.
-```bash
-python teleop_hand_and_arm.py
-```
+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.
+
+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.
+## 3.4 π Exit
-# Codebase Tutorial
+To exit the program, **Operator B** can press the **q** key in the 'record image' window.
-The overall structure of the code remains the same as TeleVision, and we only focus on the modified file directories related to Unitree Robot.
+> 
+>
+> To avoid damaging the robot, **Operator A** need to make sure the robot's arms are in a natural down position before exiting.
- avp_teleoperate/
- β
- βββ act [Documents Related to ACT Policy for Imitation Learning]
- β
- βββ assets [Storage of robot URDF-related files]
- β
- βββ scripts
- β
- βββ teleop
- β βββ image_server/ [Image Transfer Server and Client Code]
- β β βββ image_client.py [Client (only used to test whether the image stream service is OK, not used for teleoperation)]
- β β βββ image_server.py [Capture images from binocular cameras and send via network (performed on Unitree H1_2)]
- β β
- β βββ robot_control/ [Storage of IK solver, arm and hand control related documents]
- β β βββ robot_arm_ik.py [Inverse kinematics of the arm]
- β β βββ robot_arm.py [Control dual arm joints and lock the others]
- β β βββ robot_hand.py [Control hand joints]
- β β
- β βββteleop_hand_and_arm.py [Startup execution code for teleoperation]
- | |ββteleop_hand.py [Can be used for testing the environment configuration]
+
+
+# 4. πΊοΈ Codebase Tutorial
+
+```
+avp_teleoperate/
+β
+βββ assets [Storage of robot URDF-related files]
+β
+βββ teleop
+β βββ image_server
+β β βββ image_client.py [Used to receive image data from the robot image server]
+β β βββ image_server.py [Capture images from cameras and send via network (Running on robot's on-board computer)]
+β β
+β βββ open_television
+β β βββ television.py [Using Vuer to capture wrist and hand data from apple vision pro]
+β β βββ tv_wrapper.py [Post-processing of captured data]
+β β
+β βββ robot_control
+β β βββ robot_arm_ik.py [Inverse kinematics of the arm]
+β β βββ robot_arm.py [Control dual arm joints and lock the others]
+β β βββ robot_hand_inspire.py [Control inspire hand joints]
+β β βββ robot_hand_unitree.py [Control unitree hand joints]
+β β
+β βββ utils
+β β βββ episode_writer.py [Used to record data for imitation learning]
+β β βββ mat_tool.py [Some small math tools]
+β β βββ 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]
+```
-# Acknowledgement
+# 5. π Acknowledgement
This code builds upon following open-source code-bases. Please visit the URLs to see the respective LICENSES:
@@ -214,4 +286,5 @@ This code builds upon following open-source code-bases. Please visit the URLs to
7) https://github.com/zeromq/pyzmq
8) https://github.com/unitreerobotics/unitree_dds_wrapper
9) https://github.com/tonyzhaozh/act
-10) https://github.com/facebookresearch/detr
\ No newline at end of file
+10) https://github.com/facebookresearch/detr
+11) https://github.com/Dingry/BunnyVisionPro
\ No newline at end of file
diff --git a/act/LICENSE b/act/LICENSE
deleted file mode 100644
index 35e5f5e..0000000
--- a/act/LICENSE
+++ /dev/null
@@ -1,21 +0,0 @@
-MIT License
-
-Copyright (c) 2023 Tony Z. Zhao
-
-Permission is hereby granted, free of charge, to any person obtaining a copy
-of this software and associated documentation files (the "Software"), to deal
-in the Software without restriction, including without limitation the rights
-to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-copies of the Software, and to permit persons to whom the Software is
-furnished to do so, subject to the following conditions:
-
-The above copyright notice and this permission notice shall be included in all
-copies or substantial portions of the Software.
-
-THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
-SOFTWARE.
diff --git a/act/README.md b/act/README.md
deleted file mode 100644
index 1f58040..0000000
--- a/act/README.md
+++ /dev/null
@@ -1,8 +0,0 @@
-This part of the codebase is modified from ACT https://github.com/tonyzhaozh/act under MIT License.
-
- @article{zhao2023learning,
- title={Learning fine-grained bimanual manipulation with low-cost hardware},
- author={Zhao, Tony Z and Kumar, Vikash and Levine, Sergey and Finn, Chelsea},
- journal={arXiv preprint arXiv:2304.13705},
- year={2023}
- }
\ No newline at end of file
diff --git a/act/conda_env.yaml b/act/conda_env.yaml
deleted file mode 100644
index 0f44d6b..0000000
--- a/act/conda_env.yaml
+++ /dev/null
@@ -1,23 +0,0 @@
-name: aloha
-channels:
- - pytorch
- - nvidia
- - conda-forge
-dependencies:
- - python=3.9
- - pip=23.0.1
- - pytorch=2.0.0
- - torchvision=0.15.0
- - pytorch-cuda=11.8
- - pyquaternion=0.9.9
- - pyyaml=6.0
- - rospkg=1.5.0
- - pexpect=4.8.0
- - mujoco=2.3.3
- - dm_control=1.0.9
- - py-opencv=4.7.0
- - matplotlib=3.7.1
- - einops=0.6.0
- - packaging=23.0
- - h5py=3.8.0
- - ipython=8.12.0
diff --git a/act/detr/LICENSE b/act/detr/LICENSE
deleted file mode 100644
index b1395e9..0000000
--- a/act/detr/LICENSE
+++ /dev/null
@@ -1,201 +0,0 @@
- Apache License
- Version 2.0, January 2004
- http://www.apache.org/licenses/
-
- TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
-
- 1. Definitions.
-
- "License" shall mean the terms and conditions for use, reproduction,
- and distribution as defined by Sections 1 through 9 of this document.
-
- "Licensor" shall mean the copyright owner or entity authorized by
- the copyright owner that is granting the License.
-
- "Legal Entity" shall mean the union of the acting entity and all
- other entities that control, are controlled by, or are under common
- control with that entity. For the purposes of this definition,
- "control" means (i) the power, direct or indirect, to cause the
- direction or management of such entity, whether by contract or
- otherwise, or (ii) ownership of fifty percent (50%) or more of the
- outstanding shares, or (iii) beneficial ownership of such entity.
-
- "You" (or "Your") shall mean an individual or Legal Entity
- exercising permissions granted by this License.
-
- "Source" form shall mean the preferred form for making modifications,
- including but not limited to software source code, documentation
- source, and configuration files.
-
- "Object" form shall mean any form resulting from mechanical
- transformation or translation of a Source form, including but
- not limited to compiled object code, generated documentation,
- and conversions to other media types.
-
- "Work" shall mean the work of authorship, whether in Source or
- Object form, made available under the License, as indicated by a
- copyright notice that is included in or attached to the work
- (an example is provided in the Appendix below).
-
- "Derivative Works" shall mean any work, whether in Source or Object
- form, that is based on (or derived from) the Work and for which the
- editorial revisions, annotations, elaborations, or other modifications
- represent, as a whole, an original work of authorship. For the purposes
- of this License, Derivative Works shall not include works that remain
- separable from, or merely link (or bind by name) to the interfaces of,
- the Work and Derivative Works thereof.
-
- "Contribution" shall mean any work of authorship, including
- the original version of the Work and any modifications or additions
- to that Work or Derivative Works thereof, that is intentionally
- submitted to Licensor for inclusion in the Work by the copyright owner
- or by an individual or Legal Entity authorized to submit on behalf of
- the copyright owner. For the purposes of this definition, "submitted"
- means any form of electronic, verbal, or written communication sent
- to the Licensor or its representatives, including but not limited to
- communication on electronic mailing lists, source code control systems,
- and issue tracking systems that are managed by, or on behalf of, the
- Licensor for the purpose of discussing and improving the Work, but
- excluding communication that is conspicuously marked or otherwise
- designated in writing by the copyright owner as "Not a Contribution."
-
- "Contributor" shall mean Licensor and any individual or Legal Entity
- on behalf of whom a Contribution has been received by Licensor and
- subsequently incorporated within the Work.
-
- 2. Grant of Copyright License. Subject to the terms and conditions of
- this License, each Contributor hereby grants to You a perpetual,
- worldwide, non-exclusive, no-charge, royalty-free, irrevocable
- copyright license to reproduce, prepare Derivative Works of,
- publicly display, publicly perform, sublicense, and distribute the
- Work and such Derivative Works in Source or Object form.
-
- 3. Grant of Patent License. Subject to the terms and conditions of
- this License, each Contributor hereby grants to You a perpetual,
- worldwide, non-exclusive, no-charge, royalty-free, irrevocable
- (except as stated in this section) patent license to make, have made,
- use, offer to sell, sell, import, and otherwise transfer the Work,
- where such license applies only to those patent claims licensable
- by such Contributor that are necessarily infringed by their
- Contribution(s) alone or by combination of their Contribution(s)
- with the Work to which such Contribution(s) was submitted. If You
- institute patent litigation against any entity (including a
- cross-claim or counterclaim in a lawsuit) alleging that the Work
- or a Contribution incorporated within the Work constitutes direct
- or contributory patent infringement, then any patent licenses
- granted to You under this License for that Work shall terminate
- as of the date such litigation is filed.
-
- 4. Redistribution. You may reproduce and distribute copies of the
- Work or Derivative Works thereof in any medium, with or without
- modifications, and in Source or Object form, provided that You
- meet the following conditions:
-
- (a) You must give any other recipients of the Work or
- Derivative Works a copy of this License; and
-
- (b) You must cause any modified files to carry prominent notices
- stating that You changed the files; and
-
- (c) You must retain, in the Source form of any Derivative Works
- that You distribute, all copyright, patent, trademark, and
- attribution notices from the Source form of the Work,
- excluding those notices that do not pertain to any part of
- the Derivative Works; and
-
- (d) If the Work includes a "NOTICE" text file as part of its
- distribution, then any Derivative Works that You distribute must
- include a readable copy of the attribution notices contained
- within such NOTICE file, excluding those notices that do not
- pertain to any part of the Derivative Works, in at least one
- of the following places: within a NOTICE text file distributed
- as part of the Derivative Works; within the Source form or
- documentation, if provided along with the Derivative Works; or,
- within a display generated by the Derivative Works, if and
- wherever such third-party notices normally appear. The contents
- of the NOTICE file are for informational purposes only and
- do not modify the License. You may add Your own attribution
- notices within Derivative Works that You distribute, alongside
- or as an addendum to the NOTICE text from the Work, provided
- that such additional attribution notices cannot be construed
- as modifying the License.
-
- You may add Your own copyright statement to Your modifications and
- may provide additional or different license terms and conditions
- for use, reproduction, or distribution of Your modifications, or
- for any such Derivative Works as a whole, provided Your use,
- reproduction, and distribution of the Work otherwise complies with
- the conditions stated in this License.
-
- 5. Submission of Contributions. Unless You explicitly state otherwise,
- any Contribution intentionally submitted for inclusion in the Work
- by You to the Licensor shall be under the terms and conditions of
- this License, without any additional terms or conditions.
- Notwithstanding the above, nothing herein shall supersede or modify
- the terms of any separate license agreement you may have executed
- with Licensor regarding such Contributions.
-
- 6. Trademarks. This License does not grant permission to use the trade
- names, trademarks, service marks, or product names of the Licensor,
- except as required for reasonable and customary use in describing the
- origin of the Work and reproducing the content of the NOTICE file.
-
- 7. Disclaimer of Warranty. Unless required by applicable law or
- agreed to in writing, Licensor provides the Work (and each
- Contributor provides its Contributions) on an "AS IS" BASIS,
- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
- implied, including, without limitation, any warranties or conditions
- of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
- PARTICULAR PURPOSE. You are solely responsible for determining the
- appropriateness of using or redistributing the Work and assume any
- risks associated with Your exercise of permissions under this License.
-
- 8. Limitation of Liability. In no event and under no legal theory,
- whether in tort (including negligence), contract, or otherwise,
- unless required by applicable law (such as deliberate and grossly
- negligent acts) or agreed to in writing, shall any Contributor be
- liable to You for damages, including any direct, indirect, special,
- incidental, or consequential damages of any character arising as a
- result of this License or out of the use or inability to use the
- Work (including but not limited to damages for loss of goodwill,
- work stoppage, computer failure or malfunction, or any and all
- other commercial damages or losses), even if such Contributor
- has been advised of the possibility of such damages.
-
- 9. Accepting Warranty or Additional Liability. While redistributing
- the Work or Derivative Works thereof, You may choose to offer,
- and charge a fee for, acceptance of support, warranty, indemnity,
- or other liability obligations and/or rights consistent with this
- License. However, in accepting such obligations, You may act only
- on Your own behalf and on Your sole responsibility, not on behalf
- of any other Contributor, and only if You agree to indemnify,
- defend, and hold each Contributor harmless for any liability
- incurred by, or claims asserted against, such Contributor by reason
- of your accepting any such warranty or additional liability.
-
- END OF TERMS AND CONDITIONS
-
- APPENDIX: How to apply the Apache License to your work.
-
- To apply the Apache License to your work, attach the following
- boilerplate notice, with the fields enclosed by brackets "[]"
- replaced with your own identifying information. (Don't include
- the brackets!) The text should be enclosed in the appropriate
- comment syntax for the file format. We also recommend that a
- file or class name and description of purpose be included on the
- same "printed page" as the copyright notice for easier
- identification within third-party archives.
-
- Copyright 2020 - present, Facebook, Inc
-
- Licensed under the Apache License, Version 2.0 (the "License");
- you may not use this file except in compliance with the License.
- You may obtain a copy of the License at
-
- http://www.apache.org/licenses/LICENSE-2.0
-
- Unless required by applicable law or agreed to in writing, software
- distributed under the License is distributed on an "AS IS" BASIS,
- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- See the License for the specific language governing permissions and
- limitations under the License.
diff --git a/act/detr/README.md b/act/detr/README.md
deleted file mode 100644
index 500b1b8..0000000
--- a/act/detr/README.md
+++ /dev/null
@@ -1,9 +0,0 @@
-This part of the codebase is modified from DETR https://github.com/facebookresearch/detr under APACHE 2.0.
-
- @article{Carion2020EndtoEndOD,
- title={End-to-End Object Detection with Transformers},
- author={Nicolas Carion and Francisco Massa and Gabriel Synnaeve and Nicolas Usunier and Alexander Kirillov and Sergey Zagoruyko},
- journal={ArXiv},
- year={2020},
- volume={abs/2005.12872}
- }
\ No newline at end of file
diff --git a/act/detr/main.py b/act/detr/main.py
deleted file mode 100644
index ca17adf..0000000
--- a/act/detr/main.py
+++ /dev/null
@@ -1,128 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-import argparse
-from pathlib import Path
-
-import numpy as np
-import torch
-from .models import build_ACT_model, build_CNNMLP_model
-
-import IPython
-e = IPython.embed
-
-def get_args_parser():
- parser = argparse.ArgumentParser('Set transformer detector', add_help=False)
- parser.add_argument('--lr', default=1e-4, type=float) # will be overridden
- parser.add_argument('--lr_backbone', default=1e-5, type=float) # will be overridden
- parser.add_argument('--batch_size', default=2, type=int) # not used
- parser.add_argument('--weight_decay', default=1e-4, type=float)
- parser.add_argument('--epochs', default=300, type=int) # not used
- parser.add_argument('--lr_drop', default=200, type=int) # not used
- parser.add_argument('--clip_max_norm', default=0.1, type=float, # not used
- help='gradient clipping max norm')
- parser.add_argument('--qpos_noise_std', action='store', default=0, type=float, help='lr', required=False)
-
-
- # Model parameters
- # * Backbone
- parser.add_argument('--backbone', default='resnet18', type=str, # will be overridden
- help="Name of the convolutional backbone to use")
- parser.add_argument('--dilation', action='store_true',
- help="If true, we replace stride with dilation in the last convolutional block (DC5)")
- parser.add_argument('--position_embedding', default='sine', type=str, choices=('sine', 'learned'),
- help="Type of positional embedding to use on top of the image features")
- parser.add_argument('--camera_names', default=[], type=list, # will be overridden
- help="A list of camera names")
-
- # * Transformer
- parser.add_argument('--enc_layers', default=4, type=int, # will be overridden
- help="Number of encoding layers in the transformer")
- parser.add_argument('--dec_layers', default=6, type=int, # will be overridden
- help="Number of decoding layers in the transformer")
- parser.add_argument('--dim_feedforward', default=2048, type=int, # will be overridden
- help="Intermediate size of the feedforward layers in the transformer blocks")
- parser.add_argument('--hidden_dim', default=256, type=int, # will be overridden
- help="Size of the embeddings (dimension of the transformer)")
- parser.add_argument('--dropout', default=0.1, type=float,
- help="Dropout applied in the transformer")
- parser.add_argument('--nheads', default=8, type=int, # will be overridden
- help="Number of attention heads inside the transformer's attentions")
- parser.add_argument('--num_queries', default=400, type=int, # will be overridden
- help="Number of query slots")
- parser.add_argument('--pre_norm', action='store_true')
-
- # * Segmentation
- parser.add_argument('--masks', action='store_true',
- help="Train segmentation head if the flag is provided")
-
- # repeat args in imitate_episodes just to avoid error. Will not be used
- parser.add_argument('--eval', action='store_true')
- parser.add_argument('--onscreen_render', action='store_true')
- # parser.add_argument('--ckpt_dir', action='store', type=str, help='ckpt_dir', required=True)
- parser.add_argument('--policy_class', action='store', type=str, help='policy_class, capitalize', required=True)
- # parser.add_argument('--task_name', action='store', type=str, help='task_name', required=True)
- parser.add_argument('--seed', action='store', type=int, help='seed', required=True)
- parser.add_argument('--num_epochs', action='store', type=int, help='num_epochs', required=True)
- parser.add_argument('--kl_weight', action='store', type=int, help='KL Weight', required=False)
- parser.add_argument('--chunk_size', action='store', type=int, help='chunk_size', required=False)
- parser.add_argument('--temporal_agg', action='store_true')
-
- parser.add_argument('--save_jit', action='store_true')
- parser.add_argument('--ckpt_dir', default='/home/cxx/h1_hardware/data/logs', type=str, # will be overridden
- help='ckpt_dir')
-
- parser.add_argument('--no_wandb', action='store_true')
- parser.add_argument('--resumeid', action='store', type=str, help='resume id', required=False)
- parser.add_argument('--resume_ckpt', action='store', type=str, help='resume ckpt', required=False)
- parser.add_argument('--taskid', action='store', type=str, help='task id', required=True)
- parser.add_argument('--exptid', action='store', type=str, help='experiment id', required=True)
- parser.add_argument('--source', choices=['self', 'ssd'], default='self')
-
-
- return parser
-
-
-def build_ACT_model_and_optimizer(args_override):
- parser = argparse.ArgumentParser('DETR training and evaluation script', parents=[get_args_parser()])
- args = parser.parse_args()
-
- for k, v in args_override.items():
- setattr(args, k, v)
-
- model = build_ACT_model(args)
- model.cuda()
-
- param_dicts = [
- {"params": [p for n, p in model.named_parameters() if "backbone" not in n and p.requires_grad]},
- {
- "params": [p for n, p in model.named_parameters() if "backbone" in n and p.requires_grad],
- "lr": args.lr_backbone,
- },
- ]
- optimizer = torch.optim.AdamW(param_dicts, lr=args.lr,
- weight_decay=args.weight_decay)
-
- return model, optimizer
-
-
-def build_CNNMLP_model_and_optimizer(args_override):
- parser = argparse.ArgumentParser('DETR training and evaluation script', parents=[get_args_parser()])
- args = parser.parse_args()
-
- for k, v in args_override.items():
- setattr(args, k, v)
-
- model = build_CNNMLP_model(args)
- model.cuda()
-
- param_dicts = [
- {"params": [p for n, p in model.named_parameters() if "backbone" not in n and p.requires_grad]},
- {
- "params": [p for n, p in model.named_parameters() if "backbone" in n and p.requires_grad],
- "lr": args.lr_backbone,
- },
- ]
- optimizer = torch.optim.AdamW(param_dicts, lr=args.lr,
- weight_decay=args.weight_decay)
-
- return model, optimizer
-
diff --git a/act/detr/models/__init__.py b/act/detr/models/__init__.py
deleted file mode 100644
index cc78db1..0000000
--- a/act/detr/models/__init__.py
+++ /dev/null
@@ -1,9 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-from .detr_vae import build as build_vae
-from .detr_vae import build_cnnmlp as build_cnnmlp
-
-def build_ACT_model(args):
- return build_vae(args)
-
-def build_CNNMLP_model(args):
- return build_cnnmlp(args)
\ No newline at end of file
diff --git a/act/detr/models/backbone.py b/act/detr/models/backbone.py
deleted file mode 100644
index 1ded145..0000000
--- a/act/detr/models/backbone.py
+++ /dev/null
@@ -1,144 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-"""
-Backbone modules.
-"""
-from collections import OrderedDict
-
-import torch
-import torch.nn.functional as F
-import torchvision
-from torch import nn
-from torchvision.models._utils import IntermediateLayerGetter
-from typing import Dict, List
-
-from util.misc import NestedTensor, is_main_process
-
-from .position_encoding import build_position_encoding
-
-import IPython
-e = IPython.embed
-
-class FrozenBatchNorm2d(torch.nn.Module):
- """
- BatchNorm2d where the batch statistics and the affine parameters are fixed.
-
- Copy-paste from torchvision.misc.ops with added eps before rqsrt,
- without which any other policy_models than torchvision.policy_models.resnet[18,34,50,101]
- produce nans.
- """
-
- def __init__(self, n):
- super(FrozenBatchNorm2d, self).__init__()
- self.register_buffer("weight", torch.ones(n))
- self.register_buffer("bias", torch.zeros(n))
- self.register_buffer("running_mean", torch.zeros(n))
- self.register_buffer("running_var", torch.ones(n))
-
- def _load_from_state_dict(self, state_dict, prefix, local_metadata, strict,
- missing_keys, unexpected_keys, error_msgs):
- num_batches_tracked_key = prefix + 'num_batches_tracked'
- if num_batches_tracked_key in state_dict:
- del state_dict[num_batches_tracked_key]
-
- super(FrozenBatchNorm2d, self)._load_from_state_dict(
- state_dict, prefix, local_metadata, strict,
- missing_keys, unexpected_keys, error_msgs)
-
- def forward(self, x):
- # move reshapes to the beginning
- # to make it fuser-friendly
- w = self.weight.reshape(1, -1, 1, 1)
- b = self.bias.reshape(1, -1, 1, 1)
- rv = self.running_var.reshape(1, -1, 1, 1)
- rm = self.running_mean.reshape(1, -1, 1, 1)
- eps = 1e-5
- scale = w * (rv + eps).rsqrt()
- bias = b - rm * scale
- return x * scale + bias
-
-
-class BackboneBase(nn.Module):
-
- def __init__(self, backbone: nn.Module, train_backbone: bool, num_channels: int, return_interm_layers: bool):
- super().__init__()
- # for name, parameter in backbone.named_parameters(): # only train later layers # TODO do we want this?
- # if not train_backbone or 'layer2' not in name and 'layer3' not in name and 'layer4' not in name:
- # parameter.requires_grad_(False)
- if return_interm_layers:
- return_layers = {"layer1": "0", "layer2": "1", "layer3": "2", "layer4": "3"}
- else:
- return_layers = {'layer4': "0"}
- self.body = IntermediateLayerGetter(backbone, return_layers=return_layers)
- self.num_channels = num_channels
-
- def forward(self, tensor):
- xs = self.body(tensor)
- return xs
- # out: Dict[str, NestedTensor] = {}
- # for name, x in xs.items():
- # m = tensor_list.mask
- # assert m is not None
- # mask = F.interpolate(m[None].float(), size=x.shape[-2:]).to(torch.bool)[0]
- # out[name] = NestedTensor(x, mask)
- # return out
-
-
-class Backbone(BackboneBase):
- """ResNet backbone with frozen BatchNorm."""
- def __init__(self, name: str,
- train_backbone: bool,
- return_interm_layers: bool,
- dilation: bool):
- backbone = getattr(torchvision.models, name)(
- replace_stride_with_dilation=[False, False, dilation],
- pretrained=is_main_process(), norm_layer=FrozenBatchNorm2d) # pretrained # TODO do we want frozen batch_norm??
- num_channels = 512 if name in ('resnet18', 'resnet34') else 2048
- super().__init__(backbone, train_backbone, num_channels, return_interm_layers)
-
-class DINOv2BackBone(nn.Module):
- def __init__(self) -> None:
- super().__init__()
- self.body = torch.hub.load('facebookresearch/dinov2', 'dinov2_vits14')
- self.body.eval()
- self.num_channels = 384
-
- @torch.no_grad()
- def forward(self, tensor):
- xs = self.body.forward_features(tensor)["x_norm_patchtokens"]
- od = OrderedDict()
- od["0"] = xs.reshape(xs.shape[0], 22, 16, 384).permute(0, 3, 2, 1)
- return od
-
-class Joiner(nn.Sequential):
- def __init__(self, backbone, position_embedding):
- super().__init__(backbone, position_embedding)
-
- # def forward (self, tensor):
- # xs = self[0](tensor)
- # pos = self[1](xs)
- # return xs, pos
-
- def forward(self, tensor_list: NestedTensor):
- xs = self[0](tensor_list)
- out: List[NestedTensor] = []
- pos = []
- for name, x in xs.items():
- out.append(x)
- # position encoding
- pos.append(self[1](x).to(x.dtype))
-
- return out, pos
-
-
-def build_backbone(args):
- position_embedding = build_position_encoding(args)
- train_backbone = args.lr_backbone > 0
- return_interm_layers = args.masks
- if args.backbone == 'dino_v2':
- backbone = DINOv2BackBone()
- else:
- assert args.backbone in ['resnet18', 'resnet34']
- backbone = Backbone(args.backbone, train_backbone, return_interm_layers, args.dilation)
- model = Joiner(backbone, position_embedding)
- model.num_channels = backbone.num_channels
- return model
diff --git a/act/detr/models/detr_vae.py b/act/detr/models/detr_vae.py
deleted file mode 100644
index b3b3ee0..0000000
--- a/act/detr/models/detr_vae.py
+++ /dev/null
@@ -1,302 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-"""
-DETR model and criterion classes.
-"""
-import torch
-from torch import nn
-from torch.autograd import Variable
-from .backbone import build_backbone
-from .transformer import build_transformer, TransformerEncoder, TransformerEncoderLayer
-
-import numpy as np
-import time
-
-import IPython
-e = IPython.embed
-
-
-def reparametrize(mu, logvar):
- std = logvar.div(2).exp()
- eps = Variable(std.data.new(std.size()).normal_())
- return mu + std * eps
-
-
-def get_sinusoid_encoding_table(n_position, d_hid):
- def get_position_angle_vec(position):
- return [position / np.power(10000, 2 * (hid_j // 2) / d_hid) for hid_j in range(d_hid)]
-
- sinusoid_table = np.array([get_position_angle_vec(pos_i) for pos_i in range(n_position)])
- sinusoid_table[:, 0::2] = np.sin(sinusoid_table[:, 0::2]) # dim 2i
- sinusoid_table[:, 1::2] = np.cos(sinusoid_table[:, 1::2]) # dim 2i+1
-
- return torch.FloatTensor(sinusoid_table).unsqueeze(0)
-
-
-class DETRVAE(nn.Module):
- """ This is the DETR module that performs object detection """
- def __init__(self, backbones, transformer, encoder, state_dim, action_dim, num_queries, camera_names):
- """ Initializes the model.
- Parameters:
- backbones: torch module of the backbone to be used. See backbone.py
- transformer: torch module of the transformer architecture. See transformer.py
- state_dim: robot state dimension of the environment
- num_queries: number of object queries, ie detection slot. This is the maximal number of objects
- DETR can detect in a single image. For COCO, we recommend 100 queries.
- aux_loss: True if auxiliary decoding losses (loss at each decoder layer) are to be used.
- """
- super().__init__()
- self.num_queries = num_queries
- self.camera_names = camera_names
- self.transformer = transformer
- self.encoder = encoder
- hidden_dim = transformer.d_model
- self.action_head = nn.Linear(hidden_dim, action_dim)
- self.is_pad_head = nn.Linear(hidden_dim, 1)
- self.query_embed = nn.Embedding(num_queries, hidden_dim)
- if backbones is not None:
- self.input_proj = nn.Conv2d(backbones[0].num_channels, hidden_dim, kernel_size=1)
- self.backbones = nn.ModuleList(backbones)
- self.input_proj_robot_state = nn.Linear(state_dim, hidden_dim)
- else:
- raise NotImplementedError
- # input_dim = 14 + 7 # robot_state + env_state
- self.input_proj_robot_state = nn.Linear(state_dim, hidden_dim)
- self.input_proj_env_state = nn.Linear(7, hidden_dim)
- self.pos = torch.nn.Embedding(2, hidden_dim)
- self.backbones = None
-
- # encoder extra parameters
- self.latent_dim = 32 # final size of latent z # TODO tune
- self.cls_embed = nn.Embedding(1, hidden_dim) # extra cls token embedding
- self.encoder_action_proj = nn.Linear(action_dim, hidden_dim) # project action to embedding
- self.encoder_joint_proj = nn.Linear(state_dim, hidden_dim) # project qpos to embedding
- self.latent_proj = nn.Linear(hidden_dim, self.latent_dim*2) # project hidden state to latent std, var
- self.register_buffer('pos_table', get_sinusoid_encoding_table(1+1+num_queries, hidden_dim)) # [CLS], qpos, a_seq
-
- # decoder extra parameters
- self.latent_out_proj = nn.Linear(self.latent_dim, hidden_dim) # project latent sample to embedding
- self.additional_pos_embed = nn.Embedding(2, hidden_dim) # learned position embedding for proprio and latent
-
- def forward(self, qpos, image, env_state, actions=None, is_pad=None):
- """
- qpos: batch, qpos_dim
- image: batch, num_cam, channel, height, width
- env_state: None
- actions: batch, seq, action_dim
- """
- is_training = actions is not None # train or val
- bs, _ = qpos.shape
- ### Obtain latent z from action sequence
- if is_training:
- # project action sequence to embedding dim, and concat with a CLS token
- action_embed = self.encoder_action_proj(actions) # (bs, seq, hidden_dim)
- qpos_embed = self.encoder_joint_proj(qpos) # (bs, hidden_dim)
- qpos_embed = torch.unsqueeze(qpos_embed, axis=1) # (bs, 1, hidden_dim)
- cls_embed = self.cls_embed.weight # (1, hidden_dim)
- cls_embed = torch.unsqueeze(cls_embed, axis=0).repeat(bs, 1, 1) # (bs, 1, hidden_dim)
- encoder_input = torch.cat([cls_embed, qpos_embed, action_embed], axis=1) # (bs, seq+1, hidden_dim)
- encoder_input = encoder_input.permute(1, 0, 2) # (seq+1, bs, hidden_dim)
- # do not mask cls token
- cls_joint_is_pad = torch.full((bs, 2), False).to(qpos.device) # False: not a padding
- is_pad = torch.cat([cls_joint_is_pad, is_pad], axis=1) # (bs, seq+1)
- # obtain position embedding
- pos_embed = self.pos_table.clone().detach()
- pos_embed = pos_embed.permute(1, 0, 2) # (seq+1, 1, hidden_dim)
- # query model
- encoder_output = self.encoder(encoder_input, pos=pos_embed, src_key_padding_mask=is_pad)
- encoder_output = encoder_output[0] # take cls output only
- latent_info = self.latent_proj(encoder_output)
- mu = latent_info[:, :self.latent_dim]
- logvar = latent_info[:, self.latent_dim:]
- latent_sample = reparametrize(mu, logvar)
- latent_input = self.latent_out_proj(latent_sample)
- else:
- mu = logvar = None
- latent_sample = torch.zeros([bs, self.latent_dim], dtype=torch.float32).to(qpos.device)
- latent_input = self.latent_out_proj(latent_sample)
-
- if self.backbones is not None:
- # Image observation features and position embeddings
- all_cam_features = []
- all_cam_pos = []
- featuress, poss = self.backbones[0](image.flatten(0, 1)) # HARDCODED
- featuress = featuress[0].view(image.shape[0], 2, 384, 16, 22) # take the last layer feature
- pos = poss[0]
- for cam_id, cam_name in enumerate(self.camera_names):
- # start = time.time()
- # import ipdb; ipdb.set_trace()
- features = featuress[:, cam_id] # HARDCODED
- # features, pos = self.backbones[cam_id](image[:, cam_id]) # HARDCODED
- # print("Time for 1 backbone: ", time.time() - start, image.shape)
- # features = features[0] # take the last layer feature
- # pos = pos[0]
- all_cam_features.append(self.input_proj(features))
- all_cam_pos.append(pos/2+ cam_id - 0.5)
- # break
-
- # for cam_id, cam_name in enumerate(self.camera_names):
- # features, pos = self.backbones[0](image[:, cam_id]) # HARDCODED
- # features = features[0] # take the last layer feature
- # pos = pos[0]
- # all_cam_features.append(self.input_proj(features))
- # all_cam_pos.append(pos)
-
- # proprioception features
- proprio_input = self.input_proj_robot_state(qpos)
- # fold camera dimension into width dimension
- src = torch.cat(all_cam_features, axis=3)
- pos = torch.cat(all_cam_pos, axis=3)
- hs = self.transformer(src, None, self.query_embed.weight, pos, latent_input, proprio_input, self.additional_pos_embed.weight)[0]
- else:
- raise NotImplementedError
- qpos = self.input_proj_robot_state(qpos)
- env_state = self.input_proj_env_state(env_state)
- transformer_input = torch.cat([qpos, env_state], axis=1) # seq length = 2
- hs = self.transformer(transformer_input, None, self.query_embed.weight, self.pos.weight)[0]
- a_hat = self.action_head(hs)
- is_pad_hat = self.is_pad_head(hs)
- return a_hat, is_pad_hat, [mu, logvar]
-
-
-
-class CNNMLP(nn.Module):
- def __init__(self, backbones, state_dim, camera_names):
- """ Initializes the model.
- Parameters:
- backbones: torch module of the backbone to be used. See backbone.py
- transformer: torch module of the transformer architecture. See transformer.py
- state_dim: robot state dimension of the environment
- num_queries: number of object queries, ie detection slot. This is the maximal number of objects
- DETR can detect in a single image. For COCO, we recommend 100 queries.
- aux_loss: True if auxiliary decoding losses (loss at each decoder layer) are to be used.
- """
- super().__init__()
- self.camera_names = camera_names
- self.action_head = nn.Linear(1000, state_dim) # TODO add more
- if backbones is not None:
- self.backbones = nn.ModuleList(backbones)
- backbone_down_projs = []
- for backbone in backbones:
- down_proj = nn.Sequential(
- nn.Conv2d(backbone.num_channels, 128, kernel_size=5),
- nn.Conv2d(128, 64, kernel_size=5),
- nn.Conv2d(64, 32, kernel_size=5)
- )
- backbone_down_projs.append(down_proj)
- self.backbone_down_projs = nn.ModuleList(backbone_down_projs)
-
- mlp_in_dim = 768 * len(backbones) + 14
- self.mlp = mlp(input_dim=mlp_in_dim, hidden_dim=1024, output_dim=14, hidden_depth=2)
- else:
- raise NotImplementedError
-
- def forward(self, qpos, image, env_state, actions=None):
- """
- qpos: batch, qpos_dim
- image: batch, num_cam, channel, height, width
- env_state: None
- actions: batch, seq, action_dim
- """
- is_training = actions is not None # train or val
- bs, _ = qpos.shape
- # Image observation features and position embeddings
- all_cam_features = []
- for cam_id, cam_name in enumerate(self.camera_names):
- features, pos = self.backbones[cam_id](image[:, cam_id])
- features = features[0] # take the last layer feature
- pos = pos[0] # not used
- all_cam_features.append(self.backbone_down_projs[cam_id](features))
- # flatten everything
- flattened_features = []
- for cam_feature in all_cam_features:
- flattened_features.append(cam_feature.reshape([bs, -1]))
- flattened_features = torch.cat(flattened_features, axis=1) # 768 each
- features = torch.cat([flattened_features, qpos], axis=1) # qpos: 14
- a_hat = self.mlp(features)
- return a_hat
-
-
-def mlp(input_dim, hidden_dim, output_dim, hidden_depth):
- if hidden_depth == 0:
- mods = [nn.Linear(input_dim, output_dim)]
- else:
- mods = [nn.Linear(input_dim, hidden_dim), nn.ReLU(inplace=True)]
- for i in range(hidden_depth - 1):
- mods += [nn.Linear(hidden_dim, hidden_dim), nn.ReLU(inplace=True)]
- mods.append(nn.Linear(hidden_dim, output_dim))
- trunk = nn.Sequential(*mods)
- return trunk
-
-
-def build_encoder(args):
- d_model = args.hidden_dim # 256
- dropout = args.dropout # 0.1
- nhead = args.nheads # 8
- dim_feedforward = args.dim_feedforward # 2048
- num_encoder_layers = args.enc_layers # 4 # TODO shared with VAE decoder
- normalize_before = args.pre_norm # False
- activation = "relu"
-
- encoder_layer = TransformerEncoderLayer(d_model, nhead, dim_feedforward,
- dropout, activation, normalize_before)
- encoder_norm = nn.LayerNorm(d_model) if normalize_before else None
- encoder = TransformerEncoder(encoder_layer, num_encoder_layers, encoder_norm)
-
- return encoder
-
-
-def build(args):
- state_dim = args.state_dim
- action_dim = args.action_dim
-
- # From state
- # backbone = None # from state for now, no need for conv nets
- # From image
- backbones = []
- # backbone = build_backbone(args)
- # backbones.append(backbone)
- # for _ in args.camera_names:
- backbone = build_backbone(args)
- backbones.append(backbone)
-
- transformer = build_transformer(args)
-
- encoder = build_encoder(args)
-
- model = DETRVAE(
- backbones,
- transformer,
- encoder,
- state_dim=state_dim,
- action_dim=action_dim,
- num_queries=args.num_queries,
- camera_names=args.camera_names,
- )
-
- n_parameters = sum(p.numel() for p in model.parameters() if p.requires_grad)
- print("number of parameters: %.2fM" % (n_parameters/1e6,))
-
- return model
-
-def build_cnnmlp(args):
- state_dim = 14 # TODO hardcode
-
- # From state
- # backbone = None # from state for now, no need for conv nets
- # From image
- backbones = []
- for _ in args.camera_names:
- backbone = build_backbone(args)
- backbones.append(backbone)
-
- model = CNNMLP(
- backbones,
- state_dim=state_dim,
- camera_names=args.camera_names,
- )
-
- n_parameters = sum(p.numel() for p in model.parameters() if p.requires_grad)
- print("number of parameters: %.2fM" % (n_parameters/1e6,))
-
- return model
-
diff --git a/act/detr/models/position_encoding.py b/act/detr/models/position_encoding.py
deleted file mode 100644
index 209d917..0000000
--- a/act/detr/models/position_encoding.py
+++ /dev/null
@@ -1,93 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-"""
-Various positional encodings for the transformer.
-"""
-import math
-import torch
-from torch import nn
-
-from util.misc import NestedTensor
-
-import IPython
-e = IPython.embed
-
-class PositionEmbeddingSine(nn.Module):
- """
- This is a more standard version of the position embedding, very similar to the one
- used by the Attention is all you need paper, generalized to work on images.
- """
- def __init__(self, num_pos_feats=64, temperature=10000, normalize=False, scale=None):
- super().__init__()
- self.num_pos_feats = num_pos_feats
- self.temperature = temperature
- self.normalize = normalize
- if scale is not None and normalize is False:
- raise ValueError("normalize should be True if scale is passed")
- if scale is None:
- scale = 2 * math.pi
- self.scale = scale
-
- def forward(self, tensor):
- x = tensor
- # mask = tensor_list.mask
- # assert mask is not None
- # not_mask = ~mask
-
- not_mask = torch.ones_like(x[0, [0]])
- y_embed = not_mask.cumsum(1, dtype=torch.float32)
- x_embed = not_mask.cumsum(2, dtype=torch.float32)
- if self.normalize:
- eps = 1e-6
- y_embed = y_embed / (y_embed[:, -1:, :] + eps) * self.scale
- x_embed = x_embed / (x_embed[:, :, -1:] + eps) * self.scale
-
- dim_t = torch.arange(self.num_pos_feats, dtype=torch.float32, device=x.device)
- dim_t = self.temperature ** (2 * (dim_t // 2) / self.num_pos_feats)
-
- pos_x = x_embed[:, :, :, None] / dim_t
- pos_y = y_embed[:, :, :, None] / dim_t
- pos_x = torch.stack((pos_x[:, :, :, 0::2].sin(), pos_x[:, :, :, 1::2].cos()), dim=4).flatten(3)
- pos_y = torch.stack((pos_y[:, :, :, 0::2].sin(), pos_y[:, :, :, 1::2].cos()), dim=4).flatten(3)
- pos = torch.cat((pos_y, pos_x), dim=3).permute(0, 3, 1, 2)
- return pos
-
-
-class PositionEmbeddingLearned(nn.Module):
- """
- Absolute pos embedding, learned.
- """
- def __init__(self, num_pos_feats=256):
- super().__init__()
- self.row_embed = nn.Embedding(50, num_pos_feats)
- self.col_embed = nn.Embedding(50, num_pos_feats)
- self.reset_parameters()
-
- def reset_parameters(self):
- nn.init.uniform_(self.row_embed.weight)
- nn.init.uniform_(self.col_embed.weight)
-
- def forward(self, tensor_list: NestedTensor):
- x = tensor_list.tensors
- h, w = x.shape[-2:]
- i = torch.arange(w, device=x.device)
- j = torch.arange(h, device=x.device)
- x_emb = self.col_embed(i)
- y_emb = self.row_embed(j)
- pos = torch.cat([
- x_emb.unsqueeze(0).repeat(h, 1, 1),
- y_emb.unsqueeze(1).repeat(1, w, 1),
- ], dim=-1).permute(2, 0, 1).unsqueeze(0).repeat(x.shape[0], 1, 1, 1)
- return pos
-
-
-def build_position_encoding(args):
- N_steps = args.hidden_dim // 2
- if args.position_embedding in ('v2', 'sine'):
- # TODO find a better way of exposing other arguments
- position_embedding = PositionEmbeddingSine(N_steps, normalize=True)
- elif args.position_embedding in ('v3', 'learned'):
- position_embedding = PositionEmbeddingLearned(N_steps)
- else:
- raise ValueError(f"not supported {args.position_embedding}")
-
- return position_embedding
diff --git a/act/detr/models/transformer.py b/act/detr/models/transformer.py
deleted file mode 100644
index f38afd0..0000000
--- a/act/detr/models/transformer.py
+++ /dev/null
@@ -1,314 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-"""
-DETR Transformer class.
-
-Copy-paste from torch.nn.Transformer with modifications:
- * positional encodings are passed in MHattention
- * extra LN at the end of encoder is removed
- * decoder returns a stack of activations from all decoding layers
-"""
-import copy
-from typing import Optional, List
-
-import torch
-import torch.nn.functional as F
-from torch import nn, Tensor
-
-import IPython
-e = IPython.embed
-
-class Transformer(nn.Module):
-
- def __init__(self, d_model=512, nhead=8, num_encoder_layers=6,
- num_decoder_layers=6, dim_feedforward=2048, dropout=0.1,
- activation="relu", normalize_before=False,
- return_intermediate_dec=False):
- super().__init__()
-
- encoder_layer = TransformerEncoderLayer(d_model, nhead, dim_feedforward,
- dropout, activation, normalize_before)
- encoder_norm = nn.LayerNorm(d_model) if normalize_before else None
- self.encoder = TransformerEncoder(encoder_layer, num_encoder_layers, encoder_norm)
-
- decoder_layer = TransformerDecoderLayer(d_model, nhead, dim_feedforward,
- dropout, activation, normalize_before)
- decoder_norm = nn.LayerNorm(d_model)
- self.decoder = TransformerDecoder(decoder_layer, num_decoder_layers, decoder_norm,
- return_intermediate=return_intermediate_dec)
-
- self._reset_parameters()
-
- self.d_model = d_model
- self.nhead = nhead
-
- def _reset_parameters(self):
- for p in self.parameters():
- if p.dim() > 1:
- nn.init.xavier_uniform_(p)
-
- def forward(self, src, mask, query_embed, pos_embed, latent_input=None, proprio_input=None, additional_pos_embed=None):
- # TODO flatten only when input has H and W
- if len(src.shape) == 4: # has H and W
- # flatten NxCxHxW to HWxNxC
- bs, c, h, w = src.shape
- src = src.flatten(2).permute(2, 0, 1)
- pos_embed = pos_embed.flatten(2).permute(2, 0, 1).repeat(1, bs, 1)
- query_embed = query_embed.unsqueeze(1).repeat(1, bs, 1)
- # mask = mask.flatten(1)
-
- additional_pos_embed = additional_pos_embed.unsqueeze(1).repeat(1, bs, 1) # seq, bs, dim
- pos_embed = torch.cat([additional_pos_embed, pos_embed], axis=0)
-
- addition_input = torch.stack([latent_input, proprio_input], axis=0)
- src = torch.cat([addition_input, src], axis=0)
- else:
- assert len(src.shape) == 3
- # flatten NxHWxC to HWxNxC
- bs, hw, c = src.shape
- src = src.permute(1, 0, 2)
- pos_embed = pos_embed.unsqueeze(1).repeat(1, bs, 1)
- query_embed = query_embed.unsqueeze(1).repeat(1, bs, 1)
-
- tgt = torch.zeros_like(query_embed)
- memory = self.encoder(src, src_key_padding_mask=mask, pos=pos_embed)
- hs = self.decoder(tgt, memory, memory_key_padding_mask=mask,
- pos=pos_embed, query_pos=query_embed)
- hs = hs.transpose(1, 2)
- return hs
-
-class TransformerEncoder(nn.Module):
-
- def __init__(self, encoder_layer, num_layers, norm=None):
- super().__init__()
- self.layers = _get_clones(encoder_layer, num_layers)
- self.num_layers = num_layers
- self.norm = norm
-
- def forward(self, src,
- mask: Optional[Tensor] = None,
- src_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None):
- output = src
-
- for layer in self.layers:
- output = layer(output, src_mask=mask,
- src_key_padding_mask=src_key_padding_mask, pos=pos)
-
- if self.norm is not None:
- output = self.norm(output)
-
- return output
-
-
-class TransformerDecoder(nn.Module):
-
- def __init__(self, decoder_layer, num_layers, norm=None, return_intermediate=False):
- super().__init__()
- self.layers = _get_clones(decoder_layer, num_layers)
- self.num_layers = num_layers
- self.norm = norm
- self.return_intermediate = return_intermediate
-
- def forward(self, tgt, memory,
- tgt_mask: Optional[Tensor] = None,
- memory_mask: Optional[Tensor] = None,
- tgt_key_padding_mask: Optional[Tensor] = None,
- memory_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None,
- query_pos: Optional[Tensor] = None):
- output = tgt
-
- intermediate = []
-
- for layer in self.layers:
- output = layer(output, memory, tgt_mask=tgt_mask,
- memory_mask=memory_mask,
- tgt_key_padding_mask=tgt_key_padding_mask,
- memory_key_padding_mask=memory_key_padding_mask,
- pos=pos, query_pos=query_pos)
- if self.return_intermediate:
- intermediate.append(self.norm(output))
-
- if self.norm is not None:
- output = self.norm(output)
- if self.return_intermediate:
- intermediate.pop()
- intermediate.append(output)
-
- if self.return_intermediate:
- return torch.stack(intermediate)
-
- return output.unsqueeze(0)
-
-
-class TransformerEncoderLayer(nn.Module):
-
- def __init__(self, d_model, nhead, dim_feedforward=2048, dropout=0.1,
- activation="relu", normalize_before=False):
- super().__init__()
- self.self_attn = nn.MultiheadAttention(d_model, nhead, dropout=dropout)
- # Implementation of Feedforward model
- self.linear1 = nn.Linear(d_model, dim_feedforward)
- self.dropout = nn.Dropout(dropout)
- self.linear2 = nn.Linear(dim_feedforward, d_model)
-
- self.norm1 = nn.LayerNorm(d_model)
- self.norm2 = nn.LayerNorm(d_model)
- self.dropout1 = nn.Dropout(dropout)
- self.dropout2 = nn.Dropout(dropout)
-
- self.activation = _get_activation_fn(activation)
- self.normalize_before = normalize_before
-
- def with_pos_embed(self, tensor, pos: Optional[Tensor]):
- return tensor if pos is None else tensor + pos
-
- def forward_post(self,
- src,
- src_mask: Optional[Tensor] = None,
- src_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None):
- q = k = self.with_pos_embed(src, pos)
- src2 = self.self_attn(q, k, value=src, attn_mask=src_mask,
- key_padding_mask=src_key_padding_mask)[0]
- src = src + self.dropout1(src2)
- src = self.norm1(src)
- src2 = self.linear2(self.dropout(self.activation(self.linear1(src))))
- src = src + self.dropout2(src2)
- src = self.norm2(src)
- return src
-
- def forward_pre(self, src,
- src_mask: Optional[Tensor] = None,
- src_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None):
- src2 = self.norm1(src)
- q = k = self.with_pos_embed(src2, pos)
- src2 = self.self_attn(q, k, value=src2, attn_mask=src_mask,
- key_padding_mask=src_key_padding_mask)[0]
- src = src + self.dropout1(src2)
- src2 = self.norm2(src)
- src2 = self.linear2(self.dropout(self.activation(self.linear1(src2))))
- src = src + self.dropout2(src2)
- return src
-
- def forward(self, src,
- src_mask: Optional[Tensor] = None,
- src_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None):
- if self.normalize_before:
- return self.forward_pre(src, src_mask, src_key_padding_mask, pos)
- return self.forward_post(src, src_mask, src_key_padding_mask, pos)
-
-
-class TransformerDecoderLayer(nn.Module):
-
- def __init__(self, d_model, nhead, dim_feedforward=2048, dropout=0.1,
- activation="relu", normalize_before=False):
- super().__init__()
- self.self_attn = nn.MultiheadAttention(d_model, nhead, dropout=dropout)
- self.multihead_attn = nn.MultiheadAttention(d_model, nhead, dropout=dropout)
- # Implementation of Feedforward model
- self.linear1 = nn.Linear(d_model, dim_feedforward)
- self.dropout = nn.Dropout(dropout)
- self.linear2 = nn.Linear(dim_feedforward, d_model)
-
- self.norm1 = nn.LayerNorm(d_model)
- self.norm2 = nn.LayerNorm(d_model)
- self.norm3 = nn.LayerNorm(d_model)
- self.dropout1 = nn.Dropout(dropout)
- self.dropout2 = nn.Dropout(dropout)
- self.dropout3 = nn.Dropout(dropout)
-
- self.activation = _get_activation_fn(activation)
- self.normalize_before = normalize_before
-
- def with_pos_embed(self, tensor, pos: Optional[Tensor]):
- return tensor if pos is None else tensor + pos
-
- def forward_post(self, tgt, memory,
- tgt_mask: Optional[Tensor] = None,
- memory_mask: Optional[Tensor] = None,
- tgt_key_padding_mask: Optional[Tensor] = None,
- memory_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None,
- query_pos: Optional[Tensor] = None):
- q = k = self.with_pos_embed(tgt, query_pos)
- tgt2 = self.self_attn(q, k, value=tgt, attn_mask=tgt_mask,
- key_padding_mask=tgt_key_padding_mask)[0]
- tgt = tgt + self.dropout1(tgt2)
- tgt = self.norm1(tgt)
- tgt2 = self.multihead_attn(query=self.with_pos_embed(tgt, query_pos),
- key=self.with_pos_embed(memory, pos),
- value=memory, attn_mask=memory_mask,
- key_padding_mask=memory_key_padding_mask)[0]
- tgt = tgt + self.dropout2(tgt2)
- tgt = self.norm2(tgt)
- tgt2 = self.linear2(self.dropout(self.activation(self.linear1(tgt))))
- tgt = tgt + self.dropout3(tgt2)
- tgt = self.norm3(tgt)
- return tgt
-
- def forward_pre(self, tgt, memory,
- tgt_mask: Optional[Tensor] = None,
- memory_mask: Optional[Tensor] = None,
- tgt_key_padding_mask: Optional[Tensor] = None,
- memory_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None,
- query_pos: Optional[Tensor] = None):
- tgt2 = self.norm1(tgt)
- q = k = self.with_pos_embed(tgt2, query_pos)
- tgt2 = self.self_attn(q, k, value=tgt2, attn_mask=tgt_mask,
- key_padding_mask=tgt_key_padding_mask)[0]
- tgt = tgt + self.dropout1(tgt2)
- tgt2 = self.norm2(tgt)
- tgt2 = self.multihead_attn(query=self.with_pos_embed(tgt2, query_pos),
- key=self.with_pos_embed(memory, pos),
- value=memory, attn_mask=memory_mask,
- key_padding_mask=memory_key_padding_mask)[0]
- tgt = tgt + self.dropout2(tgt2)
- tgt2 = self.norm3(tgt)
- tgt2 = self.linear2(self.dropout(self.activation(self.linear1(tgt2))))
- tgt = tgt + self.dropout3(tgt2)
- return tgt
-
- def forward(self, tgt, memory,
- tgt_mask: Optional[Tensor] = None,
- memory_mask: Optional[Tensor] = None,
- tgt_key_padding_mask: Optional[Tensor] = None,
- memory_key_padding_mask: Optional[Tensor] = None,
- pos: Optional[Tensor] = None,
- query_pos: Optional[Tensor] = None):
- if self.normalize_before:
- return self.forward_pre(tgt, memory, tgt_mask, memory_mask,
- tgt_key_padding_mask, memory_key_padding_mask, pos, query_pos)
- return self.forward_post(tgt, memory, tgt_mask, memory_mask,
- tgt_key_padding_mask, memory_key_padding_mask, pos, query_pos)
-
-
-def _get_clones(module, N):
- return nn.ModuleList([copy.deepcopy(module) for i in range(N)])
-
-
-def build_transformer(args):
- return Transformer(
- d_model=args.hidden_dim,
- dropout=args.dropout,
- nhead=args.nheads,
- dim_feedforward=args.dim_feedforward,
- num_encoder_layers=args.enc_layers,
- num_decoder_layers=args.dec_layers,
- normalize_before=args.pre_norm,
- return_intermediate_dec=True,
- )
-
-
-def _get_activation_fn(activation):
- """Return an activation function given a string"""
- if activation == "relu":
- return F.relu
- if activation == "gelu":
- return F.gelu
- if activation == "glu":
- return F.glu
- raise RuntimeError(F"activation should be relu/gelu, not {activation}.")
diff --git a/act/detr/setup.py b/act/detr/setup.py
deleted file mode 100644
index 55d18c0..0000000
--- a/act/detr/setup.py
+++ /dev/null
@@ -1,10 +0,0 @@
-from distutils.core import setup
-from setuptools import find_packages
-
-setup(
- name='detr',
- version='0.0.0',
- packages=find_packages(),
- license='MIT License',
- long_description=open('README.md').read(),
-)
\ No newline at end of file
diff --git a/act/detr/util/__init__.py b/act/detr/util/__init__.py
deleted file mode 100644
index 168f997..0000000
--- a/act/detr/util/__init__.py
+++ /dev/null
@@ -1 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
diff --git a/act/detr/util/box_ops.py b/act/detr/util/box_ops.py
deleted file mode 100644
index 9c088e5..0000000
--- a/act/detr/util/box_ops.py
+++ /dev/null
@@ -1,88 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-"""
-Utilities for bounding box manipulation and GIoU.
-"""
-import torch
-from torchvision.ops.boxes import box_area
-
-
-def box_cxcywh_to_xyxy(x):
- x_c, y_c, w, h = x.unbind(-1)
- b = [(x_c - 0.5 * w), (y_c - 0.5 * h),
- (x_c + 0.5 * w), (y_c + 0.5 * h)]
- return torch.stack(b, dim=-1)
-
-
-def box_xyxy_to_cxcywh(x):
- x0, y0, x1, y1 = x.unbind(-1)
- b = [(x0 + x1) / 2, (y0 + y1) / 2,
- (x1 - x0), (y1 - y0)]
- return torch.stack(b, dim=-1)
-
-
-# modified from torchvision to also return the union
-def box_iou(boxes1, boxes2):
- area1 = box_area(boxes1)
- area2 = box_area(boxes2)
-
- lt = torch.max(boxes1[:, None, :2], boxes2[:, :2]) # [N,M,2]
- rb = torch.min(boxes1[:, None, 2:], boxes2[:, 2:]) # [N,M,2]
-
- wh = (rb - lt).clamp(min=0) # [N,M,2]
- inter = wh[:, :, 0] * wh[:, :, 1] # [N,M]
-
- union = area1[:, None] + area2 - inter
-
- iou = inter / union
- return iou, union
-
-
-def generalized_box_iou(boxes1, boxes2):
- """
- Generalized IoU from https://giou.stanford.edu/
-
- The boxes should be in [x0, y0, x1, y1] format
-
- Returns a [N, M] pairwise matrix, where N = len(boxes1)
- and M = len(boxes2)
- """
- # degenerate boxes gives inf / nan results
- # so do an early check
- assert (boxes1[:, 2:] >= boxes1[:, :2]).all()
- assert (boxes2[:, 2:] >= boxes2[:, :2]).all()
- iou, union = box_iou(boxes1, boxes2)
-
- lt = torch.min(boxes1[:, None, :2], boxes2[:, :2])
- rb = torch.max(boxes1[:, None, 2:], boxes2[:, 2:])
-
- wh = (rb - lt).clamp(min=0) # [N,M,2]
- area = wh[:, :, 0] * wh[:, :, 1]
-
- return iou - (area - union) / area
-
-
-def masks_to_boxes(masks):
- """Compute the bounding boxes around the provided masks
-
- The masks should be in format [N, H, W] where N is the number of masks, (H, W) are the spatial dimensions.
-
- Returns a [N, 4] tensors, with the boxes in xyxy format
- """
- if masks.numel() == 0:
- return torch.zeros((0, 4), device=masks.device)
-
- h, w = masks.shape[-2:]
-
- y = torch.arange(0, h, dtype=torch.float)
- x = torch.arange(0, w, dtype=torch.float)
- y, x = torch.meshgrid(y, x)
-
- x_mask = (masks * x.unsqueeze(0))
- x_max = x_mask.flatten(1).max(-1)[0]
- x_min = x_mask.masked_fill(~(masks.bool()), 1e8).flatten(1).min(-1)[0]
-
- y_mask = (masks * y.unsqueeze(0))
- y_max = y_mask.flatten(1).max(-1)[0]
- y_min = y_mask.masked_fill(~(masks.bool()), 1e8).flatten(1).min(-1)[0]
-
- return torch.stack([x_min, y_min, x_max, y_max], 1)
diff --git a/act/detr/util/misc.py b/act/detr/util/misc.py
deleted file mode 100644
index dfa9fb5..0000000
--- a/act/detr/util/misc.py
+++ /dev/null
@@ -1,468 +0,0 @@
-# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved
-"""
-Misc functions, including distributed helpers.
-
-Mostly copy-paste from torchvision references.
-"""
-import os
-import subprocess
-import time
-from collections import defaultdict, deque
-import datetime
-import pickle
-from packaging import version
-from typing import Optional, List
-
-import torch
-import torch.distributed as dist
-from torch import Tensor
-
-# needed due to empty tensor bug in pytorch and torchvision 0.5
-import torchvision
-if version.parse(torchvision.__version__) < version.parse('0.7'):
- from torchvision.ops import _new_empty_tensor
- from torchvision.ops.misc import _output_size
-
-
-class SmoothedValue(object):
- """Track a series of values and provide access to smoothed values over a
- window or the global series average.
- """
-
- def __init__(self, window_size=20, fmt=None):
- if fmt is None:
- fmt = "{median:.4f} ({global_avg:.4f})"
- self.deque = deque(maxlen=window_size)
- self.total = 0.0
- self.count = 0
- self.fmt = fmt
-
- def update(self, value, n=1):
- self.deque.append(value)
- self.count += n
- self.total += value * n
-
- def synchronize_between_processes(self):
- """
- Warning: does not synchronize the deque!
- """
- if not is_dist_avail_and_initialized():
- return
- t = torch.tensor([self.count, self.total], dtype=torch.float64, device='cuda')
- dist.barrier()
- dist.all_reduce(t)
- t = t.tolist()
- self.count = int(t[0])
- self.total = t[1]
-
- @property
- def median(self):
- d = torch.tensor(list(self.deque))
- return d.median().item()
-
- @property
- def avg(self):
- d = torch.tensor(list(self.deque), dtype=torch.float32)
- return d.mean().item()
-
- @property
- def global_avg(self):
- return self.total / self.count
-
- @property
- def max(self):
- return max(self.deque)
-
- @property
- def value(self):
- return self.deque[-1]
-
- def __str__(self):
- return self.fmt.format(
- median=self.median,
- avg=self.avg,
- global_avg=self.global_avg,
- max=self.max,
- value=self.value)
-
-
-def all_gather(data):
- """
- Run all_gather on arbitrary picklable data (not necessarily tensors)
- Args:
- data: any picklable object
- Returns:
- list[data]: list of data gathered from each rank
- """
- world_size = get_world_size()
- if world_size == 1:
- return [data]
-
- # serialized to a Tensor
- buffer = pickle.dumps(data)
- storage = torch.ByteStorage.from_buffer(buffer)
- tensor = torch.ByteTensor(storage).to("cuda")
-
- # obtain Tensor size of each rank
- local_size = torch.tensor([tensor.numel()], device="cuda")
- size_list = [torch.tensor([0], device="cuda") for _ in range(world_size)]
- dist.all_gather(size_list, local_size)
- size_list = [int(size.item()) for size in size_list]
- max_size = max(size_list)
-
- # receiving Tensor from all ranks
- # we pad the tensor because torch all_gather does not support
- # gathering tensors of different shapes
- tensor_list = []
- for _ in size_list:
- tensor_list.append(torch.empty((max_size,), dtype=torch.uint8, device="cuda"))
- if local_size != max_size:
- padding = torch.empty(size=(max_size - local_size,), dtype=torch.uint8, device="cuda")
- tensor = torch.cat((tensor, padding), dim=0)
- dist.all_gather(tensor_list, tensor)
-
- data_list = []
- for size, tensor in zip(size_list, tensor_list):
- buffer = tensor.cpu().numpy().tobytes()[:size]
- data_list.append(pickle.loads(buffer))
-
- return data_list
-
-
-def reduce_dict(input_dict, average=True):
- """
- Args:
- input_dict (dict): all the values will be reduced
- average (bool): whether to do average or sum
- Reduce the values in the dictionary from all processes so that all processes
- have the averaged results. Returns a dict with the same fields as
- input_dict, after reduction.
- """
- world_size = get_world_size()
- if world_size < 2:
- return input_dict
- with torch.no_grad():
- names = []
- values = []
- # sort the keys so that they are consistent across processes
- for k in sorted(input_dict.keys()):
- names.append(k)
- values.append(input_dict[k])
- values = torch.stack(values, dim=0)
- dist.all_reduce(values)
- if average:
- values /= world_size
- reduced_dict = {k: v for k, v in zip(names, values)}
- return reduced_dict
-
-
-class MetricLogger(object):
- def __init__(self, delimiter="\t"):
- self.meters = defaultdict(SmoothedValue)
- self.delimiter = delimiter
-
- def update(self, **kwargs):
- for k, v in kwargs.items():
- if isinstance(v, torch.Tensor):
- v = v.item()
- assert isinstance(v, (float, int))
- self.meters[k].update(v)
-
- def __getattr__(self, attr):
- if attr in self.meters:
- return self.meters[attr]
- if attr in self.__dict__:
- return self.__dict__[attr]
- raise AttributeError("'{}' object has no attribute '{}'".format(
- type(self).__name__, attr))
-
- def __str__(self):
- loss_str = []
- for name, meter in self.meters.items():
- loss_str.append(
- "{}: {}".format(name, str(meter))
- )
- return self.delimiter.join(loss_str)
-
- def synchronize_between_processes(self):
- for meter in self.meters.values():
- meter.synchronize_between_processes()
-
- def add_meter(self, name, meter):
- self.meters[name] = meter
-
- def log_every(self, iterable, print_freq, header=None):
- i = 0
- if not header:
- header = ''
- start_time = time.time()
- end = time.time()
- iter_time = SmoothedValue(fmt='{avg:.4f}')
- data_time = SmoothedValue(fmt='{avg:.4f}')
- space_fmt = ':' + str(len(str(len(iterable)))) + 'd'
- if torch.cuda.is_available():
- log_msg = self.delimiter.join([
- header,
- '[{0' + space_fmt + '}/{1}]',
- 'eta: {eta}',
- '{meters}',
- 'time: {time}',
- 'data: {data}',
- 'max mem: {memory:.0f}'
- ])
- else:
- log_msg = self.delimiter.join([
- header,
- '[{0' + space_fmt + '}/{1}]',
- 'eta: {eta}',
- '{meters}',
- 'time: {time}',
- 'data: {data}'
- ])
- MB = 1024.0 * 1024.0
- for obj in iterable:
- data_time.update(time.time() - end)
- yield obj
- iter_time.update(time.time() - end)
- if i % print_freq == 0 or i == len(iterable) - 1:
- eta_seconds = iter_time.global_avg * (len(iterable) - i)
- eta_string = str(datetime.timedelta(seconds=int(eta_seconds)))
- if torch.cuda.is_available():
- print(log_msg.format(
- i, len(iterable), eta=eta_string,
- meters=str(self),
- time=str(iter_time), data=str(data_time),
- memory=torch.cuda.max_memory_allocated() / MB))
- else:
- print(log_msg.format(
- i, len(iterable), eta=eta_string,
- meters=str(self),
- time=str(iter_time), data=str(data_time)))
- i += 1
- end = time.time()
- total_time = time.time() - start_time
- total_time_str = str(datetime.timedelta(seconds=int(total_time)))
- print('{} Total time: {} ({:.4f} s / it)'.format(
- header, total_time_str, total_time / len(iterable)))
-
-
-def get_sha():
- cwd = os.path.dirname(os.path.abspath(__file__))
-
- def _run(command):
- return subprocess.check_output(command, cwd=cwd).decode('ascii').strip()
- sha = 'N/A'
- diff = "clean"
- branch = 'N/A'
- try:
- sha = _run(['git', 'rev-parse', 'HEAD'])
- subprocess.check_output(['git', 'diff'], cwd=cwd)
- diff = _run(['git', 'diff-index', 'HEAD'])
- diff = "has uncommited changes" if diff else "clean"
- branch = _run(['git', 'rev-parse', '--abbrev-ref', 'HEAD'])
- except Exception:
- pass
- message = f"sha: {sha}, status: {diff}, branch: {branch}"
- return message
-
-
-def collate_fn(batch):
- batch = list(zip(*batch))
- batch[0] = nested_tensor_from_tensor_list(batch[0])
- return tuple(batch)
-
-
-def _max_by_axis(the_list):
- # type: (List[List[int]]) -> List[int]
- maxes = the_list[0]
- for sublist in the_list[1:]:
- for index, item in enumerate(sublist):
- maxes[index] = max(maxes[index], item)
- return maxes
-
-
-class NestedTensor(object):
- def __init__(self, tensors, mask: Optional[Tensor]):
- self.tensors = tensors
- self.mask = mask
-
- def to(self, device):
- # type: (Device) -> NestedTensor # noqa
- cast_tensor = self.tensors.to(device)
- mask = self.mask
- if mask is not None:
- assert mask is not None
- cast_mask = mask.to(device)
- else:
- cast_mask = None
- return NestedTensor(cast_tensor, cast_mask)
-
- def decompose(self):
- return self.tensors, self.mask
-
- def __repr__(self):
- return str(self.tensors)
-
-
-def nested_tensor_from_tensor_list(tensor_list: List[Tensor]):
- # TODO make this more general
- if tensor_list[0].ndim == 3:
- if torchvision._is_tracing():
- # nested_tensor_from_tensor_list() does not export well to ONNX
- # call _onnx_nested_tensor_from_tensor_list() instead
- return _onnx_nested_tensor_from_tensor_list(tensor_list)
-
- # TODO make it support different-sized images
- max_size = _max_by_axis([list(img.shape) for img in tensor_list])
- # min_size = tuple(min(s) for s in zip(*[img.shape for img in tensor_list]))
- batch_shape = [len(tensor_list)] + max_size
- b, c, h, w = batch_shape
- dtype = tensor_list[0].dtype
- device = tensor_list[0].device
- tensor = torch.zeros(batch_shape, dtype=dtype, device=device)
- mask = torch.ones((b, h, w), dtype=torch.bool, device=device)
- for img, pad_img, m in zip(tensor_list, tensor, mask):
- pad_img[: img.shape[0], : img.shape[1], : img.shape[2]].copy_(img)
- m[: img.shape[1], :img.shape[2]] = False
- else:
- raise ValueError('not supported')
- return NestedTensor(tensor, mask)
-
-
-# _onnx_nested_tensor_from_tensor_list() is an implementation of
-# nested_tensor_from_tensor_list() that is supported by ONNX tracing.
-@torch.jit.unused
-def _onnx_nested_tensor_from_tensor_list(tensor_list: List[Tensor]) -> NestedTensor:
- max_size = []
- for i in range(tensor_list[0].dim()):
- max_size_i = torch.max(torch.stack([img.shape[i] for img in tensor_list]).to(torch.float32)).to(torch.int64)
- max_size.append(max_size_i)
- max_size = tuple(max_size)
-
- # work around for
- # pad_img[: img.shape[0], : img.shape[1], : img.shape[2]].copy_(img)
- # m[: img.shape[1], :img.shape[2]] = False
- # which is not yet supported in onnx
- padded_imgs = []
- padded_masks = []
- for img in tensor_list:
- padding = [(s1 - s2) for s1, s2 in zip(max_size, tuple(img.shape))]
- padded_img = torch.nn.functional.pad(img, (0, padding[2], 0, padding[1], 0, padding[0]))
- padded_imgs.append(padded_img)
-
- m = torch.zeros_like(img[0], dtype=torch.int, device=img.device)
- padded_mask = torch.nn.functional.pad(m, (0, padding[2], 0, padding[1]), "constant", 1)
- padded_masks.append(padded_mask.to(torch.bool))
-
- tensor = torch.stack(padded_imgs)
- mask = torch.stack(padded_masks)
-
- return NestedTensor(tensor, mask=mask)
-
-
-def setup_for_distributed(is_master):
- """
- This function disables printing when not in master process
- """
- import builtins as __builtin__
- builtin_print = __builtin__.print
-
- def print(*args, **kwargs):
- force = kwargs.pop('force', False)
- if is_master or force:
- builtin_print(*args, **kwargs)
-
- __builtin__.print = print
-
-
-def is_dist_avail_and_initialized():
- if not dist.is_available():
- return False
- if not dist.is_initialized():
- return False
- return True
-
-
-def get_world_size():
- if not is_dist_avail_and_initialized():
- return 1
- return dist.get_world_size()
-
-
-def get_rank():
- if not is_dist_avail_and_initialized():
- return 0
- return dist.get_rank()
-
-
-def is_main_process():
- return get_rank() == 0
-
-
-def save_on_master(*args, **kwargs):
- if is_main_process():
- torch.save(*args, **kwargs)
-
-
-def init_distributed_mode(args):
- if 'RANK' in os.environ and 'WORLD_SIZE' in os.environ:
- args.rank = int(os.environ["RANK"])
- args.world_size = int(os.environ['WORLD_SIZE'])
- args.gpu = int(os.environ['LOCAL_RANK'])
- elif 'SLURM_PROCID' in os.environ:
- args.rank = int(os.environ['SLURM_PROCID'])
- args.gpu = args.rank % torch.cuda.device_count()
- else:
- print('Not using distributed mode')
- args.distributed = False
- return
-
- args.distributed = True
-
- torch.cuda.set_device(args.gpu)
- args.dist_backend = 'nccl'
- print('| distributed init (rank {}): {}'.format(
- args.rank, args.dist_url), flush=True)
- torch.distributed.init_process_group(backend=args.dist_backend, init_method=args.dist_url,
- world_size=args.world_size, rank=args.rank)
- torch.distributed.barrier()
- setup_for_distributed(args.rank == 0)
-
-
-@torch.no_grad()
-def accuracy(output, target, topk=(1,)):
- """Computes the precision@k for the specified values of k"""
- if target.numel() == 0:
- return [torch.zeros([], device=output.device)]
- maxk = max(topk)
- batch_size = target.size(0)
-
- _, pred = output.topk(maxk, 1, True, True)
- pred = pred.t()
- correct = pred.eq(target.view(1, -1).expand_as(pred))
-
- res = []
- for k in topk:
- correct_k = correct[:k].view(-1).float().sum(0)
- res.append(correct_k.mul_(100.0 / batch_size))
- return res
-
-
-def interpolate(input, size=None, scale_factor=None, mode="nearest", align_corners=None):
- # type: (Tensor, Optional[List[int]], Optional[float], str, Optional[bool]) -> Tensor
- """
- Equivalent to nn.functional.interpolate, but with support for empty batch sizes.
- This will eventually be supported natively by PyTorch, and this
- class can go away.
- """
- if version.parse(torchvision.__version__) < version.parse('0.7'):
- if input.numel() > 0:
- return torch.nn.functional.interpolate(
- input, size, scale_factor, mode, align_corners
- )
-
- output_shape = _output_size(2, input, size, scale_factor)
- output_shape = list(input.shape[:-2]) + list(output_shape)
- return _new_empty_tensor(input, output_shape)
- else:
- return torchvision.ops.misc.interpolate(input, size, scale_factor, mode, align_corners)
diff --git a/act/detr/util/plot_utils.py b/act/detr/util/plot_utils.py
deleted file mode 100644
index 0f24bed..0000000
--- a/act/detr/util/plot_utils.py
+++ /dev/null
@@ -1,107 +0,0 @@
-"""
-Plotting utilities to visualize training logs.
-"""
-import torch
-import pandas as pd
-import numpy as np
-import seaborn as sns
-import matplotlib.pyplot as plt
-
-from pathlib import Path, PurePath
-
-
-def plot_logs(logs, fields=('class_error', 'loss_bbox_unscaled', 'mAP'), ewm_col=0, log_name='log.txt'):
- '''
- Function to plot specific fields from training log(s). Plots both training and test results.
-
- :: Inputs - logs = list containing Path objects, each pointing to individual dir with a log file
- - fields = which results to plot from each log file - plots both training and test for each field.
- - ewm_col = optional, which column to use as the exponential weighted smoothing of the plots
- - log_name = optional, name of log file if different than default 'log.txt'.
-
- :: Outputs - matplotlib plots of results in fields, color coded for each log file.
- - solid lines are training results, dashed lines are test results.
-
- '''
- func_name = "plot_utils.py::plot_logs"
-
- # verify logs is a list of Paths (list[Paths]) or single Pathlib object Path,
- # convert single Path to list to avoid 'not iterable' error
-
- if not isinstance(logs, list):
- if isinstance(logs, PurePath):
- logs = [logs]
- print(f"{func_name} info: logs param expects a list argument, converted to list[Path].")
- else:
- raise ValueError(f"{func_name} - invalid argument for logs parameter.\n \
- Expect list[Path] or single Path obj, received {type(logs)}")
-
- # Quality checks - verify valid dir(s), that every item in list is Path object, and that log_name exists in each dir
- for i, dir in enumerate(logs):
- if not isinstance(dir, PurePath):
- raise ValueError(f"{func_name} - non-Path object in logs argument of {type(dir)}: \n{dir}")
- if not dir.exists():
- raise ValueError(f"{func_name} - invalid directory in logs argument:\n{dir}")
- # verify log_name exists
- fn = Path(dir / log_name)
- if not fn.exists():
- print(f"-> missing {log_name}. Have you gotten to Epoch 1 in training?")
- print(f"--> full path of missing log file: {fn}")
- return
-
- # load log file(s) and plot
- dfs = [pd.read_json(Path(p) / log_name, lines=True) for p in logs]
-
- fig, axs = plt.subplots(ncols=len(fields), figsize=(16, 5))
-
- for df, color in zip(dfs, sns.color_palette(n_colors=len(logs))):
- for j, field in enumerate(fields):
- if field == 'mAP':
- coco_eval = pd.DataFrame(
- np.stack(df.test_coco_eval_bbox.dropna().values)[:, 1]
- ).ewm(com=ewm_col).mean()
- axs[j].plot(coco_eval, c=color)
- else:
- df.interpolate().ewm(com=ewm_col).mean().plot(
- y=[f'train_{field}', f'test_{field}'],
- ax=axs[j],
- color=[color] * 2,
- style=['-', '--']
- )
- for ax, field in zip(axs, fields):
- ax.legend([Path(p).name for p in logs])
- ax.set_title(field)
-
-
-def plot_precision_recall(files, naming_scheme='iter'):
- if naming_scheme == 'exp_id':
- # name becomes exp_id
- names = [f.parts[-3] for f in files]
- elif naming_scheme == 'iter':
- names = [f.stem for f in files]
- else:
- raise ValueError(f'not supported {naming_scheme}')
- fig, axs = plt.subplots(ncols=2, figsize=(16, 5))
- for f, color, name in zip(files, sns.color_palette("Blues", n_colors=len(files)), names):
- data = torch.load(f)
- # precision is n_iou, n_points, n_cat, n_area, max_det
- precision = data['precision']
- recall = data['params'].recThrs
- scores = data['scores']
- # take precision for all classes, all areas and 100 detections
- precision = precision[0, :, :, 0, -1].mean(1)
- scores = scores[0, :, :, 0, -1].mean(1)
- prec = precision.mean()
- rec = data['recall'][0, :, 0, -1].mean()
- print(f'{naming_scheme} {name}: mAP@50={prec * 100: 05.1f}, ' +
- f'score={scores.mean():0.3f}, ' +
- f'f1={2 * prec * rec / (prec + rec + 1e-8):0.3f}'
- )
- axs[0].plot(recall, precision, c=color)
- axs[1].plot(recall, scores, c=color)
-
- axs[0].set_title('Precision / Recall')
- axs[0].legend(names)
- axs[1].set_title('Scores / Recall')
- axs[1].legend(names)
- return fig, axs
diff --git a/act/imitate_episodes.py b/act/imitate_episodes.py
deleted file mode 100644
index f771972..0000000
--- a/act/imitate_episodes.py
+++ /dev/null
@@ -1,367 +0,0 @@
-import torch
-import numpy as np
-import os
-import pickle
-import argparse
-import matplotlib.pyplot as plt
-from copy import deepcopy
-from tqdm import tqdm
-from einops import rearrange
-
-# from .constants import DT
-# from .constants import PUPPET_GRIPPER_JOINT_OPEN
-from utils import load_data # data functions
-from utils import compute_dict_mean, set_seed, detach_dict, parse_id, find_all_ckpt # helper functions
-from policy import ACTPolicy, CNNMLPPolicy
-# from .visualize_episodes import save_videos
-import wandb
-
-# from sim_env import BOX_POSE
-# from constants import SIM_TASK_CONFIGS
-import IPython
-e = IPython.embed
-import time
-from itertools import repeat
-
-def repeater(data_loader):
- epoch = 0
- for loader in repeat(data_loader):
- for data in loader:
- yield data
- print(f'Epoch {epoch} done')
- epoch += 1
-
-from pathlib import Path
-
-
-def main(args):
- set_seed(1)
- # command line parameters
- is_eval = args['eval']
- policy_class = args['policy_class']
- onscreen_render = args['onscreen_render']
- # task_name = args['task_name']
- batch_size_train = args['batch_size']
- batch_size_val = args['batch_size']
- num_epochs = args['num_epochs']
-
- # get task parameters
- # is_sim = task_name[:4] == 'sim_'
- task_dir, task_name = parse_id(RECORD_DIR, args['taskid'])
- dataset_dir = (Path(task_dir) / 'processed').resolve()
- ckpt_dir = (LOG_DIR / task_name / args['exptid']).resolve()
- print("*"*20)
- print(f"Task name: {task_name}")
- print("*"*20)
-
- # print(f"Checkpoint dir: {ckpt_dir}")
- # task_config = SIM_TASK_CONFIGS[task_name]
- # dataset_dir = task_config['dataset_dir']
- # ckpt_dir = task_config['ckpt_dir']
- # num_episodes = task_config['num_episodes']
- # episode_len = task_config['episode_len']
- camera_names = ['left', 'right']
-
- # fixed parameters
- state_dim = 26
- action_dim = 28
- lr_backbone = 1e-5
- backbone = 'dino_v2'
- if policy_class == 'ACT':
- enc_layers = 4
- dec_layers = 7
- nheads = 8
- policy_config = {'lr': args['lr'],
- 'num_queries': args['chunk_size'],
- 'kl_weight': args['kl_weight'],
- 'hidden_dim': args['hidden_dim'],
- 'dim_feedforward': args['dim_feedforward'],
- 'lr_backbone': lr_backbone,
- 'backbone': backbone,
- 'enc_layers': enc_layers,
- 'dec_layers': dec_layers,
- 'nheads': nheads,
- 'camera_names': camera_names,
- 'state_dim': state_dim,
- 'action_dim': action_dim,
- 'qpos_noise_std': args['qpos_noise_std'],
- }
- elif policy_class == 'CNNMLP':
- policy_config = {'lr': args['lr'], 'lr_backbone': lr_backbone, 'backbone' : backbone, 'num_queries': 1,
- 'camera_names': camera_names,}
- else:
- raise NotImplementedError
-
- config = {
- 'num_epochs': num_epochs,
- 'ckpt_dir': ckpt_dir,
- # 'episode_len': episode_len,
- 'state_dim': state_dim,
- 'action_dim': action_dim,
- 'lr': args['lr'],
- 'policy_class': policy_class,
- 'onscreen_render': onscreen_render,
- 'policy_config': policy_config,
- # 'task_name': task_name,
- 'seed': args['seed'],
- 'temporal_agg': args['temporal_agg'],
- 'camera_names': camera_names,
- # 'real_robot': not is_sim
- 'resumeid': args['resumeid'],
- 'resume_ckpt': args['resume_ckpt'],
- 'task_name': task_name,
- 'exptid': args['exptid'],
- }
- mode = "disabled" if args["no_wandb"] or args["save_jit"] else "online"
- wandb.init(project="television", name=args['exptid'], group=task_name, entity="cxx", mode=mode, dir="../data/logs")
- wandb.config.update(config)
- train_dataloader, val_dataloader, stats, _ = load_data(dataset_dir, camera_names, batch_size_train, batch_size_val)
-
- # save dataset stats
- if not os.path.isdir(ckpt_dir):
- os.makedirs(ckpt_dir)
- stats_path = os.path.join(ckpt_dir, f'dataset_stats.pkl')
- with open(stats_path, 'wb') as f:
- pickle.dump(stats, f)
-
- if args['save_jit']:
- save_jit(config)
- return
-
- best_ckpt_info = train_bc(train_dataloader, val_dataloader, config)
- best_epoch, min_val_loss, best_state_dict = best_ckpt_info
-
- # save best checkpoint
- ckpt_path = os.path.join(ckpt_dir, f'policy_best.ckpt')
- torch.save(best_state_dict, ckpt_path)
- print(f'Best ckpt, val loss {min_val_loss:.6f} @ epoch{best_epoch}')
- wandb.finish()
-
-def make_policy(policy_class, policy_config):
- if policy_class == 'ACT':
- policy = ACTPolicy(policy_config)
- elif policy_class == 'CNNMLP':
- policy = CNNMLPPolicy(policy_config)
- else:
- raise NotImplementedError
- return policy
-
-
-def make_optimizer(policy_class, policy):
- if policy_class == 'ACT':
- optimizer = policy.configure_optimizers()
- elif policy_class == 'CNNMLP':
- optimizer = policy.configure_optimizers()
- else:
- raise NotImplementedError
- return optimizer
-
-
-def get_image(ts, camera_names):
- curr_images = []
- for cam_name in camera_names:
- curr_image = rearrange(ts.observation['images'][cam_name], 'h w c -> c h w')
- curr_images.append(curr_image)
- curr_image = np.stack(curr_images, axis=0)
- curr_image = torch.from_numpy(curr_image / 255.0).float().cuda().unsqueeze(0)
- return curr_image
-
-
-def forward_pass(data, policy):
- image_data, qpos_data, action_data, is_pad = data
- image_data, qpos_data, action_data, is_pad = image_data.cuda(), qpos_data.cuda(), action_data.cuda(), is_pad.cuda()
- return policy(qpos_data, image_data, action_data, is_pad) # TODO remove None
-
-
-
-def train_bc(train_dataloader, val_dataloader, config):
- num_epochs = config['num_epochs']
- ckpt_dir = config['ckpt_dir']
- seed = config['seed']
- policy_class = config['policy_class']
- policy_config = config['policy_config']
-
- set_seed(seed)
-
- policy = make_policy(policy_class, policy_config)
- policy.cuda()
- optimizer = make_optimizer(policy_class, policy)
-
- if config['resumeid']:
- exp_dir, exp_name = parse_id((LOG_DIR / config['task_name']).resolve(), config['resumeid'])
- policy, _, _ = load_ckpt(policy, exp_dir, config['resume_ckpt'])
- # if config['resume_ckpt']:
- # ckpt_name = f"policy_epoch_{config['resume_ckpt']}_seed_0.ckpt"
- # else:
- # ckpt_name, _ = find_all_ckpt(exp_dir)#f"policy_last.ckpt"
- # resume_path = (Path(exp_dir) / ckpt_name).resolve()
- # print(f"Resuming from {resume_path}")
- # checkpoint = torch.load(resume_path)
- # policy.load_state_dict(checkpoint)
-
- # train_history = []
- # validation_history = []
- min_val_loss = np.inf
- best_ckpt_info = None
-
- train_dataloader = repeater(train_dataloader)
- for epoch in tqdm(range(num_epochs)):
- print(f'\nEpoch {epoch}')
- if epoch % 500 == 0:
- # validation
- with torch.inference_mode():
- policy.eval()
- validation_dicts = []
- for batch_idx, data in enumerate(val_dataloader):
- forward_dict = forward_pass(data, policy)
- validation_dicts.append(forward_dict)
- if batch_idx > 20:
- break
-
- validation_summary = compute_dict_mean(validation_dicts)
-
- epoch_val_loss = validation_summary['loss']
- if epoch_val_loss < min_val_loss:
- min_val_loss = epoch_val_loss
- best_ckpt_info = (epoch, min_val_loss, deepcopy(policy.state_dict()))
- for k in list(validation_summary.keys()):
- validation_summary[f'val/{k}'] = validation_summary.pop(k)
- wandb.log(validation_summary, step=epoch)
- print(f'Val loss: {epoch_val_loss:.5f}')
- summary_string = ''
- for k, v in validation_summary.items():
- summary_string += f'{k}: {v.item():.3f} '
- print(summary_string)
-
- # training
- policy.train()
- optimizer.zero_grad()
-
- data = next(train_dataloader)
- forward_dict = forward_pass(data, policy)
- # backward
- loss = forward_dict['loss']
- loss.backward()
- optimizer.step()
- optimizer.zero_grad()
-
- epoch_summary = detach_dict(forward_dict)
-
- # epoch_summary = compute_dict_mean(train_history[(batch_idx+1)*epoch:(batch_idx+1)*(epoch+1)])
- epoch_train_loss = epoch_summary['loss']
- print(f'Train loss: {epoch_train_loss:.5f}')
- summary_string = ''
- for k, v in epoch_summary.items():
- summary_string += f'{k}: {v.item():.3f} '
- print(summary_string)
- wandb.log(epoch_summary, step=epoch)
-
- if epoch % 1000 == 0 and epoch >= 1000:
- ckpt_path = os.path.join(ckpt_dir, f'policy_epoch_{epoch}_seed_{seed}.ckpt')
- torch.save(policy.state_dict(), ckpt_path)
- # plot_history(train_history, validation_history, epoch, ckpt_dir, seed)
-
- ckpt_path = os.path.join(ckpt_dir, f'policy_last.ckpt')
- torch.save(policy.state_dict(), ckpt_path)
-
- best_epoch, min_val_loss, best_state_dict = best_ckpt_info
- ckpt_path = os.path.join(ckpt_dir, f'policy_epoch_{best_epoch}_seed_{seed}.ckpt')
- torch.save(best_state_dict, ckpt_path)
- print(f'Training finished:\nSeed {seed}, val loss {min_val_loss:.6f} at epoch {best_epoch}')
-
- # save training curves
- # plot_history(train_history, validation_history, num_epochs, ckpt_dir, seed)
-
- return best_ckpt_info
-
-
-def plot_history(train_history, validation_history, num_epochs, ckpt_dir, seed):
- # save training curves
- for key in train_history[0]:
- plot_path = os.path.join(ckpt_dir, f'train_val_{key}_seed_{seed}.png')
- plt.figure()
- train_values = [summary[key].item() for summary in train_history]
- val_values = [summary[key].item() for summary in validation_history]
- plt.plot(np.linspace(0, num_epochs-1, len(train_history)), train_values, label='train')
- plt.plot(np.linspace(0, num_epochs-1, len(validation_history)), val_values, label='validation')
- # plt.ylim([-0.1, 1])
- plt.tight_layout()
- plt.legend()
- plt.title(key)
- plt.savefig(plot_path)
- print(f'Saved plots to {ckpt_dir}')
-
-def load_ckpt(policy, exp_dir, ckpt_name):
- if ckpt_name:
- epoch = ckpt_name
- ckpt_name = f"policy_epoch_{ckpt_name}_seed_0.ckpt"
- else:
- ckpt_name, epoch = find_all_ckpt(exp_dir)#f"policy_last.ckpt"
- resume_path = (Path(exp_dir) / ckpt_name).resolve()
- print("*"*20)
- print(f"Resuming from {resume_path}")
- print("*"*20)
- policy.load_state_dict(torch.load(resume_path))
- return policy, ckpt_name, epoch
-
-def save_jit(config):
- # ckpt_dir = config['ckpt_dir']
- policy_class = config['policy_class']
- policy_config = config['policy_config']
-
- exp_dir, exp_name = parse_id((LOG_DIR / config['task_name']).resolve(), config['exptid'])
-
- policy = make_policy(policy_class, policy_config)
- policy.cuda()
-
- policy, ckpt_name, epoch = load_ckpt(policy, exp_dir, config['resume_ckpt'])
-
- policy.eval()
- image_data = torch.rand((1, 2, 3, 480, 640), device='cuda')
- qpos_data = torch.rand((1, config['state_dim']), device='cuda')
- input_data = (qpos_data, image_data)
-
- traced_policy = torch.jit.trace(policy, input_data)
- save_path = os.path.join(exp_dir, f"traced_jit_{epoch}.pt")
- traced_policy.save(save_path)
- print("Saved traced actor at ", save_path)
-
- new_policy = torch.jit.load(save_path)
-
-if __name__ == '__main__':
- parser = argparse.ArgumentParser()
- parser.add_argument('--eval', action='store_true')
- parser.add_argument('--onscreen_render', action='store_true')
- parser.add_argument('--policy_class', action='store', type=str, help='policy_class, capitalize', required=True)
- # parser.add_argument('--task_name', action='store', type=str, help='task_name', required=True)
- parser.add_argument('--batch_size', action='store', type=int, help='batch_size', required=True)
- parser.add_argument('--seed', action='store', type=int, help='seed', required=True)
- parser.add_argument('--num_epochs', action='store', type=int, help='num_epochs', required=True)
- parser.add_argument('--lr', action='store', type=float, help='lr', required=True)
- parser.add_argument('--qpos_noise_std', action='store', default=0, type=float, help='lr', required=False)
-
- # for ACT
- parser.add_argument('--kl_weight', action='store', type=int, help='KL Weight', required=False)
- parser.add_argument('--chunk_size', action='store', type=int, help='chunk_size', required=False)
- parser.add_argument('--hidden_dim', action='store', type=int, help='hidden_dim', required=False)
- parser.add_argument('--dim_feedforward', action='store', type=int, help='dim_feedforward', required=False)
- parser.add_argument('--temporal_agg', action='store_true')
- parser.add_argument('--save_jit', action='store_true')
- parser.add_argument('--no_wandb', action='store_true')
- parser.add_argument('--resumeid', action='store', default="", type=str, help='resume id', required=False)
- parser.add_argument('--resume_ckpt', action='store', default="", type=str, help='resume ckpt', required=False)
- parser.add_argument('--taskid', action='store', type=str, help='task id', required=True)
- parser.add_argument('--exptid', action='store', type=str, help='experiment id', required=True)
- parser.add_argument('--source', choices=['self', 'ssd'], default='self')
- args = vars(parser.parse_args())
-
- if args['source'] == 'self':
- current_dir = Path(__file__).parent.resolve()
- else:
- current_dir = Path("/media/cxx/Extreme Pro/human2robot/data/").resolve()
- DATA_DIR = (current_dir.parent / 'data/').resolve()
- RECORD_DIR = (DATA_DIR / 'recordings/').resolve()
- LOG_DIR = (DATA_DIR / 'logs/').resolve()
- # print(f"\nDATA dir: {DATA_DIR}")
-
- main(args)
diff --git a/act/policy.py b/act/policy.py
deleted file mode 100644
index ef6061d..0000000
--- a/act/policy.py
+++ /dev/null
@@ -1,115 +0,0 @@
-import torch.nn as nn
-from torch.nn import functional as F
-from torchvision.transforms import v2
-import torch
-
-from detr.main import build_ACT_model_and_optimizer, build_CNNMLP_model_and_optimizer
-import IPython
-e = IPython.embed
-
-class ACTPolicy(nn.Module):
- def __init__(self, args_override):
- super().__init__()
- model, optimizer = build_ACT_model_and_optimizer(args_override)
- self.model = model # CVAE decoder
- self.optimizer = optimizer
- self.kl_weight = args_override['kl_weight']
- self.qpos_noise_std = args_override['qpos_noise_std']
- print(f'KL Weight {self.kl_weight}')
-
- def __call__(self, qpos, image, actions=None, is_pad=None):
- env_state = None
- # normalize = transforms.Normalize(mean=[0.485, 0.456, 0.406],
- # std=[0.229, 0.224, 0.225])
- patch_h = 16
- patch_w = 22
- if actions is not None: # training time
- # transform = v2.Compose([
- # v2.ColorJitter(brightness=0.5, contrast=0.5, saturation=0.5, hue=0.5),
- # v2.RandomPerspective(distortion_scale=0.5),
- # v2.RandomAffine(degrees=10, translate=(0.1,0.1), scale=(0.9,1.1)),
- # v2.GaussianBlur(kernel_size=(9,9), sigma=(0.1,2.0)),
- # v2.Normalize(
- # mean=[0.485, 0.456, 0.406],
- # std=[0.229, 0.224, 0.225])
- # ])
- transform = v2.Compose([
- v2.ColorJitter(brightness=0.5, contrast=0.5, saturation=0.5, hue=0.5),
- v2.RandomPerspective(distortion_scale=0.5),
- v2.RandomAffine(degrees=10, translate=(0.1,0.1), scale=(0.9,1.1)),
- v2.GaussianBlur(kernel_size=(9,9), sigma=(0.1,2.0)),
- v2.Resize((patch_h * 14, patch_w * 14)),
- # v2.CenterCrop((patch_h * 14, patch_w * 14)),
- v2.Normalize(mean=(0.485, 0.456, 0.406), std=(0.229, 0.224, 0.225)),
- ])
- qpos += (self.qpos_noise_std**0.5)*torch.randn_like(qpos)
- else: # inference time
- transform = v2.Compose([
- v2.Resize((patch_h * 14, patch_w * 14)),
- # v2.CenterCrop((patch_h * 14, patch_w * 14)),
- v2.Normalize(mean=(0.485, 0.456, 0.406), std=(0.229, 0.224, 0.225))
- ])
-
- image = transform(image)
- if actions is not None: # training time
- actions = actions[:, :self.model.num_queries]
- is_pad = is_pad[:, :self.model.num_queries]
-
- a_hat, is_pad_hat, (mu, logvar) = self.model(qpos, image, env_state, actions, is_pad)
- total_kld, dim_wise_kld, mean_kld = kl_divergence(mu, logvar)
- loss_dict = dict()
- all_l1 = F.l1_loss(actions, a_hat, reduction='none')
- l1 = (all_l1 * ~is_pad.unsqueeze(-1)).mean()
- loss_dict['l1'] = l1
- loss_dict['kl'] = total_kld[0]
- loss_dict['loss'] = loss_dict['l1'] + loss_dict['kl'] * self.kl_weight
- return loss_dict
- else: # inference time
- a_hat, _, (_, _) = self.model(qpos, image, env_state) # no action, sample from prior
- return a_hat
-
- def configure_optimizers(self):
- return self.optimizer
-
-
-class CNNMLPPolicy(nn.Module):
- def __init__(self, args_override):
- super().__init__()
- model, optimizer = build_CNNMLP_model_and_optimizer(args_override)
- self.model = model # decoder
- self.optimizer = optimizer
-
- def __call__(self, qpos, image, actions=None, is_pad=None):
- env_state = None # TODO
- normalize = transforms.Normalize(mean=[0.485, 0.456, 0.406],
- std=[0.229, 0.224, 0.225])
- image = normalize(image)
- if actions is not None: # training time
- actions = actions[:, 0]
- a_hat = self.model(qpos, image, env_state, actions)
- mse = F.mse_loss(actions, a_hat)
- loss_dict = dict()
- loss_dict['mse'] = mse
- loss_dict['loss'] = loss_dict['mse']
- return loss_dict
- else: # inference time
- a_hat = self.model(qpos, image, env_state) # no action, sample from prior
- return a_hat
-
- def configure_optimizers(self):
- return self.optimizer
-
-def kl_divergence(mu, logvar):
- batch_size = mu.size(0)
- assert batch_size != 0
- if mu.data.ndimension() == 4:
- mu = mu.view(mu.size(0), mu.size(1))
- if logvar.data.ndimension() == 4:
- logvar = logvar.view(logvar.size(0), logvar.size(1))
-
- klds = -0.5 * (1 + logvar - mu.pow(2) - logvar.exp())
- total_kld = klds.sum(1).mean(0, True)
- dimension_wise_kld = klds.mean(0)
- mean_kld = klds.mean(1).mean(0, True)
-
- return total_kld, dimension_wise_kld, mean_kld
diff --git a/act/utils.py b/act/utils.py
deleted file mode 100644
index f4de4ab..0000000
--- a/act/utils.py
+++ /dev/null
@@ -1,286 +0,0 @@
-import numpy as np
-import torch
-import os
-import h5py
-from torch.utils.data import TensorDataset, DataLoader
-import time
-import IPython
-e = IPython.embed
-from pathlib import Path
-
-class EpisodicDataset(torch.utils.data.Dataset):
- def __init__(self, episode_ids, dataset_dir, camera_names, norm_stats, episode_len, history_stack=0):
- super(EpisodicDataset).__init__()
- self.episode_ids = episode_ids
- self.dataset_dir = dataset_dir
- self.camera_names = camera_names
- self.norm_stats = norm_stats
- self.is_sim = None
- self.max_pad_len = 200
- action_str = 'qpos_action'
-
- self.history_stack = history_stack
-
- self.dataset_paths = []
- self.roots = []
- self.is_sims = []
- self.original_action_shapes = []
-
- self.states = []
- self.image_dict = dict()
- for cam_name in self.camera_names:
- self.image_dict[cam_name] = []
- self.actions = []
-
- for i, episode_id in enumerate(self.episode_ids):
- self.dataset_paths.append(os.path.join(self.dataset_dir, f'processed_episode_{episode_id}.hdf5'))
- root = h5py.File(self.dataset_paths[i], 'r')
- self.roots.append(root)
- self.is_sims.append(root.attrs['sim'])
- self.original_action_shapes.append(root[action_str].shape)
-
- self.states.append(np.array(root['observation.state']))
- for cam_name in self.camera_names:
- self.image_dict[cam_name].append(root[f'observation.image.{cam_name}'])
- self.actions.append(np.array(root[action_str]))
-
- self.is_sim = self.is_sims[0]
-
- self.episode_len = episode_len
- self.cumulative_len = np.cumsum(self.episode_len)
-
- # self.__getitem__(0) # initialize self.is_sim
-
- # def __len__(self):
- # return len(self.episode_ids)
-
- def _locate_transition(self, index):
- assert index < self.cumulative_len[-1]
- episode_index = np.argmax(self.cumulative_len > index) # argmax returns first True index
- start_ts = index - (self.cumulative_len[episode_index] - self.episode_len[episode_index])
- return episode_index, start_ts
-
- def __getitem__(self, ts_index):
- sample_full_episode = False # hardcode
-
- index, start_ts = self._locate_transition(ts_index)
-
- original_action_shape = self.original_action_shapes[index]
- episode_len = original_action_shape[0]
-
- if sample_full_episode:
- start_ts = 0
- else:
- start_ts = np.random.choice(episode_len)
-
- # get observation at start_ts only
- qpos = self.states[index][start_ts]
- # qvel = root['/observations/qvel'][start_ts]
-
- if self.history_stack > 0:
- last_indices = np.maximum(0, np.arange(start_ts-self.history_stack, start_ts)).astype(int)
- last_action = self.actions[index][last_indices, :]
-
- image_dict = dict()
- for cam_name in self.camera_names:
- image_dict[cam_name] = self.image_dict[cam_name][index][start_ts]
- # get all actions after and including start_ts
- all_time_action = self.actions[index][:]
-
- all_time_action_padded = np.zeros((self.max_pad_len+original_action_shape[0], original_action_shape[1]), dtype=np.float32)
- all_time_action_padded[:episode_len] = all_time_action
- all_time_action_padded[episode_len:] = all_time_action[-1]
-
- padded_action = all_time_action_padded[start_ts:start_ts+self.max_pad_len]
- real_len = episode_len - start_ts
-
- is_pad = np.zeros(self.max_pad_len)
- is_pad[real_len:] = 1
-
- # new axis for different cameras
- all_cam_images = []
- for cam_name in self.camera_names:
- all_cam_images.append(image_dict[cam_name])
- all_cam_images = np.stack(all_cam_images, axis=0)
-
- # construct observations
- image_data = torch.from_numpy(all_cam_images)
- qpos_data = torch.from_numpy(qpos).float()
- action_data = torch.from_numpy(padded_action).float()
- is_pad = torch.from_numpy(is_pad).bool()
- if self.history_stack > 0:
- last_action_data = torch.from_numpy(last_action).float()
-
- # normalize image and change dtype to float
- image_data = image_data / 255.0
- action_data = (action_data - self.norm_stats["action_mean"]) / self.norm_stats["action_std"]
- qpos_data = (qpos_data - self.norm_stats["qpos_mean"]) / self.norm_stats["qpos_std"]
- if self.history_stack > 0:
- last_action_data = (last_action_data - self.norm_stats['action_mean']) / self.norm_stats['action_std']
- qpos_data = torch.cat((qpos_data, last_action_data.flatten()))
- # print(f"qpos_data: {qpos_data.shape}, action_data: {action_data.shape}, image_data: {image_data.shape}, is_pad: {is_pad.shape}")
- return image_data, qpos_data, action_data, is_pad
-
-
-def get_norm_stats(dataset_dir, num_episodes):
- action_str = 'qpos_action'
- all_qpos_data = []
- all_action_data = []
- all_episode_len = []
- for episode_idx in range(num_episodes):
- dataset_path = os.path.join(dataset_dir, f'processed_episode_{episode_idx}.hdf5')
- with h5py.File(dataset_path, 'r') as root:
- qpos = root['observation.state'][()]
- action = root[action_str][()]
- all_qpos_data.append(torch.from_numpy(qpos))
- all_action_data.append(torch.from_numpy(action))
- all_episode_len.append(len(qpos))
- all_qpos_data = torch.cat(all_qpos_data)
- all_action_data = torch.cat(all_action_data)
- all_action_data = all_action_data
-
- # normalize action data
- action_mean = all_action_data.mean(dim=0, keepdim=True) # (episode, timstep, action_dim)
- action_std = all_action_data.std(dim=0, keepdim=True)
- action_std = torch.clip(action_std, 1e-2, np.inf) # clipping
-
- # normalize qpos data
- qpos_mean = all_qpos_data.mean(dim=0, keepdim=True)
- qpos_std = all_qpos_data.std(dim=0, keepdim=True)
- qpos_std = torch.clip(qpos_std, 1e-2, np.inf) # clipping
-
- stats = {"action_mean": action_mean.numpy().squeeze(), "action_std": action_std.numpy().squeeze(),
- "qpos_mean": qpos_mean.numpy().squeeze(), "qpos_std": qpos_std.numpy().squeeze(),
- "example_qpos": qpos}
-
- return stats, all_episode_len
-
-def find_all_processed_episodes(path):
- episodes = [f for f in os.listdir(path)]
- return episodes
-
-def BatchSampler(batch_size, episode_len_l, sample_weights=None):
- sample_probs = np.array(sample_weights) / np.sum(sample_weights) if sample_weights is not None else None
- sum_dataset_len_l = np.cumsum([0] + [np.sum(episode_len) for episode_len in episode_len_l])
- while True:
- batch = []
- for _ in range(batch_size):
- episode_idx = np.random.choice(len(episode_len_l), p=sample_probs)
- step_idx = np.random.randint(sum_dataset_len_l[episode_idx], sum_dataset_len_l[episode_idx + 1])
- batch.append(step_idx)
- yield batch
-
-def load_data(dataset_dir, camera_names, batch_size_train, batch_size_val):
- print(f'\nData from: {dataset_dir}\n')
-
- all_eps = find_all_processed_episodes(dataset_dir)
- num_episodes = len(all_eps)
-
- # obtain train test split
- train_ratio = 0.99
- shuffled_indices = np.random.permutation(num_episodes)
- train_indices = shuffled_indices[:int(train_ratio * num_episodes)]
- val_indices = shuffled_indices[int(train_ratio * num_episodes):]
- print(f"Train episodes: {len(train_indices)}, Val episodes: {len(val_indices)}")
- # obtain normalization stats for qpos and action
- norm_stats, all_episode_len = get_norm_stats(dataset_dir, num_episodes)
-
- train_episode_len_l = [all_episode_len[i] for i in train_indices]
- val_episode_len_l = [all_episode_len[i] for i in val_indices]
- batch_sampler_train = BatchSampler(batch_size_train, train_episode_len_l)
- batch_sampler_val = BatchSampler(batch_size_val, val_episode_len_l, None)
-
- # construct dataset and dataloader
- train_dataset = EpisodicDataset(train_indices, dataset_dir, camera_names, norm_stats, train_episode_len_l)
- val_dataset = EpisodicDataset(val_indices, dataset_dir, camera_names, norm_stats, val_episode_len_l)
- train_dataloader = DataLoader(train_dataset, batch_sampler=batch_sampler_train, pin_memory=True, num_workers=24, prefetch_factor=2)
- val_dataloader = DataLoader(val_dataset, batch_sampler=batch_sampler_val, pin_memory=True, num_workers=16, prefetch_factor=2)
-
- return train_dataloader, val_dataloader, norm_stats, train_dataset.is_sim
-
-def sample_box_pose():
- x_range = [0.0, 0.2]
- y_range = [0.4, 0.6]
- z_range = [0.05, 0.05]
-
- ranges = np.vstack([x_range, y_range, z_range])
- cube_position = np.random.uniform(ranges[:, 0], ranges[:, 1])
-
- cube_quat = np.array([1, 0, 0, 0])
- return np.concatenate([cube_position, cube_quat])
-
-def sample_insertion_pose():
- # Peg
- x_range = [0.1, 0.2]
- y_range = [0.4, 0.6]
- z_range = [0.05, 0.05]
-
- ranges = np.vstack([x_range, y_range, z_range])
- peg_position = np.random.uniform(ranges[:, 0], ranges[:, 1])
-
- peg_quat = np.array([1, 0, 0, 0])
- peg_pose = np.concatenate([peg_position, peg_quat])
-
- # Socket
- x_range = [-0.2, -0.1]
- y_range = [0.4, 0.6]
- z_range = [0.05, 0.05]
-
- ranges = np.vstack([x_range, y_range, z_range])
- socket_position = np.random.uniform(ranges[:, 0], ranges[:, 1])
-
- socket_quat = np.array([1, 0, 0, 0])
- socket_pose = np.concatenate([socket_position, socket_quat])
-
- return peg_pose, socket_pose
-
-### helper functions
-
-def compute_dict_mean(epoch_dicts):
- result = {k: None for k in epoch_dicts[0]}
- num_items = len(epoch_dicts)
- for k in result:
- value_sum = 0
- for epoch_dict in epoch_dicts:
- value_sum += epoch_dict[k]
- result[k] = value_sum / num_items
- return result
-
-def detach_dict(d):
- new_d = dict()
- for k, v in d.items():
- new_d[k] = v.detach()
- return new_d
-
-def set_seed(seed):
- torch.manual_seed(seed)
- np.random.seed(seed)
-
-def parse_id(base_dir, prefix):
- base_path = Path(base_dir)
- # Ensure the base path exists and is a directory
- if not base_path.exists() or not base_path.is_dir():
- raise ValueError(f"The provided base directory does not exist or is not a directory: \n{base_path}")
-
- # Loop through all subdirectories of the base path
- for subfolder in base_path.iterdir():
- if subfolder.is_dir() and subfolder.name.startswith(prefix):
- return str(subfolder), subfolder.name
-
- # If no matching subfolder is found
- return None, None
-
-def find_all_ckpt(base_dir, prefix="policy_epoch_"):
- base_path = Path(base_dir)
- # Ensure the base path exists and is a directory
- if not base_path.exists() or not base_path.is_dir():
- raise ValueError("The provided base directory does not exist or is not a directory.")
-
- ckpt_files = []
- for file in base_path.iterdir():
- if file.is_file() and file.name.startswith(prefix):
- ckpt_files.append(file.name)
- # find latest ckpt
- ckpt_files = sorted(ckpt_files, key=lambda x: int(x.split(prefix)[-1].split('_')[0]), reverse=True)
- epoch = int(ckpt_files[0].split(prefix)[-1].split('_')[0])
- return ckpt_files[0], epoch
\ No newline at end of file
diff --git a/teleop/inspire_hand.yml b/assets/inspire_hand/inspire_hand.yml
similarity index 100%
rename from teleop/inspire_hand.yml
rename to assets/inspire_hand/inspire_hand.yml
diff --git a/assets/inspire_hand/inspire_hand_left.urdf b/assets/inspire_hand/inspire_hand_left.urdf
new file mode 100644
index 0000000..86299b3
--- /dev/null
+++ b/assets/inspire_hand/inspire_hand_left.urdf
@@ -0,0 +1,819 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/assets/inspire_hand/inspire_hand_right.urdf b/assets/inspire_hand/inspire_hand_right.urdf
new file mode 100644
index 0000000..8b9101a
--- /dev/null
+++ b/assets/inspire_hand/inspire_hand_right.urdf
@@ -0,0 +1,830 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/assets/inspire_hand/meshes/L_hand_base_link.STL b/assets/inspire_hand/meshes/L_hand_base_link.STL
new file mode 100644
index 0000000..a2f67ee
Binary files /dev/null and b/assets/inspire_hand/meshes/L_hand_base_link.STL differ
diff --git a/assets/inspire_hand/meshes/L_hand_base_link.STL.convex.stl b/assets/inspire_hand/meshes/L_hand_base_link.STL.convex.stl
new file mode 100644
index 0000000..554d9e0
--- /dev/null
+++ b/assets/inspire_hand/meshes/L_hand_base_link.STL.convex.stl
@@ -0,0 +1,1474 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.0187028348 -4.32133662e-10 -0.0180611182
+ vertex 0.0105751529 -4.32133662e-10 -0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.0105751529 -4.32133662e-10 -0.0237521827
+ vertex -0.000907386828 -4.32133662e-10 -0.0259841606
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.000907386828 -4.32133662e-10 -0.0259841606
+ vertex -0.0105751529 -4.32133662e-10 -0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0105751529 -4.32133662e-10 -0.0237521827
+ vertex -0.0187028348 -4.32133662e-10 -0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0187028348 -4.32133662e-10 -0.0180611182
+ vertex -0.0241067782 -4.32133662e-10 -0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0260000005 -4.32133662e-10 -1.38777878e-17
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0260000005 -4.32133662e-10 -1.38777878e-17
+ vertex -0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0241067782 -4.32133662e-10 0.00973977149
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0.000907386828 -4.32133662e-10 0.0259841606
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.000907386828 -4.32133662e-10 0.0259841606
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ vertex 0.0260000005 -4.32133662e-10 5.55111512e-17
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ vertex -0.0244811159 -0.0695781782 0.00495223841
+ vertex -0.0273340065 -0.0173235666 0.00190073461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0273340065 -0.0173235666 0.00190073461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ vertex -0.0273340065 -0.0173235666 0.00190073461
+ vertex -0.0244811159 -0.0695781782 0.00495223841
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125433328 -0.124834225 -0.000688163855
+ vertex -0.00650519738 -0.135713443 -0.0355430096
+ vertex -0.00650519738 -0.137854412 -0.00833936967
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125433328 -0.124834225 -0.000688163855
+ vertex -0.00650519738 -0.137854412 -0.00833936967
+ vertex -0.00650519738 -0.137646362 0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ vertex 0.009664963 -0.0640965328 0.0344437957
+ vertex 0.00479329983 -0.0740510002 0.0372099876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ vertex 0.00479329983 -0.0740510002 0.0372099876
+ vertex 0.00691642752 -0.12569502 0.0382629186
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ vertex -0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0187028348 -4.32133662e-10 -0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ vertex -0.0187028348 -4.32133662e-10 -0.0180611182
+ vertex -0.0192147028 -0.0557070896 -0.0333674178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0190336388 -0.00809999928 0.0197099112
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ vertex -0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0190336388 -0.00809999928 0.0197099112
+ vertex -0.0241067782 -4.32133662e-10 0.00973977149
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0105751529 -4.32133662e-10 -0.0237521827
+ vertex 0.0187028348 -4.32133662e-10 -0.0180611182
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ vertex -0.0190336388 -0.00809999928 0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex -0.0190336388 -0.00809999928 0.0197099112
+ vertex -0.00896000024 -0.0650000498 0.0366151184
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex -0.00896000024 -0.0650000498 0.0366151184
+ vertex -0.00234867237 -0.0606266819 0.0370310843
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex -0.00234867237 -0.0606266819 0.0370310843
+ vertex 0.000907386828 -4.32133662e-10 0.0259841606
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ vertex 0.0187028348 -4.32133662e-10 -0.0180611182
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00716353394 -0.128624678 0.0372513905
+ vertex -0.0101149492 -0.124164529 0.0367809236
+ vertex -0.00650519738 -0.137646362 0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0.0190336388 -0.00809999928 0.0197099112
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0105751529 -4.32133662e-10 -0.0237521827
+ vertex -0.000907386828 -4.32133662e-10 -0.0259841606
+ vertex -0.00969933067 -0.0557453819 -0.0384127125
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00578141259 -0.126041174 -0.0416803807
+ vertex 0.00793453213 -0.125224873 -0.0420319252
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00578141259 -0.126041174 -0.0416803807
+ vertex -0.00650519738 -0.135713443 -0.0355430096
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.011908954 -0.133186683 -0.0316933468
+ vertex 0.0109475097 -0.130095139 -0.038542293
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0116867665 -0.122572944 -0.0329686888
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ vertex -0.00650519738 -0.135713443 -0.0355430096
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0116867665 -0.122572944 -0.0329686888
+ vertex -0.00650519738 -0.135713443 -0.0355430096
+ vertex -0.0125433328 -0.124834225 -0.000688163855
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125433328 -0.124834225 -0.000688163855
+ vertex -0.0244811159 -0.0695781782 0.00495223841
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125433328 -0.124834225 -0.000688163855
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ vertex -0.0116867665 -0.122572944 -0.0329686888
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0116867665 -0.122572944 -0.0329686888
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.0260000005 -4.32133662e-10 5.55111512e-17
+ vertex 0.027383307 -0.00809999928 -0.000956246222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex 0.027383307 -0.00809999928 -0.000956246222
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00926867872 -0.0801111758 -0.0412325785
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ vertex -0.0140070468 -0.0764443204 -0.0390844345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00396833802 -0.0550836511 -0.0369117446
+ vertex -0.00969933067 -0.0557453819 -0.0384127125
+ vertex -0.000907386828 -4.32133662e-10 -0.0259841606
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00396833802 -0.0550836511 -0.0369117446
+ vertex -0.000907386828 -4.32133662e-10 -0.0259841606
+ vertex 0.0105751529 -4.32133662e-10 -0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00396833802 -0.0550836511 -0.0369117446
+ vertex 0.00419739075 -0.0827994943 -0.0402534939
+ vertex -0.00926867872 -0.0801111758 -0.0412325785
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00396833802 -0.0550836511 -0.0369117446
+ vertex -0.00926867872 -0.0801111758 -0.0412325785
+ vertex -0.00969933067 -0.0557453819 -0.0384127125
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0122685954 -0.12224935 -0.0389004983
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0122685954 -0.12224935 -0.0389004983
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0194394514 -0.0721387342 -0.0344212465
+ vertex -0.0140070468 -0.0764443204 -0.0390844345
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0194394514 -0.0721387342 -0.0344212465
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00884837657 -0.0709709451 -0.0369242877
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ vertex 0.0122685954 -0.12224935 -0.0389004983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00884837657 -0.0709709451 -0.0369242877
+ vertex 0.0122685954 -0.12224935 -0.0389004983
+ vertex 0.0102642374 -0.127630726 -0.0405962504
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00884837657 -0.0709709451 -0.0369242877
+ vertex 0.0102642374 -0.127630726 -0.0405962504
+ vertex 0.00793453213 -0.125224873 -0.0420319252
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00884837657 -0.0709709451 -0.0369242877
+ vertex 0.00793453213 -0.125224873 -0.0420319252
+ vertex 0.00419739075 -0.0827994943 -0.0402534939
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00884837657 -0.0709709451 -0.0369242877
+ vertex 0.00419739075 -0.0827994943 -0.0402534939
+ vertex 0.00396833802 -0.0550836511 -0.0369117446
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00884837657 -0.0709709451 -0.0369242877
+ vertex 0.00396833802 -0.0550836511 -0.0369117446
+ vertex 0.0105751529 -4.32133662e-10 -0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00884837657 -0.0709709451 -0.0369242877
+ vertex 0.0105751529 -4.32133662e-10 -0.0237521827
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0150081459 -0.13048014 -0.0119399633
+ vertex 0.0118030375 -0.13570255 0.0262240786
+ vertex 0.0118844798 -0.1352534 -0.0126531059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0150081459 -0.13048014 -0.0119399633
+ vertex 0.0118844798 -0.1352534 -0.0126531059
+ vertex 0.011908954 -0.133186683 -0.0316933468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0150081459 -0.13048014 -0.0119399633
+ vertex 0.011908954 -0.133186683 -0.0316933468
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.009664963 -0.0640965328 0.0344437957
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ vertex 0.0190336388 -0.00809999928 0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.009664963 -0.0640965328 0.0344437957
+ vertex 0.0190336388 -0.00809999928 0.0197099112
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00468235975 -0.123600312 0.0386325717
+ vertex -0.0101149492 -0.124164529 0.0367809236
+ vertex -0.00716353394 -0.128624678 0.0372513905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00468235975 -0.123600312 0.0386325717
+ vertex -0.00716353394 -0.128624678 0.0372513905
+ vertex 0.00691642752 -0.12569502 0.0382629186
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0161695033 -0.0521000028 0.0286835991
+ vertex -0.00896000024 -0.0650000498 0.0366151184
+ vertex -0.0190336388 -0.00809999928 0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0117047932 -0.124387383 0.0304749254
+ vertex -0.0244811159 -0.0695781782 0.00495223841
+ vertex -0.0125433328 -0.124834225 -0.000688163855
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0117047932 -0.124387383 0.0304749254
+ vertex -0.0125433328 -0.124834225 -0.000688163855
+ vertex -0.00650519738 -0.137646362 0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0117047932 -0.124387383 0.0304749254
+ vertex -0.00650519738 -0.137646362 0.0303055886
+ vertex -0.0101149492 -0.124164529 0.0367809236
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0117047932 -0.124387383 0.0304749254
+ vertex -0.0101149492 -0.124164529 0.0367809236
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0117047932 -0.124387383 0.0304749254
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ vertex -0.0244811159 -0.0695781782 0.00495223841
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ vertex 0.0112652676 -0.132724613 0.0330186933
+ vertex 0.0136911394 -0.128477469 0.0313561112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ vertex 0.00691642752 -0.12569502 0.0382629186
+ vertex -0.00716353394 -0.128624678 0.0372513905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ vertex -0.00716353394 -0.128624678 0.0372513905
+ vertex 4.00000536e-05 -0.141044259 0.0304242466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ vertex 0.02669774 -0.00809999928 0.00616365904
+ vertex 0.0250311345 -0.0176656488 0.0111445794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ vertex 0.0250311345 -0.0176656488 0.0111445794
+ vertex 0.0136911394 -0.128477469 0.0313561112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ vertex 0.0162261464 -0.12460582 0.00690309471
+ vertex 0.0150081459 -0.13048014 -0.0119399633
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ vertex 0.0150081459 -0.13048014 -0.0119399633
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 0.0260582734
+ vertex 0.0118030375 -0.13570255 0.0262240786
+ vertex 0.0150081459 -0.13048014 -0.0119399633
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 0.0260582734
+ vertex 0.0150081459 -0.13048014 -0.0119399633
+ vertex 0.0162261464 -0.12460582 0.00690309471
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 0.0260582734
+ vertex 0.0162261464 -0.12460582 0.00690309471
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 0.0260582734
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ vertex 0.0136911394 -0.128477469 0.0313561112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 0.0260582734
+ vertex 0.0136911394 -0.128477469 0.0313561112
+ vertex 0.0112652676 -0.132724613 0.0330186933
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 0.0260582734
+ vertex 0.0112652676 -0.132724613 0.0330186933
+ vertex 0.0118030375 -0.13570255 0.0262240786
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.02669774 -0.00809999928 0.00616365904
+ vertex 0.027383307 -0.00809999928 -0.000956246222
+ vertex 0.0260000005 -4.32133662e-10 5.55111512e-17
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.02669774 -0.00809999928 0.00616365904
+ vertex 0.0260000005 -4.32133662e-10 5.55111512e-17
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.02669774 -0.00809999928 0.00616365904
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ vertex 0.027383307 -0.00809999928 -0.000956246222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.140095204 0.010950001
+ vertex -0.00650519738 -0.137646362 0.0303055886
+ vertex -0.00650519738 -0.137854412 -0.00833936967
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 4.00000536e-05 -0.141044259 0.0304242466
+ vertex -0.00456004171 -0.139590338 0.0303734709
+ vertex -0.00456004171 -0.140095204 0.010950001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 4.00000536e-05 -0.141044259 0.0304242466
+ vertex -0.00456004171 -0.140095204 0.010950001
+ vertex -0.00207098434 -0.140547872 -0.0164915081
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 4.00000536e-05 -0.141044259 0.0304242466
+ vertex -0.00207098434 -0.140547872 -0.0164915081
+ vertex 0.000540000095 -0.141550004 0.00435000053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0107648969 -0.101644546 0.0370954052
+ vertex -0.00896000024 -0.0650000498 0.0366151184
+ vertex -0.0161695033 -0.0521000028 0.0286835991
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0107648969 -0.101644546 0.0370954052
+ vertex -0.0201005768 -0.0531000048 0.0238450337
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0107648969 -0.101644546 0.0370954052
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ vertex -0.0101149492 -0.124164529 0.0367809236
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0107648969 -0.101644546 0.0370954052
+ vertex -0.0101149492 -0.124164529 0.0367809236
+ vertex -0.00468235975 -0.123600312 0.0386325717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312220678 -0.120272629 -0.0427364185
+ vertex -0.00578141259 -0.126041174 -0.0416803807
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312220678 -0.120272629 -0.0427364185
+ vertex -0.00924593396 -0.12188343 -0.0407302305
+ vertex -0.00926867872 -0.0801111758 -0.0412325785
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00926867872 -0.0801111758 -0.0412325785
+ vertex 0.00419739075 -0.0827994943 -0.0402534939
+ vertex 0.00793453213 -0.125224873 -0.0420319252
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00926867872 -0.0801111758 -0.0412325785
+ vertex 0.00793453213 -0.125224873 -0.0420319252
+ vertex -0.00312220678 -0.120272629 -0.0427364185
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312220678 -0.120272629 -0.0427364185
+ vertex 0.00793453213 -0.125224873 -0.0420319252
+ vertex -0.00578141259 -0.126041174 -0.0416803807
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.02669774 -0.00809999928 -0.00616365904
+ vertex -0.0260000005 -4.32133662e-10 -1.38777878e-17
+ vertex -0.0241067782 -4.32133662e-10 -0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.02669774 -0.00809999928 -0.00616365904
+ vertex -0.0241067782 -4.32133662e-10 -0.00973977149
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ vertex -0.0273340065 -0.0173235666 0.00190073461
+ vertex -0.0274 -0.00809999928 1.16598398e-12
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ vertex -0.0274 -0.00809999928 1.16598398e-12
+ vertex -0.02669774 -0.00809999928 -0.00616365904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0118844798 -0.1352534 -0.0126531059
+ vertex 0.0118030375 -0.13570255 0.0262240786
+ vertex 0.00207073404 -0.140739962 0.0304136146
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0118844798 -0.1352534 -0.0126531059
+ vertex 0.00207073404 -0.140739962 0.0304136146
+ vertex 0.000540000095 -0.141550004 0.00435000053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0118844798 -0.1352534 -0.0126531059
+ vertex 0.000540000095 -0.141550004 0.00435000053
+ vertex 0.00207073404 -0.140526965 -0.0164904129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000540000095 -0.141550004 0.00435000053
+ vertex -0.00207098434 -0.140547872 -0.0164915081
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000540000095 -0.141550004 0.00435000053
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ vertex 0.00207073404 -0.140526965 -0.0164904129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 0.0383646116
+ vertex -0.00234867237 -0.0606266819 0.0370310843
+ vertex -0.00896000024 -0.0650000498 0.0366151184
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 0.0383646116
+ vertex -0.00896000024 -0.0650000498 0.0366151184
+ vertex -0.0107648969 -0.101644546 0.0370954052
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 0.0383646116
+ vertex -0.0107648969 -0.101644546 0.0370954052
+ vertex -0.00468235975 -0.123600312 0.0386325717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 0.0383646116
+ vertex -0.00468235975 -0.123600312 0.0386325717
+ vertex 0.00691642752 -0.12569502 0.0382629186
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 0.0383646116
+ vertex 0.00691642752 -0.12569502 0.0382629186
+ vertex 0.00479329983 -0.0740510002 0.0372099876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 0.0383646116
+ vertex 0.00479329983 -0.0740510002 0.0372099876
+ vertex 0.00376458443 -0.0579354391 0.0357277319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 0.0383646116
+ vertex 0.00376458443 -0.0579354391 0.0357277319
+ vertex -0.00234867237 -0.0606266819 0.0370310843
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00969933067 -0.0557453819 -0.0384127125
+ vertex -0.00926867872 -0.0801111758 -0.0412325785
+ vertex -0.0140070468 -0.0764443204 -0.0390844345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00969933067 -0.0557453819 -0.0384127125
+ vertex -0.0140070468 -0.0764443204 -0.0390844345
+ vertex -0.015752852 -0.0586207621 -0.0366881713
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140070468 -0.0764443204 -0.0390844345
+ vertex -0.0194394514 -0.0721387342 -0.0344212465
+ vertex -0.0192147028 -0.0557070896 -0.0333674178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140070468 -0.0764443204 -0.0390844345
+ vertex -0.0192147028 -0.0557070896 -0.0333674178
+ vertex -0.015752852 -0.0586207621 -0.0366881713
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.015752852 -0.0586207621 -0.0366881713
+ vertex -0.0192147028 -0.0557070896 -0.0333674178
+ vertex -0.0187028348 -4.32133662e-10 -0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.015752852 -0.0586207621 -0.0366881713
+ vertex -0.0187028348 -4.32133662e-10 -0.0180611182
+ vertex -0.0105751529 -4.32133662e-10 -0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.015752852 -0.0586207621 -0.0366881713
+ vertex -0.0105751529 -4.32133662e-10 -0.0237521827
+ vertex -0.00969933067 -0.0557453819 -0.0384127125
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0250311345 -0.0176656488 0.0111445794
+ vertex 0.02669774 -0.00809999928 0.00616365904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.02669774 -0.00809999928 0.00616365904
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ vertex 0.0190336388 -0.00809999928 0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0190336388 -0.00809999928 0.0197099112
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0216429979 -0.0626868457 -0.0306501053
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ vertex -0.02669774 -0.00809999928 -0.00616365904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0216429979 -0.0626868457 -0.0306501053
+ vertex -0.02669774 -0.00809999928 -0.00616365904
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0216429979 -0.0626868457 -0.0306501053
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ vertex -0.0192147028 -0.0557070896 -0.0333674178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0216429979 -0.0626868457 -0.0306501053
+ vertex -0.0192147028 -0.0557070896 -0.0333674178
+ vertex -0.0194394514 -0.0721387342 -0.0344212465
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0216429979 -0.0626868457 -0.0306501053
+ vertex -0.0194394514 -0.0721387342 -0.0344212465
+ vertex -0.0219425522 -0.0723681003 -0.0289502181
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ vertex -0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0241067782 -4.32133662e-10 0.00973977149
+ vertex -0.0260000005 -4.32133662e-10 -1.38777878e-17
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0146485306 -0.0976632088 0.0313057005
+ vertex 0.0136911394 -0.128477469 0.0313561112
+ vertex 0.0250311345 -0.0176656488 0.0111445794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0146485306 -0.0976632088 0.0313057005
+ vertex 0.0250311345 -0.0176656488 0.0111445794
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0146485306 -0.0976632088 0.0313057005
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0265060496 -0.0163604673 -0.00694184285
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0265060496 -0.0163604673 -0.00694184285
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.027383307 -0.00809999928 -0.000956246222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0265060496 -0.0163604673 -0.00694184285
+ vertex 0.027383307 -0.00809999928 -0.000956246222
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0265060496 -0.0163604673 -0.00694184285
+ vertex 0.0262385644 -0.027397478 0.00503142551
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.137647942 -0.035746336
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ vertex -0.00207098434 -0.140547872 -0.0164915081
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.137647942 -0.035746336
+ vertex -0.00207098434 -0.140547872 -0.0164915081
+ vertex -0.00456004171 -0.140095204 0.010950001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.137647942 -0.035746336
+ vertex -0.00456004171 -0.140095204 0.010950001
+ vertex -0.00650519738 -0.137854412 -0.00833936967
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.137647942 -0.035746336
+ vertex -0.00650519738 -0.137854412 -0.00833936967
+ vertex -0.00650519738 -0.135713443 -0.0355430096
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.137647942 -0.035746336
+ vertex -0.00650519738 -0.135713443 -0.0355430096
+ vertex -0.00578141259 -0.126041174 -0.0416803807
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.137647942 -0.035746336
+ vertex -0.00578141259 -0.126041174 -0.0416803807
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 0.0303734709
+ vertex -0.00650519738 -0.137646362 0.0303055886
+ vertex -0.00456004171 -0.140095204 0.010950001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 0.0303734709
+ vertex 4.00000536e-05 -0.141044259 0.0304242466
+ vertex -0.00716353394 -0.128624678 0.0372513905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 0.0303734709
+ vertex -0.00716353394 -0.128624678 0.0372513905
+ vertex -0.00650519738 -0.137646362 0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.138791963 -0.0358665772
+ vertex 0.0109475097 -0.130095139 -0.038542293
+ vertex 0.011908954 -0.133186683 -0.0316933468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.011908954 -0.133186683 -0.0316933468
+ vertex 0.0118844798 -0.1352534 -0.0126531059
+ vertex 0.00207073404 -0.140526965 -0.0164904129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.011908954 -0.133186683 -0.0316933468
+ vertex 0.00207073404 -0.140526965 -0.0164904129
+ vertex 0.00207073404 -0.138791963 -0.0358665772
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.138791963 -0.0358665772
+ vertex 0.00207073404 -0.140526965 -0.0164904129
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102642374 -0.127630726 -0.0405962504
+ vertex 0.0122685954 -0.12224935 -0.0389004983
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102642374 -0.127630726 -0.0405962504
+ vertex 0.0143548204 -0.127449095 -0.0345514566
+ vertex 0.0109475097 -0.130095139 -0.038542293
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102642374 -0.127630726 -0.0405962504
+ vertex 0.0109475097 -0.130095139 -0.038542293
+ vertex 0.00207073404 -0.138791963 -0.0358665772
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102642374 -0.127630726 -0.0405962504
+ vertex 0.00207073404 -0.138791963 -0.0358665772
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102642374 -0.127630726 -0.0405962504
+ vertex 4.00000536e-05 -0.1390948 -0.0358984023
+ vertex 0.00793453213 -0.125224873 -0.0420319252
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 0.0304136146
+ vertex 0.0118030375 -0.13570255 0.0262240786
+ vertex 0.0112652676 -0.132724613 0.0330186933
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 0.0304136146
+ vertex 0.0112652676 -0.132724613 0.0330186933
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 0.0304136146
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ vertex 4.00000536e-05 -0.141044259 0.0304242466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 0.0304136146
+ vertex 4.00000536e-05 -0.141044259 0.0304242466
+ vertex 0.000540000095 -0.141550004 0.00435000053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0201005768 -0.0531000048 0.0238450337
+ vertex -0.0107648969 -0.101644546 0.0370954052
+ vertex -0.0161695033 -0.0521000028 0.0286835991
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0201005768 -0.0531000048 0.0238450337
+ vertex -0.0161695033 -0.0521000028 0.0286835991
+ vertex -0.0190336388 -0.00809999928 0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0201005768 -0.0531000048 0.0238450337
+ vertex -0.0190336388 -0.00809999928 0.0197099112
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0201005768 -0.0531000048 0.0238450337
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ vertex -0.0207397547 -0.0680999979 0.0225905795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0119340783 -0.122804232 0.0347546414
+ vertex 0.0136911394 -0.128477469 0.0313561112
+ vertex 0.0146485306 -0.0976632088 0.0313057005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0119340783 -0.122804232 0.0347546414
+ vertex 0.0146485306 -0.0976632088 0.0313057005
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ vertex 0.00691642752 -0.12569502 0.0382629186
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0118619818 -0.0842017457 0.0344196782
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ vertex 0.0119340783 -0.122804232 0.0347546414
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0119340783 -0.122804232 0.0347546414
+ vertex 0.00912100729 -0.129655525 0.0367581472
+ vertex 0.0136911394 -0.128477469 0.0313561112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00376458443 -0.0579354391 0.0357277319
+ vertex 0.00479329983 -0.0740510002 0.0372099876
+ vertex 0.009664963 -0.0640965328 0.0344437957
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00376458443 -0.0579354391 0.0357277319
+ vertex 0.009664963 -0.0640965328 0.0344437957
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00376458443 -0.0579354391 0.0357277319
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0.000907386828 -4.32133662e-10 0.0259841606
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00376458443 -0.0579354391 0.0357277319
+ vertex 0.000907386828 -4.32133662e-10 0.0259841606
+ vertex -0.00234867237 -0.0606266819 0.0370310843
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0274 -0.00809999928 1.16598398e-12
+ vertex -0.0273340065 -0.0173235666 0.00190073461
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0274 -0.00809999928 1.16598398e-12
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0260000005 -4.32133662e-10 -1.38777878e-17
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0274 -0.00809999928 1.16598398e-12
+ vertex -0.0260000005 -4.32133662e-10 -1.38777878e-17
+ vertex -0.02669774 -0.00809999928 -0.00616365904
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link11_L.STL b/assets/inspire_hand/meshes/Link11_L.STL
new file mode 100644
index 0000000..9933a6c
Binary files /dev/null and b/assets/inspire_hand/meshes/Link11_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link11_L.STL.convex.stl b/assets/inspire_hand/meshes/Link11_L.STL.convex.stl
new file mode 100644
index 0000000..2b614e9
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link11_L.STL.convex.stl
@@ -0,0 +1,354 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex -0.0034187967 -0.00834355317 -0.0139000015
+ vertex -0.00586737599 -0.00661021611 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex -0.00586737599 -0.00661021611 -0.0139000015
+ vertex -0.00617566239 -0.000897735415 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex -0.00617566239 -0.000897735415 -0.0139000015
+ vertex -0.00410403404 0.00264112325 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex -0.00410403404 0.00264112325 -0.0139000015
+ vertex 0.000184911041 0.00485059852 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex 0.000184911041 0.00485059852 -0.0139000015
+ vertex 0.0103229769 0.00658453628 -0.0137637034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex 0.0103229769 0.00658453628 -0.0137637034
+ vertex 0.0119245276 -0.00277949241 -0.0137637034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0125521189 -0.00267215422 0.0013271413
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ vertex 0.00968639739 -0.00316228531 0.00293946848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00644383626 -0.003635498 -0.00239999988
+ vertex -0.00586737599 -0.00661021611 -0.00239999988
+ vertex 0.00968639739 -0.00316228531 0.00293946848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00644383626 -0.003635498 -0.00239999988
+ vertex 0.00968639739 -0.00316228531 0.00293946848
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00644383626 -0.003635498 -0.00239999988
+ vertex -0.00617566239 -0.000897735415 -0.0139000015
+ vertex -0.00644383626 -0.003635498 -0.00590000022
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00586737599 -0.00661021611 -0.0139000015
+ vertex -0.00644383626 -0.003635498 -0.00590000022
+ vertex -0.00617566239 -0.000897735415 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00586737599 -0.00661021611 -0.0139000015
+ vertex -0.0034187967 -0.00834355317 -0.0139000015
+ vertex -0.00418250822 -0.00817011949 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0112613048 0.00674502039 0.000513367006
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ vertex 0.0125521189 -0.00267215422 0.0013271413
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.00239999988
+ vertex 0.0125521189 -0.00267215422 0.0013271413
+ vertex 0.00968639739 -0.00316228531 0.00293946848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.00239999988
+ vertex 0.00968639739 -0.00316228531 0.00293946848
+ vertex -0.00418250822 -0.00817011949 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.00239999988
+ vertex -0.00418250822 -0.00817011949 -0.00239999988
+ vertex -0.0034187967 -0.00834355317 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000184911041 0.00485059852 -0.0139000015
+ vertex -0.00410403404 0.00264112325 -0.0139000015
+ vertex -0.00410403404 0.00264112325 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000184911041 0.00485059852 -0.0139000015
+ vertex -0.00410403404 0.00264112325 -0.00239999988
+ vertex -0.000551194127 0.0046886811 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000551194127 0.0046886811 -0.00239999988
+ vertex -0.00410403404 0.00264112325 -0.00239999988
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex 0.0127170384 0.00699399831 -0.0119000003
+ vertex 0.0103229769 0.00658453628 -0.0137637034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex 0.0103229769 0.00658453628 -0.0137637034
+ vertex 0.000184911041 0.00485059852 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex 0.000184911041 0.00485059852 -0.0139000015
+ vertex -0.000551194127 0.0046886811 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex -0.000551194127 0.0046886811 -0.00239999988
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ vertex 0.0112613048 0.00674502039 0.000513367006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex 0.0112613048 0.00674502039 0.000513367006
+ vertex 0.0125521189 -0.00267215422 0.0013271413
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex 0.0125521189 -0.00267215422 0.0013271413
+ vertex 0.0148468185 -0.00227968604 -0.00989999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132452659 0.00708434219 -0.00889999978
+ vertex 0.0148468185 -0.00227968604 -0.00989999995
+ vertex 0.0127170384 0.00699399831 -0.0119000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00586737599 -0.00661021611 -0.00239999988
+ vertex -0.00644383626 -0.003635498 -0.00239999988
+ vertex -0.00644383626 -0.003635498 -0.00590000022
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00586737599 -0.00661021611 -0.00239999988
+ vertex -0.00644383626 -0.003635498 -0.00590000022
+ vertex -0.00586737599 -0.00661021611 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00586737599 -0.00661021611 -0.00239999988
+ vertex -0.00586737599 -0.00661021611 -0.0139000015
+ vertex -0.00418250822 -0.00817011949 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00586737599 -0.00661021611 -0.00239999988
+ vertex -0.00418250822 -0.00817011949 -0.00239999988
+ vertex 0.00968639739 -0.00316228531 0.00293946848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0143185901 -0.00237003039 -0.0119000003
+ vertex 0.0119245276 -0.00277949241 -0.0137637034
+ vertex 0.0103229769 0.00658453628 -0.0137637034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0143185901 -0.00237003039 -0.0119000003
+ vertex 0.0103229769 0.00658453628 -0.0137637034
+ vertex 0.0127170384 0.00699399831 -0.0119000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0143185901 -0.00237003039 -0.0119000003
+ vertex 0.0127170384 0.00699399831 -0.0119000003
+ vertex 0.0148468185 -0.00227968604 -0.00989999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex 0.0119245276 -0.00277949241 -0.0137637034
+ vertex 0.0143185901 -0.00237003039 -0.0119000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex 0.0143185901 -0.00237003039 -0.0119000003
+ vertex 0.0148468185 -0.00227968604 -0.00989999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex 0.0148468185 -0.00227968604 -0.00989999995
+ vertex 0.0125521189 -0.00267215422 0.0013271413
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex 0.0125521189 -0.00267215422 0.0013271413
+ vertex 0.000320842082 -0.00780766038 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000320842082 -0.00780766038 -0.0139000015
+ vertex 0.000320842082 -0.00780766038 -0.00239999988
+ vertex -0.0034187967 -0.00834355317 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00569342636 0.00039588529 -0.00239999988
+ vertex -0.00617566239 -0.000897735415 -0.0139000015
+ vertex -0.00644383626 -0.003635498 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00569342636 0.00039588529 -0.00239999988
+ vertex -0.00644383626 -0.003635498 -0.00239999988
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00569342636 0.00039588529 -0.00239999988
+ vertex 0.00894162059 0.0063482793 0.0028615233
+ vertex -0.00410403404 0.00264112325 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00569342636 0.00039588529 -0.00239999988
+ vertex -0.00410403404 0.00264112325 -0.00239999988
+ vertex -0.00410403404 0.00264112325 -0.0139000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00569342636 0.00039588529 -0.00239999988
+ vertex -0.00410403404 0.00264112325 -0.0139000015
+ vertex -0.00617566239 -0.000897735415 -0.0139000015
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link11_R.STL b/assets/inspire_hand/meshes/Link11_R.STL
new file mode 100644
index 0000000..30817a8
Binary files /dev/null and b/assets/inspire_hand/meshes/Link11_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link11_R.STL.convex.stl b/assets/inspire_hand/meshes/Link11_R.STL.convex.stl
new file mode 100644
index 0000000..c4b9bf9
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link11_R.STL.convex.stl
@@ -0,0 +1,306 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex -0.0122268833 0.00850073155 -0.0112852762
+ vertex -0.012251948 0.00850801729 -0.00847933069
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex -0.012251948 0.00850801729 -0.00847933069
+ vertex -0.0101222722 0.00788896065 0.000977141317
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex -0.0101222722 0.00788896065 0.000977141317
+ vertex -0.00733049354 0.00707744341 0.00258946838
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex -0.00733049354 0.00707744341 0.00258946838
+ vertex 0.00231353962 0.0039788289 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex 0.00231353962 0.0039788289 -0.00274999999
+ vertex 0.00231353962 0.0039788289 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0121625876 -0.00141117361 -0.0141137028
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex 0.00231353962 0.0039788289 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0121625876 -0.00141117361 -0.0141137028
+ vertex 0.00231353962 0.0039788289 -0.01425
+ vertex 0.00514358236 0.00101133483 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0121625876 -0.00141117361 -0.0141137028
+ vertex 0.00514358236 0.00101133483 -0.01425
+ vertex 0.00613157591 -0.00296849385 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0121625876 -0.00141117361 -0.0141137028
+ vertex 0.00613157591 -0.00296849385 -0.01425
+ vertex 0.00508103101 -0.0072321631 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0121625876 -0.00141117361 -0.0141137028
+ vertex 0.00508103101 -0.0072321631 -0.01425
+ vertex 0.0016777761 -0.00855847914 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00539592188 -0.00651510013 -0.00274999999
+ vertex 0.00613157591 -0.00296849385 -0.01425
+ vertex 0.0057016327 -0.000251434773 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00539592188 -0.00651510013 -0.00274999999
+ vertex 0.0057016327 -0.000251434773 -0.00274999999
+ vertex -0.00733049354 0.00707744341 0.00258946838
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101222722 0.00788896065 0.000977141317
+ vertex -0.0115989745 -0.00157500547 0.00219807634
+ vertex -0.00733049354 0.00707744341 0.00258946838
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00508103101 -0.0072321631 -0.01425
+ vertex 0.00613157591 -0.00296849385 -0.01425
+ vertex 0.00539592188 -0.00651510013 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00508103101 -0.0072321631 -0.01425
+ vertex 0.00539592188 -0.00651510013 -0.00274999999
+ vertex 0.00245190575 -0.00867705047 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00508103101 -0.0072321631 -0.01425
+ vertex 0.00245190575 -0.00867705047 -0.00274999999
+ vertex 0.0016777761 -0.00855847914 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00231353962 0.0039788289 -0.00274999999
+ vertex -0.00733049354 0.00707744341 0.00258946838
+ vertex 0.0057016327 -0.000251434773 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0144948773 -0.000733221415 -0.0122499997
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex -0.0121625876 -0.00141117361 -0.0141137028
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0144948773 -0.000733221415 -0.0122499997
+ vertex -0.0121625876 -0.00141117361 -0.0141137028
+ vertex 0.0016777761 -0.00855847914 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00514358236 0.00101133483 -0.01425
+ vertex 0.00231353962 0.0039788289 -0.01425
+ vertex 0.00231353962 0.0039788289 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00514358236 0.00101133483 -0.01425
+ vertex 0.00231353962 0.0039788289 -0.00274999999
+ vertex 0.0057016327 -0.000251434773 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00514358236 0.00101133483 -0.01425
+ vertex 0.0057016327 -0.000251434773 -0.00274999999
+ vertex 0.00613157591 -0.00296849385 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0122268833 0.00850073155 -0.0112852762
+ vertex -0.0104372548 0.00798051991 -0.0137141012
+ vertex -0.0144948773 -0.000733221415 -0.0122499997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0122268833 0.00850073155 -0.0112852762
+ vertex -0.0144948773 -0.000733221415 -0.0122499997
+ vertex -0.0150094749 -0.000583637215 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0122268833 0.00850073155 -0.0112852762
+ vertex -0.0150094749 -0.000583637215 -0.00925000012
+ vertex -0.012251948 0.00850801729 -0.00847933069
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00915903505 -0.00228424976 0.0024259272
+ vertex 0.00245190575 -0.00867705047 -0.00274999999
+ vertex 0.00539592188 -0.00651510013 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00915903505 -0.00228424976 0.0024259272
+ vertex 0.00539592188 -0.00651510013 -0.00274999999
+ vertex -0.00733049354 0.00707744341 0.00258946838
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00915903505 -0.00228424976 0.0024259272
+ vertex -0.00733049354 0.00707744341 0.00258946838
+ vertex -0.0115989745 -0.00157500547 0.00219807634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0130767059 -0.0011454568 0.000163367033
+ vertex -0.0115989745 -0.00157500547 0.00219807634
+ vertex -0.0101222722 0.00788896065 0.000977141317
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101222722 0.00788896065 0.000977141317
+ vertex -0.012251948 0.00850801729 -0.00847933069
+ vertex -0.0150094749 -0.000583637215 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101222722 0.00788896065 0.000977141317
+ vertex -0.0150094749 -0.000583637215 -0.00925000012
+ vertex -0.0130767059 -0.0011454568 0.000163367033
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00120298541 -0.00772109628 -0.00274999999
+ vertex 0.00245190575 -0.00867705047 -0.00274999999
+ vertex -0.00915903505 -0.00228424976 0.0024259272
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00120298541 -0.00772109628 -0.00274999999
+ vertex -0.00915903505 -0.00228424976 0.0024259272
+ vertex -0.0115989745 -0.00157500547 0.00219807634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00120298541 -0.00772109628 -0.00274999999
+ vertex -0.0115989745 -0.00157500547 0.00219807634
+ vertex -0.0130767059 -0.0011454568 0.000163367033
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00120298541 -0.00772109628 -0.00274999999
+ vertex -0.0130767059 -0.0011454568 0.000163367033
+ vertex -0.0150094749 -0.000583637215 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00120298541 -0.00772109628 -0.00274999999
+ vertex -0.0150094749 -0.000583637215 -0.00925000012
+ vertex -0.0144948773 -0.000733221415 -0.0122499997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00120298541 -0.00772109628 -0.00274999999
+ vertex -0.0144948773 -0.000733221415 -0.0122499997
+ vertex 0.0016777761 -0.00855847914 -0.01425
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00120298541 -0.00772109628 -0.00274999999
+ vertex 0.0016777761 -0.00855847914 -0.01425
+ vertex 0.00245190575 -0.00867705047 -0.00274999999
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link12_L.STL b/assets/inspire_hand/meshes/Link12_L.STL
new file mode 100644
index 0000000..08071d3
Binary files /dev/null and b/assets/inspire_hand/meshes/Link12_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link12_L.STL.convex.stl b/assets/inspire_hand/meshes/Link12_L.STL.convex.stl
new file mode 100644
index 0000000..c3908b1
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link12_L.STL.convex.stl
@@ -0,0 +1,802 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ vertex -0.000944086467 -0.0178504046 -0.00800000038
+ vertex -0.00125287706 -0.0161745716 -0.00268379832
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ vertex -0.00125287706 -0.0161745716 -0.00268379832
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ vertex -0.00369759114 0.000157288829 -0.0158090685
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0587727875 -0.0249389615 -0.0129669309
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ vertex 0.0300528537 -0.0363949016 -0.00370239769
+ vertex 0.0366866067 -0.0390286148 -0.0118782828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ vertex 0.0366866067 -0.0390286148 -0.0118782828
+ vertex 0.038939625 -0.0387066342 -0.0140485372
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ vertex 0.038939625 -0.0387066342 -0.0140485372
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ vertex 0.0449747592 -0.0382568054 -0.00524999993
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246703 -0.0377887599 -0.00274999999
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ vertex 0.038556084 -0.0347322114 0.000708622334
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246703 -0.0377887599 -0.00274999999
+ vertex 0.038556084 -0.0347322114 0.000708622334
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246703 -0.0377887599 -0.00274999999
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ vertex 0.0449747592 -0.0382568054 -0.00524999993
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246703 -0.0377887599 -0.00274999999
+ vertex 0.0449747592 -0.0382568054 -0.00524999993
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ vertex 0.0587727875 -0.0249389615 -0.0129669309
+ vertex 0.0597232096 -0.0241596848 -0.0080001587
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ vertex 0.0597232096 -0.0241596848 -0.0080001587
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ vertex 0.0463246703 -0.0377887599 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.043582473 -0.0133989612 -0.000415016053
+ vertex 0.0022329858 0.00815676525 0.000276454171
+ vertex 0.0419684686 -0.0220694635 0.0013211047
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0549617745 -0.0185450427 -0.0118389707
+ vertex 0.0587727875 -0.0249389615 -0.0129669309
+ vertex 0.0475613885 -0.0173089895 -0.0156070692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0549617745 -0.0185450427 -0.0118389707
+ vertex 0.0451193266 -0.0106000351 -0.0124442028
+ vertex 0.0514556989 -0.0154607352 -0.00387924421
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0549617745 -0.0185450427 -0.0118389707
+ vertex 0.0597232096 -0.0241596848 -0.0080001587
+ vertex 0.0587727875 -0.0249389615 -0.0129669309
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ vertex -0.00148780027 -0.00483932812 -0.016804276
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ vertex 0.0403454229 -0.0248590484 -0.0176166371
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403454229 -0.0248590484 -0.0176166371
+ vertex 0.00118220644 0.00757891079 -0.0164638422
+ vertex 0.0475613885 -0.0173089895 -0.0156070692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403454229 -0.0248590484 -0.0176166371
+ vertex 0.0475613885 -0.0173089895 -0.0156070692
+ vertex 0.0587727875 -0.0249389615 -0.0129669309
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403454229 -0.0248590484 -0.0176166371
+ vertex 0.0587727875 -0.0249389615 -0.0129669309
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.038939625 -0.0387066342 -0.0140485372
+ vertex 0.0366866067 -0.0390286148 -0.0118782828
+ vertex 0.0279816389 -0.0351464711 -0.0129533736
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.038939625 -0.0387066342 -0.0140485372
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ vertex 0.0463246703 -0.0377887599 -0.0132499998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ vertex 0.00118220644 0.00757891079 -0.0164638422
+ vertex 0.0403454229 -0.0248590484 -0.0176166371
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ vertex -0.00369759114 0.000157288829 -0.0158090685
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000647108303 -0.0125640538 -0.000612358155
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ vertex -0.00125287706 -0.0161745716 -0.00268379832
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0243701637 -0.0317206345 -0.00149137573
+ vertex 0.0300528537 -0.0363949016 -0.00370239769
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0243701637 -0.0317206345 -0.00149137573
+ vertex 0.038985759 -0.0389309861 -0.00222051237
+ vertex 0.038556084 -0.0347322114 0.000708622334
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0243701637 -0.0317206345 -0.00149137573
+ vertex 0.038556084 -0.0347322114 0.000708622334
+ vertex -0.000647108303 -0.0125640538 -0.000612358155
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0243701637 -0.0317206345 -0.00149137573
+ vertex -0.000647108303 -0.0125640538 -0.000612358155
+ vertex -0.00125287706 -0.0161745716 -0.00268379832
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00206399104 0.00455146888 -0.000118971424
+ vertex 0.0022329858 0.00815676525 0.000276454171
+ vertex 0.00118220644 0.00757891079 -0.0164638422
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00206399104 0.00455146888 -0.000118971424
+ vertex 0.00118220644 0.00757891079 -0.0164638422
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00206399104 0.00455146888 -0.000118971424
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00591362314 0.0103434622 -0.00800000038
+ vertex 0.00118220644 0.00757891079 -0.0164638422
+ vertex 0.0022329858 0.00815676525 0.000276454171
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00591362314 0.0103434622 -0.00800000038
+ vertex 0.0110037131 0.0108430805 -0.00312744267
+ vertex 0.0108220866 0.0108270971 -0.0130623132
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0397079028 -0.00877458788 -0.0146957589
+ vertex 0.0108220866 0.0108270971 -0.0130623132
+ vertex 0.0451193266 -0.0106000351 -0.0124442028
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0397079028 -0.00877458788 -0.0146957589
+ vertex 0.0451193266 -0.0106000351 -0.0124442028
+ vertex 0.0549617745 -0.0185450427 -0.0118389707
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0397079028 -0.00877458788 -0.0146957589
+ vertex 0.0549617745 -0.0185450427 -0.0118389707
+ vertex 0.0475613885 -0.0173089895 -0.0156070692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00125287706 -0.0161745716 -0.00268379832
+ vertex -0.000944086467 -0.0178504046 -0.00800000038
+ vertex 0.0113675324 -0.0264426414 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00125287706 -0.0161745716 -0.00268379832
+ vertex 0.0113675324 -0.0264426414 -0.00800000038
+ vertex 0.0165896807 -0.0291688778 -0.00392314419
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0165896807 -0.0291688778 -0.00392314419
+ vertex 0.0300528537 -0.0363949016 -0.00370239769
+ vertex 0.0243701637 -0.0317206345 -0.00149137573
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0165896807 -0.0291688778 -0.00392314419
+ vertex 0.0243701637 -0.0317206345 -0.00149137573
+ vertex -0.00125287706 -0.0161745716 -0.00268379832
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275258422 0.00159642869 -0.00800000038
+ vertex 0.0313934423 -0.00158262462 -0.00309562916
+ vertex 0.0514556989 -0.0154607352 -0.00387924421
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275258422 0.00159642869 -0.00800000038
+ vertex 0.0514556989 -0.0154607352 -0.00387924421
+ vertex 0.0451193266 -0.0106000351 -0.0124442028
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275258422 0.00159642869 -0.00800000038
+ vertex 0.0451193266 -0.0106000351 -0.0124442028
+ vertex 0.0108220866 0.0108270971 -0.0130623132
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275258422 0.00159642869 -0.00800000038
+ vertex 0.0108220866 0.0108270971 -0.0130623132
+ vertex 0.0110037131 0.0108430805 -0.00312744267
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275258422 0.00159642869 -0.00800000038
+ vertex 0.0110037131 0.0108430805 -0.00312744267
+ vertex 0.0313934423 -0.00158262462 -0.00309562916
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ vertex 0.038939625 -0.0387066342 -0.0140485372
+ vertex 0.0279816389 -0.0351464711 -0.0129533736
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ vertex 0.0279816389 -0.0351464711 -0.0129533736
+ vertex 0.0240504984 -0.0300919656 -0.0153093832
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00659456057 0.0101385117 -0.0151668033
+ vertex 0.0108220866 0.0108270971 -0.0130623132
+ vertex 0.0397079028 -0.00877458788 -0.0146957589
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00659456057 0.0101385117 -0.0151668033
+ vertex 0.0397079028 -0.00877458788 -0.0146957589
+ vertex 0.0475613885 -0.0173089895 -0.0156070692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00659456057 0.0101385117 -0.0151668033
+ vertex 0.0475613885 -0.0173089895 -0.0156070692
+ vertex 0.00118220644 0.00757891079 -0.0164638422
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00659456057 0.0101385117 -0.0151668033
+ vertex 0.00118220644 0.00757891079 -0.0164638422
+ vertex 0.00591362314 0.0103434622 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00659456057 0.0101385117 -0.0151668033
+ vertex 0.00591362314 0.0103434622 -0.00800000038
+ vertex 0.0108220866 0.0108270971 -0.0130623132
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110664507 -0.0256833583 -0.0120121539
+ vertex 0.0113675324 -0.0264426414 -0.00800000038
+ vertex -0.000944086467 -0.0178504046 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110664507 -0.0256833583 -0.0120121539
+ vertex -0.000944086467 -0.0178504046 -0.00800000038
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ vertex 0.0240504984 -0.0300919656 -0.0153093832
+ vertex 0.0279816389 -0.0351464711 -0.0129533736
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ vertex 0.0279816389 -0.0351464711 -0.0129533736
+ vertex 0.0110664507 -0.0256833583 -0.0120121539
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.052863922 -0.0188148711 -0.00189987256
+ vertex 0.043582473 -0.0133989612 -0.000415016053
+ vertex 0.0419684686 -0.0220694635 0.0013211047
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.052863922 -0.0188148711 -0.00189987256
+ vertex 0.0419684686 -0.0220694635 0.0013211047
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00621645758 0.00994435139 -0.000695477705
+ vertex 0.0022329858 0.00815676525 0.000276454171
+ vertex 0.043582473 -0.0133989612 -0.000415016053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00621645758 0.00994435139 -0.000695477705
+ vertex 0.043582473 -0.0133989612 -0.000415016053
+ vertex 0.0101587456 0.00891728885 -0.00116847188
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00621645758 0.00994435139 -0.000695477705
+ vertex 0.0101587456 0.00891728885 -0.00116847188
+ vertex 0.0110037131 0.0108430805 -0.00312744267
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00621645758 0.00994435139 -0.000695477705
+ vertex 0.0110037131 0.0108430805 -0.00312744267
+ vertex 0.00591362314 0.0103434622 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00621645758 0.00994435139 -0.000695477705
+ vertex 0.00591362314 0.0103434622 -0.00800000038
+ vertex 0.0022329858 0.00815676525 0.000276454171
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00148780027 -0.00483932812 -0.016804276
+ vertex 0.0385552123 -0.0346003622 -0.0167571697
+ vertex 0.0240504984 -0.0300919656 -0.0153093832
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00148780027 -0.00483932812 -0.016804276
+ vertex 0.0240504984 -0.0300919656 -0.0153093832
+ vertex -0.00113201002 -0.0135255018 -0.0149773499
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00113201002 -0.0135255018 -0.0149773499
+ vertex 0.0240504984 -0.0300919656 -0.0153093832
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00113201002 -0.0135255018 -0.0149773499
+ vertex -0.00129650591 -0.0162051488 -0.0132586677
+ vertex -0.00369759114 0.000157288829 -0.0158090685
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00113201002 -0.0135255018 -0.0149773499
+ vertex -0.00369759114 0.000157288829 -0.0158090685
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00113201002 -0.0135255018 -0.0149773499
+ vertex -0.00346967368 0.00178620487 -0.0169463232
+ vertex -0.00148780027 -0.00483932812 -0.016804276
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252605192 -0.0346496664 -0.00800000038
+ vertex 0.0300528537 -0.0363949016 -0.00370239769
+ vertex 0.0165896807 -0.0291688778 -0.00392314419
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252605192 -0.0346496664 -0.00800000038
+ vertex 0.0165896807 -0.0291688778 -0.00392314419
+ vertex 0.0113675324 -0.0264426414 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252605192 -0.0346496664 -0.00800000038
+ vertex 0.0113675324 -0.0264426414 -0.00800000038
+ vertex 0.0110664507 -0.0256833583 -0.0120121539
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252605192 -0.0346496664 -0.00800000038
+ vertex 0.0110664507 -0.0256833583 -0.0120121539
+ vertex 0.0279816389 -0.0351464711 -0.0129533736
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252605192 -0.0346496664 -0.00800000038
+ vertex 0.0279816389 -0.0351464711 -0.0129533736
+ vertex 0.0366866067 -0.0390286148 -0.0118782828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252605192 -0.0346496664 -0.00800000038
+ vertex 0.0366866067 -0.0390286148 -0.0118782828
+ vertex 0.0300528537 -0.0363949016 -0.00370239769
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0554773659 -0.0190902278 -0.0043225158
+ vertex 0.0597232096 -0.0241596848 -0.0080001587
+ vertex 0.0549617745 -0.0185450427 -0.0118389707
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0554773659 -0.0190902278 -0.0043225158
+ vertex 0.0549617745 -0.0185450427 -0.0118389707
+ vertex 0.0514556989 -0.0154607352 -0.00387924421
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0554773659 -0.0190902278 -0.0043225158
+ vertex 0.0514556989 -0.0154607352 -0.00387924421
+ vertex 0.052863922 -0.0188148711 -0.00189987256
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0554773659 -0.0190902278 -0.0043225158
+ vertex 0.052863922 -0.0188148711 -0.00189987256
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0554773659 -0.0190902278 -0.0043225158
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ vertex 0.0597232096 -0.0241596848 -0.0080001587
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00192932202 0.00445118407 0.000857932842
+ vertex 0.0022329858 0.00815676525 0.000276454171
+ vertex -0.00206399104 0.00455146888 -0.000118971424
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00192932202 0.00445118407 0.000857932842
+ vertex -0.00206399104 0.00455146888 -0.000118971424
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00192932202 0.00445118407 0.000857932842
+ vertex 0.0419684686 -0.0220694635 0.0013211047
+ vertex 0.0022329858 0.00815676525 0.000276454171
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ vertex -0.000647108303 -0.0125640538 -0.000612358155
+ vertex 0.038556084 -0.0347322114 0.000708622334
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ vertex 0.038556084 -0.0347322114 0.000708622334
+ vertex 0.0390611216 -0.0294232871 0.00165800774
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0390611216 -0.0294232871 0.00165800774
+ vertex 0.038556084 -0.0347322114 0.000708622334
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0390611216 -0.0294232871 0.00165800774
+ vertex 0.0587270781 -0.0250065289 -0.00303167757
+ vertex 0.0419684686 -0.0220694635 0.0013211047
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0390611216 -0.0294232871 0.00165800774
+ vertex 0.0419684686 -0.0220694635 0.0013211047
+ vertex -0.00192932202 0.00445118407 0.000857932842
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0390611216 -0.0294232871 0.00165800774
+ vertex -0.00192932202 0.00445118407 0.000857932842
+ vertex -0.00361194648 0.000977804302 0.00075852446
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0446911342 -0.0114113111 -0.00193118036
+ vertex 0.0313934423 -0.00158262462 -0.00309562916
+ vertex 0.0110037131 0.0108430805 -0.00312744267
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0446911342 -0.0114113111 -0.00193118036
+ vertex 0.0110037131 0.0108430805 -0.00312744267
+ vertex 0.0101587456 0.00891728885 -0.00116847188
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0446911342 -0.0114113111 -0.00193118036
+ vertex 0.0101587456 0.00891728885 -0.00116847188
+ vertex 0.043582473 -0.0133989612 -0.000415016053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0446911342 -0.0114113111 -0.00193118036
+ vertex 0.043582473 -0.0133989612 -0.000415016053
+ vertex 0.052863922 -0.0188148711 -0.00189987256
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0446911342 -0.0114113111 -0.00193118036
+ vertex 0.052863922 -0.0188148711 -0.00189987256
+ vertex 0.0514556989 -0.0154607352 -0.00387924421
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0446911342 -0.0114113111 -0.00193118036
+ vertex 0.0514556989 -0.0154607352 -0.00387924421
+ vertex 0.0313934423 -0.00158262462 -0.00309562916
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link12_R.STL b/assets/inspire_hand/meshes/Link12_R.STL
new file mode 100644
index 0000000..137dbde
Binary files /dev/null and b/assets/inspire_hand/meshes/Link12_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link12_R.STL.convex.stl b/assets/inspire_hand/meshes/Link12_R.STL.convex.stl
new file mode 100644
index 0000000..b77a3e3
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link12_R.STL.convex.stl
@@ -0,0 +1,754 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex -0.00369002484 -0.000532748527 -0.000203864271
+ vertex -0.00338406535 0.00146551302 0.000845592876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex -0.00338406535 0.00146551302 0.000845592876
+ vertex -0.00132502557 0.0160559155 -0.0027371191
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex -0.00132502557 0.0160559155 -0.0027371191
+ vertex -0.000944086409 0.0178504046 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex -0.000944086409 0.0178504046 -0.00800000038
+ vertex -0.00138285034 0.0153856613 -0.0139250662
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0587762967 0.0249368995 -0.00303505594
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ vertex 0.0385551453 0.0345796607 0.000764651631
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ vertex 0.0449747555 0.0382568054 -0.0107499994
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ vertex 0.0372769497 0.0390150361 -0.00341521064
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.0132499998
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ vertex 0.038556084 0.0347321518 -0.016708646
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.0132499998
+ vertex 0.038556084 0.0347321518 -0.016708646
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.0132499998
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ vertex 0.0449747555 0.0382568054 -0.0107499994
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.0132499998
+ vertex 0.0449747555 0.0382568054 -0.0107499994
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ vertex 0.0587762967 0.0249368995 -0.00303505594
+ vertex 0.0597232096 0.0241596848 -0.00799984112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ vertex 0.0597232096 0.0241596848 -0.00799984112
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ vertex 0.0463246666 0.0377887599 -0.0132499998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0541602969 0.0177621543 -0.0119234342
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ vertex 0.0597232096 0.0241596848 -0.00799984112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0541602969 0.0177621543 -0.0119234342
+ vertex 0.0451193452 0.0106000016 -0.00355592696
+ vertex 0.0404670462 0.00763173169 -0.0130943134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0489069261 0.0177280754 -0.015321088
+ vertex 0.0419684649 0.0220694635 -0.0173211042
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0489069261 0.0177280754 -0.015321088
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ vertex 0.0541602969 0.0177621543 -0.0119234342
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0489069261 0.0177280754 -0.015321088
+ vertex 0.0541602969 0.0177621543 -0.0119234342
+ vertex 0.0404670462 0.00763173169 -0.0130943134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00125045481 0.00490831677 0.000815086474
+ vertex 0.0385551453 0.0345796607 0.000764651631
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0549618006 0.018545026 -0.00416113157
+ vertex 0.0587762967 0.0249368995 -0.00303505594
+ vertex 0.0475613847 0.0173089895 -0.000392930204
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0549618006 0.018545026 -0.00416113157
+ vertex 0.0451193452 0.0106000016 -0.00355592696
+ vertex 0.0541602969 0.0177621543 -0.0119234342
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0549618006 0.018545026 -0.00416113157
+ vertex 0.0541602969 0.0177621543 -0.0119234342
+ vertex 0.0597232096 0.0241596848 -0.00799984112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0549618006 0.018545026 -0.00416113157
+ vertex 0.0597232096 0.0241596848 -0.00799984112
+ vertex 0.0587762967 0.0249368995 -0.00303505594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403360985 0.0248796996 0.00161793025
+ vertex 0.0385551453 0.0345796607 0.000764651631
+ vertex -0.00125045481 0.00490831677 0.000815086474
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403360985 0.0248796996 0.00161793025
+ vertex 0.000918214442 -0.0073946747 0.000328655733
+ vertex 0.00636783149 -0.00988847017 -0.000695490802
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403360985 0.0248796996 0.00161793025
+ vertex 0.00636783149 -0.00988847017 -0.000695490802
+ vertex 0.0475613847 0.0173089895 -0.000392930204
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403360985 0.0248796996 0.00161793025
+ vertex 0.0475613847 0.0173089895 -0.000392930204
+ vertex 0.0587762967 0.0249368995 -0.00303505594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0403360985 0.0248796996 0.00161793025
+ vertex 0.0587762967 0.0249368995 -0.00303505594
+ vertex 0.0385551453 0.0345796607 0.000764651631
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000944086409 0.0178504046 -0.00800000038
+ vertex 0.00971134193 0.0251767542 -0.0107111074
+ vertex -0.00138285034 0.0153856613 -0.0139250662
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000944086409 0.0178504046 -0.00800000038
+ vertex -0.00132502557 0.0160559155 -0.0027371191
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00206399104 -0.00455146888 -0.015881028
+ vertex -0.00202409131 -0.0045184521 -0.0168692134
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00206399104 -0.00455146888 -0.015881028
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ vertex 0.000918214442 -0.0073946747 0.000328655733
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ vertex 0.000918214442 -0.0073946747 0.000328655733
+ vertex 0.0403360985 0.0248796996 0.00161793025
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ vertex -0.00369002484 -0.000532748527 -0.000203864271
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex -0.00202409131 -0.0045184521 -0.0168692134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ vertex -0.00202409131 -0.0045184521 -0.0168692134
+ vertex -0.00206399104 -0.00455146888 -0.015881028
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ vertex -0.00206399104 -0.00455146888 -0.015881028
+ vertex 0.000918214442 -0.0073946747 0.000328655733
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0278518125 0.0336349532 -0.0146128209
+ vertex 0.0300514866 0.0363943689 -0.012297445
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0278518125 0.0336349532 -0.0146128209
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ vertex 0.038556084 0.0347321518 -0.016708646
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0278518125 0.0336349532 -0.0146128209
+ vertex -0.00138285034 0.0153856613 -0.0139250662
+ vertex 0.00971134193 0.0251767542 -0.0107111074
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0278518125 0.0336349532 -0.0146128209
+ vertex 0.00971134193 0.0251767542 -0.0107111074
+ vertex 0.0300514866 0.0363943689 -0.012297445
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00591362314 -0.0103434622 -0.00800000038
+ vertex 0.000918214442 -0.0073946747 0.000328655733
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00591362314 -0.0103434622 -0.00800000038
+ vertex 0.0077118515 -0.0104039367 -0.0147853205
+ vertex 0.0110789239 -0.0108499546 -0.0127844093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00591362314 -0.0103434622 -0.00800000038
+ vertex 0.0110789239 -0.0108499546 -0.0127844093
+ vertex 0.0108520966 -0.0108297039 -0.00296667311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.039731469 0.00879117288 -0.00130356429
+ vertex 0.0108520966 -0.0108297039 -0.00296667311
+ vertex 0.0451193452 0.0106000016 -0.00355592696
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.039731469 0.00879117288 -0.00130356429
+ vertex 0.0451193452 0.0106000016 -0.00355592696
+ vertex 0.0549618006 0.018545026 -0.00416113157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.039731469 0.00879117288 -0.00130356429
+ vertex 0.0549618006 0.018545026 -0.00416113157
+ vertex 0.0475613847 0.0173089895 -0.000392930204
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275254995 -0.00159664499 -0.00800000038
+ vertex 0.0110789239 -0.0108499546 -0.0127844093
+ vertex 0.0404670462 0.00763173169 -0.0130943134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275254995 -0.00159664499 -0.00800000038
+ vertex 0.0404670462 0.00763173169 -0.0130943134
+ vertex 0.0451193452 0.0106000016 -0.00355592696
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275254995 -0.00159664499 -0.00800000038
+ vertex 0.0451193452 0.0106000016 -0.00355592696
+ vertex 0.0108520966 -0.0108297039 -0.00296667311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0275254995 -0.00159664499 -0.00800000038
+ vertex 0.0108520966 -0.0108297039 -0.00296667311
+ vertex 0.0110789239 -0.0108499546 -0.0127844093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0278568976 0.0336375833 -0.00138695969
+ vertex 0.0280355327 0.0354826637 -0.0037283462
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0278568976 0.0336375833 -0.00138695969
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ vertex 0.0385551453 0.0345796607 0.000764651631
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0404670462 0.00763173169 -0.0130943134
+ vertex 0.0110789239 -0.0108499546 -0.0127844093
+ vertex 0.0077118515 -0.0104039367 -0.0147853205
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0404670462 0.00763173169 -0.0130943134
+ vertex 0.0077118515 -0.0104039367 -0.0147853205
+ vertex 0.0236400515 -0.000443518395 -0.0150949154
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ vertex 0.0419684649 0.0220694635 -0.0173211042
+ vertex 0.0489069261 0.0177280754 -0.015321088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ vertex 0.0489069261 0.0177280754 -0.015321088
+ vertex 0.0236400515 -0.000443518395 -0.0150949154
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236400515 -0.000443518395 -0.0150949154
+ vertex 0.0489069261 0.0177280754 -0.015321088
+ vertex 0.0404670462 0.00763173169 -0.0130943134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00636783149 -0.00988847017 -0.000695490802
+ vertex 0.0108520966 -0.0108297039 -0.00296667311
+ vertex 0.039731469 0.00879117288 -0.00130356429
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00636783149 -0.00988847017 -0.000695490802
+ vertex 0.039731469 0.00879117288 -0.00130356429
+ vertex 0.0475613847 0.0173089895 -0.000392930204
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00636783149 -0.00988847017 -0.000695490802
+ vertex 0.000918214442 -0.0073946747 0.000328655733
+ vertex 0.00591362314 -0.0103434622 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00636783149 -0.00988847017 -0.000695490802
+ vertex 0.00591362314 -0.0103434622 -0.00800000038
+ vertex 0.0108520966 -0.0108297039 -0.00296667311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0389296189 0.0386557691 -0.00189383514
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ vertex 0.0372769497 0.0390150361 -0.00341521064
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0389296189 0.0386557691 -0.00189383514
+ vertex 0.0372769497 0.0390150361 -0.00341521064
+ vertex 0.0280355327 0.0354826637 -0.0037283462
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0389296189 0.0386557691 -0.00189383514
+ vertex 0.0280355327 0.0354826637 -0.0037283462
+ vertex 0.0278568976 0.0336375833 -0.00138695969
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0389296189 0.0386557691 -0.00189383514
+ vertex 0.0278568976 0.0336375833 -0.00138695969
+ vertex 0.0385551453 0.0345796607 0.000764651631
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0389296189 0.0386557691 -0.00189383514
+ vertex 0.0385551453 0.0345796607 0.000764651631
+ vertex 0.0463246666 0.0377887599 -0.00274999999
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0147730242 0.0284475405 -0.00528044254
+ vertex 0.0280355327 0.0354826637 -0.0037283462
+ vertex 0.0300514866 0.0363943689 -0.012297445
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0147730242 0.0284475405 -0.00528044254
+ vertex 0.0300514866 0.0363943689 -0.012297445
+ vertex 0.00971134193 0.0251767542 -0.0107111074
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0147730242 0.0284475405 -0.00528044254
+ vertex 0.00971134193 0.0251767542 -0.0107111074
+ vertex -0.000944086409 0.0178504046 -0.00800000038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0147730242 0.0284475405 -0.00528044254
+ vertex -0.000944086409 0.0178504046 -0.00800000038
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0147730242 0.0284475405 -0.00528044254
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ vertex 0.0280355327 0.0354826637 -0.0037283462
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00338406535 0.00146551302 0.000845592876
+ vertex -0.00369002484 -0.000532748527 -0.000203864271
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ vertex 0.0403360985 0.0248796996 0.00161793025
+ vertex -0.00125045481 0.00490831677 0.000815086474
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00315540261 -0.00244195107 0.000928608177
+ vertex -0.00125045481 0.00490831677 0.000815086474
+ vertex -0.00338406535 0.00146551302 0.000845592876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00338406535 0.00146551302 0.000845592876
+ vertex -0.00125045481 0.00490831677 0.000815086474
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00338406535 0.00146551302 0.000845592876
+ vertex 0.000677756499 0.0178687721 -0.00214548828
+ vertex -0.00132502557 0.0160559155 -0.0027371191
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0077118515 -0.0104039367 -0.0147853205
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ vertex 0.0236400515 -0.000443518395 -0.0150949154
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0077118515 -0.0104039367 -0.0147853205
+ vertex 0.00591362314 -0.0103434622 -0.00800000038
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00202409131 -0.0045184521 -0.0168692134
+ vertex 0.0419684649 0.0220694635 -0.0173211042
+ vertex 0.00241828035 -0.00839195866 -0.0162292961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000758886978 0.0123457564 -0.0154223097
+ vertex -0.00138285034 0.0153856613 -0.0139250662
+ vertex 0.0278518125 0.0336349532 -0.0146128209
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000758886978 0.0123457564 -0.0154223097
+ vertex 0.0278518125 0.0336349532 -0.0146128209
+ vertex 0.038556084 0.0347321518 -0.016708646
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000758886978 0.0123457564 -0.0154223097
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex -0.00138285034 0.0153856613 -0.0139250662
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex -0.000758886978 0.0123457564 -0.0154223097
+ vertex 0.038556084 0.0347321518 -0.016708646
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex 0.038556084 0.0347321518 -0.016708646
+ vertex 0.0390611403 0.0294230543 -0.0176580176
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0390611403 0.0294230543 -0.0176580176
+ vertex 0.038556084 0.0347321518 -0.016708646
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0390611403 0.0294230543 -0.0176580176
+ vertex 0.0587265044 0.0250115357 -0.0129659493
+ vertex 0.0419684649 0.0220694635 -0.0173211042
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0419684649 0.0220694635 -0.0173211042
+ vertex -0.00202409131 -0.0045184521 -0.0168692134
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0419684649 0.0220694635 -0.0173211042
+ vertex -0.00362793426 -0.000652820978 -0.016938217
+ vertex 0.0390611403 0.0294230543 -0.0176580176
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0362065658 0.0390213616 -0.0109558506
+ vertex 0.0300514866 0.0363943689 -0.012297445
+ vertex 0.0280355327 0.0354826637 -0.0037283462
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0362065658 0.0390213616 -0.0109558506
+ vertex 0.0280355327 0.0354826637 -0.0037283462
+ vertex 0.0372769497 0.0390150361 -0.00341521064
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0362065658 0.0390213616 -0.0109558506
+ vertex 0.0372769497 0.0390150361 -0.00341521064
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0362065658 0.0390213616 -0.0109558506
+ vertex 0.038985759 0.0389309861 -0.0137794875
+ vertex 0.0300514866 0.0363943689 -0.012297445
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link13_L.STL b/assets/inspire_hand/meshes/Link13_L.STL
new file mode 100644
index 0000000..03a3425
Binary files /dev/null and b/assets/inspire_hand/meshes/Link13_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link13_L.STL.convex.stl b/assets/inspire_hand/meshes/Link13_L.STL.convex.stl
new file mode 100644
index 0000000..cdb22cd
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link13_L.STL.convex.stl
@@ -0,0 +1,514 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954299793 0.00346851116 -0.000116769595
+ vertex -0.00952879526 0.00349948788 -0.0148
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954299793 0.00346851116 -0.000116769595
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ vertex 0.00197924627 -0.00877810735 -0.00719999941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954299793 0.00346851116 -0.000116769595
+ vertex 0.00197924627 -0.00877810735 -0.00719999941
+ vertex -0.00294060563 -0.00362145854 0.000121843914
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520853046 0.0159514118 -0.000468590471
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636306778 0.0155265052 -0.0139314095
+ vertex -0.0122086694 0.011017709 -0.0145997265
+ vertex -0.0122417556 0.0111436844 4.56855414e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636306778 0.0155265052 -0.0139314095
+ vertex -0.0122417556 0.0111436844 4.56855414e-05
+ vertex -0.00520853046 0.0159514118 -0.000468590471
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636306778 0.0155265052 -0.0139314095
+ vertex -0.00520853046 0.0159514118 -0.000468590471
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636306778 0.0155265052 -0.0139314095
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ vertex -0.0122086694 0.011017709 -0.0145997265
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0122417556 0.0111436844 4.56855414e-05
+ vertex -0.0122086694 0.011017709 -0.0145997265
+ vertex -0.00952879526 0.00349948788 -0.0148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0122417556 0.0111436844 4.56855414e-05
+ vertex -0.00952879526 0.00349948788 -0.0148
+ vertex -0.00954299793 0.00346851116 -0.000116769595
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0239881519 -0.00389247201 -0.0132786492
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ vertex 0.0103289252 0.0133193498 -0.011785998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0239881519 -0.00389247201 -0.0132786492
+ vertex 0.0103289252 0.0133193498 -0.011785998
+ vertex 0.0226684213 0.00165674044 -0.011292317
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ vertex 0.0226684213 0.00165674044 -0.011292317
+ vertex 0.0103289252 0.0133193498 -0.011785998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ vertex 0.0103289252 0.0133193498 -0.011785998
+ vertex 0.0109909363 0.0127807539 -0.00266474276
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ vertex 0.0109909363 0.0127807539 -0.00266474276
+ vertex 0.0226867665 0.00173585175 -0.00326977787
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0226867665 0.00173585175 -0.00326977787
+ vertex 0.0109909363 0.0127807539 -0.00266474276
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0226867665 0.00173585175 -0.00326977787
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ vertex 0.0240718275 -0.00358527782 -0.00124900579
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204026955 -0.00829510204 -0.0115155755
+ vertex 0.00197924627 -0.00877810735 -0.00719999941
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204026955 -0.00829510204 -0.0115155755
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ vertex 0.0198158212 -0.0136940712 -0.013746094
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0126133738 -0.012876221 -0.00719476445
+ vertex 0.00197924627 -0.00877810735 -0.00719999941
+ vertex 0.00204026955 -0.00829510204 -0.0115155755
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0126133738 -0.012876221 -0.00719476445
+ vertex 0.00204026955 -0.00829510204 -0.0115155755
+ vertex 0.0198158212 -0.0136940712 -0.013746094
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0126133738 -0.012876221 -0.00719476445
+ vertex 0.0198158212 -0.0136940712 -0.013746094
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 -0.0082951067 -0.00288442057
+ vertex -0.00294060563 -0.00362145854 0.000121843914
+ vertex 0.00197924627 -0.00877810735 -0.00719999941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 -0.0082951067 -0.00288442057
+ vertex 0.00197924627 -0.00877810735 -0.00719999941
+ vertex 0.0126133738 -0.012876221 -0.00719476445
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 -0.0082951067 -0.00288442057
+ vertex 0.0126133738 -0.012876221 -0.00719476445
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 -0.0082951067 -0.00288442057
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ vertex -0.00294060563 -0.00362145854 0.000121843914
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252160393 -0.00136334961 -0.0109543726
+ vertex 0.0239881519 -0.00389247201 -0.0132786492
+ vertex 0.0226684213 0.00165674044 -0.011292317
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252160393 -0.00136334961 -0.0109543726
+ vertex 0.0226684213 0.00165674044 -0.011292317
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252160393 -0.00136334961 -0.0109543726
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252160393 -0.00136334961 -0.0109543726
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ vertex 0.0239881519 -0.00389247201 -0.0132786492
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252181608 -0.00136049103 -0.00345343351
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ vertex 0.0226867665 0.00173585175 -0.00326977787
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252181608 -0.00136049103 -0.00345343351
+ vertex 0.0226867665 0.00173585175 -0.00326977787
+ vertex 0.0240718275 -0.00358527782 -0.00124900579
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252181608 -0.00136049103 -0.00345343351
+ vertex 0.0240718275 -0.00358527782 -0.00124900579
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252181608 -0.00136049103 -0.00345343351
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ vertex 0.0255211797 -0.00114994799 -0.00720000034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ vertex 0.0240718275 -0.00358527782 -0.00124900579
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ vertex 0.00106034789 0.0139854029 0.000899999985
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00106034789 0.0139854029 0.000899999985
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ vertex -0.00520853046 0.0159514118 -0.000468590471
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00106034789 0.0139854029 0.000899999985
+ vertex -0.00520853046 0.0159514118 -0.000468590471
+ vertex -0.0122417556 0.0111436844 4.56855414e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ vertex 0.0225232132 -0.0129914945 0.000107712556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ vertex 0.0225232132 -0.0129914945 0.000107712556
+ vertex 0.0225723535 -0.0130556496 -0.0114215398
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 -0.0130734621 -0.0144883329
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ vertex 0.0225723535 -0.0130556496 -0.0114215398
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 -0.0130734621 -0.0144883329
+ vertex 0.0225723535 -0.0130556496 -0.0114215398
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 -0.0130734621 -0.0144883329
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ vertex 0.0198158212 -0.0136940712 -0.013746094
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 -0.0130734621 -0.0144883329
+ vertex 0.0198158212 -0.0136940712 -0.013746094
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658740941 0.0156882554 -0.00720697967
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ vertex 0.0109909363 0.0127807539 -0.00266474276
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658740941 0.0156882554 -0.00720697967
+ vertex 0.0109909363 0.0127807539 -0.00266474276
+ vertex 0.0103289252 0.0133193498 -0.011785998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658740941 0.0156882554 -0.00720697967
+ vertex 0.0103289252 0.0133193498 -0.011785998
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658740941 0.0156882554 -0.00720697967
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ vertex 0.00335793849 0.0162850786 -2.80580352e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 -0.00167539215 0.000899999985
+ vertex -0.00294060563 -0.00362145854 0.000121843914
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 -0.00167539215 0.000899999985
+ vertex 0.0225232132 -0.0129914945 0.000107712556
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 -0.00167539215 0.000899999985
+ vertex 0.0236538425 -0.0112433638 0.000139167751
+ vertex 0.00106034789 0.0139854029 0.000899999985
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 -0.00167539215 0.000899999985
+ vertex 0.00106034789 0.0139854029 0.000899999985
+ vertex -0.0122417556 0.0111436844 4.56855414e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 -0.00167539215 0.000899999985
+ vertex -0.0122417556 0.0111436844 4.56855414e-05
+ vertex -0.00954299793 0.00346851116 -0.000116769595
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 -0.00167539215 0.000899999985
+ vertex -0.00954299793 0.00346851116 -0.000116769595
+ vertex -0.00294060563 -0.00362145854 0.000121843914
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772537 0.01008128 -0.0152915008
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ vertex 0.0239881519 -0.00389247201 -0.0132786492
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772537 0.01008128 -0.0152915008
+ vertex 0.0239881519 -0.00389247201 -0.0132786492
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ vertex -0.00952879526 0.00349948788 -0.0148
+ vertex 0.00551772537 0.01008128 -0.0152915008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ vertex 0.00551772537 0.01008128 -0.0152915008
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00360827777 -0.00293576159 -0.0148264747
+ vertex 0.0236305781 -0.0113051506 -0.0145429783
+ vertex 0.0224094652 -0.0130734621 -0.0144883329
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772537 0.01008128 -0.0152915008
+ vertex -0.00952879526 0.00349948788 -0.0148
+ vertex -0.0122086694 0.011017709 -0.0145997265
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772537 0.01008128 -0.0152915008
+ vertex -0.0122086694 0.011017709 -0.0145997265
+ vertex 0.00204475131 0.0164765455 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0225232132 -0.0129914945 0.000107712556
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ vertex 0.0225723535 -0.0130556496 -0.0114215398
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0225232132 -0.0129914945 0.000107712556
+ vertex -0.0034821257 -0.00167539215 0.000899999985
+ vertex 0.020417748 -0.0136719858 -0.000442875171
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link13_R.STL b/assets/inspire_hand/meshes/Link13_R.STL
new file mode 100644
index 0000000..a42829f
Binary files /dev/null and b/assets/inspire_hand/meshes/Link13_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link13_R.STL.convex.stl b/assets/inspire_hand/meshes/Link13_R.STL.convex.stl
new file mode 100644
index 0000000..ef56b3d
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link13_R.STL.convex.stl
@@ -0,0 +1,498 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00294060563 0.00362145901 0.000121843914
+ vertex 0.00197924627 0.00877810828 -0.00719999941
+ vertex -0.00360827777 0.00293576182 -0.0148264747
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00294060563 0.00362145901 0.000121843914
+ vertex -0.00360827777 0.00293576182 -0.0148264747
+ vertex -0.00952879526 -0.00349948835 -0.0148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00294060563 0.00362145901 0.000121843914
+ vertex -0.00952879526 -0.00349948835 -0.0148
+ vertex -0.00954299793 -0.00346851139 -0.000116769588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520839449 -0.0159510355 -0.000468590501
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ vertex 0.00335777202 -0.0162851103 -2.79925516e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ vertex 0.0255211815 0.0011499481 -0.00720000034
+ vertex 0.0236065667 0.0113664642 -0.0145465545
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ vertex 0.00106034789 -0.0139854029 0.000899999985
+ vertex 0.00335777202 -0.0162851103 -2.79925516e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ vertex 0.00335777202 -0.0162851103 -2.79925516e-05
+ vertex 0.0242268927 0.00308478833 -0.00149034301
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636311062 -0.0155266142 -0.0139314085
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ vertex -0.00520839449 -0.0159510355 -0.000468590501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636311062 -0.0155266142 -0.0139314085
+ vertex -0.00520839449 -0.0159510355 -0.000468590501
+ vertex -0.0122417537 -0.0111434702 4.33475725e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636311062 -0.0155266142 -0.0139314085
+ vertex -0.0122417537 -0.0111434702 4.33475725e-05
+ vertex -0.0122139715 -0.011040139 -0.0145840785
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00636311062 -0.0155266142 -0.0139314085
+ vertex -0.0122139715 -0.011040139 -0.0145840785
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954299793 -0.00346851139 -0.000116769588
+ vertex -0.00952879526 -0.00349948835 -0.0148
+ vertex -0.0122139715 -0.011040139 -0.0145840785
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954299793 -0.00346851139 -0.000116769588
+ vertex -0.0122139715 -0.011040139 -0.0145840785
+ vertex -0.0122417537 -0.0111434702 4.33475725e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0226615071 -0.00163091347 -0.0113424873
+ vertex 0.010328915 -0.013319361 -0.0117860008
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0226615071 -0.00163091347 -0.0113424873
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ vertex 0.0240981504 0.0034947677 -0.0131107569
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0242268927 0.00308478833 -0.00149034301
+ vertex 0.00335777202 -0.0162851103 -2.79925516e-05
+ vertex 0.0110015655 -0.0127716335 -0.00266540423
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0242268927 0.00308478833 -0.00149034301
+ vertex 0.0110015655 -0.0127716335 -0.00266540423
+ vertex 0.0226853397 -0.00172916998 -0.0032542767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110015655 -0.0127716335 -0.00266540423
+ vertex 0.010328915 -0.013319361 -0.0117860008
+ vertex 0.0226615071 -0.00163091347 -0.0113424873
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110015655 -0.0127716335 -0.00266540423
+ vertex 0.0226615071 -0.00163091347 -0.0113424873
+ vertex 0.0255211815 0.0011499481 -0.00720000034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110015655 -0.0127716335 -0.00266540423
+ vertex 0.0255211815 0.0011499481 -0.00720000034
+ vertex 0.0226853397 -0.00172916998 -0.0032542767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0126133747 0.0128762219 -0.00719476445
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ vertex 0.0200176239 0.0136904577 -0.01381943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204026978 0.00829510298 -0.0115155764
+ vertex -0.00360827777 0.00293576182 -0.0148264747
+ vertex 0.00197924627 0.00877810828 -0.00719999941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204026978 0.00829510298 -0.0115155764
+ vertex 0.00197924627 0.00877810828 -0.00719999941
+ vertex 0.0126133747 0.0128762219 -0.00719476445
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204026978 0.00829510298 -0.0115155764
+ vertex 0.0126133747 0.0128762219 -0.00719476445
+ vertex 0.0200176239 0.0136904577 -0.01381943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204026978 0.00829510298 -0.0115155764
+ vertex 0.0200176239 0.0136904577 -0.01381943
+ vertex -0.00360827777 0.00293576182 -0.0148264747
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 0.0082951067 -0.00288442057
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ vertex 0.0126133747 0.0128762219 -0.00719476445
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 0.0082951067 -0.00288442057
+ vertex 0.0126133747 0.0128762219 -0.00719476445
+ vertex 0.00197924627 0.00877810828 -0.00719999941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 0.0082951067 -0.00288442057
+ vertex 0.00197924627 0.00877810828 -0.00719999941
+ vertex -0.00294060563 0.00362145901 0.000121843914
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00204027537 0.0082951067 -0.00288442057
+ vertex -0.00294060563 0.00362145901 0.000121843914
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252200719 0.00135843654 -0.0109397583
+ vertex 0.0255211815 0.0011499481 -0.00720000034
+ vertex 0.0226615071 -0.00163091347 -0.0113424873
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252200719 0.00135843654 -0.0109397583
+ vertex 0.0226615071 -0.00163091347 -0.0113424873
+ vertex 0.0240981504 0.0034947677 -0.0131107569
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252200719 0.00135843654 -0.0109397583
+ vertex 0.0240981504 0.0034947677 -0.0131107569
+ vertex 0.0236065667 0.0113664642 -0.0145465545
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0252200719 0.00135843654 -0.0109397583
+ vertex 0.0236065667 0.0113664642 -0.0145465545
+ vertex 0.0255211815 0.0011499481 -0.00720000034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00106034789 -0.0139854029 0.000899999985
+ vertex -0.0122417537 -0.0111434702 4.33475725e-05
+ vertex -0.00520839449 -0.0159510355 -0.000468590501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00106034789 -0.0139854029 0.000899999985
+ vertex -0.00520839449 -0.0159510355 -0.000468590501
+ vertex 0.00335777202 -0.0162851103 -2.79925516e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.025217995 0.00136129372 -0.00345262326
+ vertex 0.0242268927 0.00308478833 -0.00149034301
+ vertex 0.0226853397 -0.00172916998 -0.0032542767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.025217995 0.00136129372 -0.00345262326
+ vertex 0.0226853397 -0.00172916998 -0.0032542767
+ vertex 0.0255211815 0.0011499481 -0.00720000034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.025217995 0.00136129372 -0.00345262326
+ vertex 0.0255211815 0.0011499481 -0.00720000034
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.025217995 0.00136129372 -0.00345262326
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ vertex 0.0242268927 0.00308478833 -0.00149034301
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0225723572 0.0130556514 -0.0114215408
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0225723572 0.0130556514 -0.0114215408
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ vertex 0.0236065667 0.0113664642 -0.0145465545
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 0.0130734639 -0.0144883338
+ vertex 0.0200176239 0.0136904577 -0.01381943
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 0.0130734639 -0.0144883338
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ vertex 0.0225723572 0.0130556514 -0.0114215408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 0.0130734639 -0.0144883338
+ vertex 0.0225723572 0.0130556514 -0.0114215408
+ vertex 0.0236065667 0.0113664642 -0.0145465545
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 0.0130734639 -0.0144883338
+ vertex -0.00360827777 0.00293576182 -0.0148264747
+ vertex 0.0200176239 0.0136904577 -0.01381943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658748997 -0.0156884696 -0.00720697967
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ vertex 0.010328915 -0.013319361 -0.0117860008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658748997 -0.0156884696 -0.00720697967
+ vertex 0.010328915 -0.013319361 -0.0117860008
+ vertex 0.0110015655 -0.0127716335 -0.00266540423
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658748997 -0.0156884696 -0.00720697967
+ vertex 0.0110015655 -0.0127716335 -0.00266540423
+ vertex 0.00335777202 -0.0162851103 -2.79925516e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00658748997 -0.0156884696 -0.00720697967
+ vertex 0.00335777202 -0.0162851103 -2.79925516e-05
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 0.00167539238 0.000899999985
+ vertex -0.0122417537 -0.0111434702 4.33475725e-05
+ vertex 0.00106034789 -0.0139854029 0.000899999985
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 0.00167539238 0.000899999985
+ vertex 0.00106034789 -0.0139854029 0.000899999985
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 0.00167539238 0.000899999985
+ vertex 0.0236391071 0.0112828389 0.00014162685
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 0.00167539238 0.000899999985
+ vertex 0.0205292013 0.0136618959 -0.000404135411
+ vertex -0.00294060563 0.00362145901 0.000121843914
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 0.00167539238 0.000899999985
+ vertex -0.00294060563 0.00362145901 0.000121843914
+ vertex -0.00954299793 -0.00346851139 -0.000116769588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0034821257 0.00167539238 0.000899999985
+ vertex -0.00954299793 -0.00346851139 -0.000116769588
+ vertex -0.0122417537 -0.0111434702 4.33475725e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 0.0130734639 -0.0144883338
+ vertex 0.0236065667 0.0113664642 -0.0145465545
+ vertex 0.00551772071 -0.0100812875 -0.0152915157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 0.0130734639 -0.0144883338
+ vertex 0.00551772071 -0.0100812875 -0.0152915157
+ vertex -0.00952879526 -0.00349948835 -0.0148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0224094652 0.0130734639 -0.0144883338
+ vertex -0.00952879526 -0.00349948835 -0.0148
+ vertex -0.00360827777 0.00293576182 -0.0148264747
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772071 -0.0100812875 -0.0152915157
+ vertex 0.0236065667 0.0113664642 -0.0145465545
+ vertex 0.0240981504 0.0034947677 -0.0131107569
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772071 -0.0100812875 -0.0152915157
+ vertex 0.0240981504 0.0034947677 -0.0131107569
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772071 -0.0100812875 -0.0152915157
+ vertex 0.00204475131 -0.0164765473 -0.0145255793
+ vertex -0.0122139715 -0.011040139 -0.0145840785
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00551772071 -0.0100812875 -0.0152915157
+ vertex -0.0122139715 -0.011040139 -0.0145840785
+ vertex -0.00952879526 -0.00349948835 -0.0148
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link14_L.STL b/assets/inspire_hand/meshes/Link14_L.STL
new file mode 100644
index 0000000..291a14f
Binary files /dev/null and b/assets/inspire_hand/meshes/Link14_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link14_L.STL.convex.stl b/assets/inspire_hand/meshes/Link14_L.STL.convex.stl
new file mode 100644
index 0000000..0ce7ba2
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link14_L.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00512673147 0.00837041344 -0.0100894896
+ vertex 0.00535698887 0.0086597912 -0.00299278554
+ vertex 0.00826827437 0.00567460945 -0.00265491288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00512673147 0.00837041344 -0.0100894896
+ vertex 0.00826827437 0.00567460945 -0.00265491288
+ vertex 0.0209318288 -0.00844171923 -0.00323660369
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00512673147 0.00837041344 -0.0100894896
+ vertex 0.0209318288 -0.00844171923 -0.00323660369
+ vertex 0.020510653 -0.00824526604 -0.00912056118
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00484760618 0.00193803303 -0.00245000003
+ vertex 0.00187790697 -0.00390737923 0.00105241139
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00484760618 0.00193803303 -0.00245000003
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ vertex -0.000304747809 0.00821762625 -0.00294999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00484760618 0.00193803303 -0.00245000003
+ vertex -0.00504786847 0.000576333841 -0.00954999961
+ vertex -0.00504786847 0.000576333841 -0.00445000036
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00535698887 0.0086597912 -0.00299278554
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ vertex 0.00826827437 0.00567460945 -0.00265491288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00535698887 0.0086597912 -0.00299278554
+ vertex 0.00512673147 0.00837041344 -0.0100894896
+ vertex -0.000242706694 0.00825330801 -0.00905000139
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00535698887 0.0086597912 -0.00299278554
+ vertex -0.000242706694 0.00825330801 -0.00905000139
+ vertex -0.000304747809 0.00821762625 -0.00294999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00535698887 0.0086597912 -0.00299278554
+ vertex -0.000304747809 0.00821762625 -0.00294999988
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209318288 -0.00844171923 -0.00323660369
+ vertex 0.00826827437 0.00567460945 -0.00265491288
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209318288 -0.00844171923 -0.00323660369
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ vertex 0.0187538359 -0.0104011679 -0.000944506261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0212634224 -0.0120062614 -0.00309343101
+ vertex 0.0222715605 -0.0103677548 -0.0063738809
+ vertex 0.0209318288 -0.00844171923 -0.00323660369
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0212634224 -0.0120062614 -0.00309343101
+ vertex 0.0209318288 -0.00844171923 -0.00323660369
+ vertex 0.0187538359 -0.0104011679 -0.000944506261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.020510653 -0.00824526604 -0.00912056118
+ vertex 0.0209318288 -0.00844171923 -0.00323660369
+ vertex 0.0222715605 -0.0103677548 -0.0063738809
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00512673147 0.00837041344 -0.0100894896
+ vertex 0.020510653 -0.00824526604 -0.00912056118
+ vertex 0.0178316291 -0.00983346161 -0.0113605987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00512673147 0.00837041344 -0.0100894896
+ vertex 0.0178316291 -0.00983346161 -0.0113605987
+ vertex 0.00407311833 0.005198495 -0.0122924624
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00407311833 0.005198495 -0.0122924624
+ vertex 0.0178316291 -0.00983346161 -0.0113605987
+ vertex 0.00383088435 -0.00185999623 -0.013342605
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00407311833 0.005198495 -0.0122924624
+ vertex 0.00383088435 -0.00185999623 -0.013342605
+ vertex 0.00124589994 -0.00437950715 -0.0127226021
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00407311833 0.005198495 -0.0122924624
+ vertex 0.00124589994 -0.00437950715 -0.0127226021
+ vertex -0.00504786847 0.000576333841 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00407311833 0.005198495 -0.0122924624
+ vertex -0.000242706694 0.00825330801 -0.00905000139
+ vertex 0.00512673147 0.00837041344 -0.0100894896
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124589994 -0.00437950715 -0.0127226021
+ vertex -0.00312809576 -0.00401181774 -0.00954999961
+ vertex -0.00504786847 0.000576333841 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124589994 -0.00437950715 -0.0127226021
+ vertex 0.00383088435 -0.00185999623 -0.013342605
+ vertex 0.00719717098 -0.00933754444 -0.0123852938
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124589994 -0.00437950715 -0.0127226021
+ vertex 0.00719717098 -0.00933754444 -0.0123852938
+ vertex -0.00312809576 -0.00401181774 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0155541738 -0.0131858038 -0.0115278177
+ vertex 0.00719717098 -0.00933754444 -0.0123852938
+ vertex 0.00383088435 -0.00185999623 -0.013342605
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0155541738 -0.0131858038 -0.0115278177
+ vertex 0.00383088435 -0.00185999623 -0.013342605
+ vertex 0.0178316291 -0.00983346161 -0.0113605987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0155541738 -0.0131858038 -0.0115278177
+ vertex 0.0178316291 -0.00983346161 -0.0113605987
+ vertex 0.0206866674 -0.0124441935 -0.0093129063
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0155541738 -0.0131858038 -0.0115278177
+ vertex 0.0206866674 -0.0124441935 -0.0093129063
+ vertex 0.0161192454 -0.0152129941 -0.00948119815
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.016499022 -0.0135002108 -0.000708093226
+ vertex 0.0114938971 -0.0135084242 -0.00118722441
+ vertex 0.0175848641 -0.0149372956 -0.00261197891
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.016499022 -0.0135002108 -0.000708093226
+ vertex 0.0175848641 -0.0149372956 -0.00261197891
+ vertex 0.0212634224 -0.0120062614 -0.00309343101
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.016499022 -0.0135002108 -0.000708093226
+ vertex 0.0212634224 -0.0120062614 -0.00309343101
+ vertex 0.0187538359 -0.0104011679 -0.000944506261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0193030369 -0.0146003636 -0.00762915239
+ vertex 0.0161192454 -0.0152129941 -0.00948119815
+ vertex 0.0206866674 -0.0124441935 -0.0093129063
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0193030369 -0.0146003636 -0.00762915239
+ vertex 0.0206866674 -0.0124441935 -0.0093129063
+ vertex 0.0222715605 -0.0103677548 -0.0063738809
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0193030369 -0.0146003636 -0.00762915239
+ vertex 0.0222715605 -0.0103677548 -0.0063738809
+ vertex 0.0212634224 -0.0120062614 -0.00309343101
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0193030369 -0.0146003636 -0.00762915239
+ vertex 0.0212634224 -0.0120062614 -0.00309343101
+ vertex 0.0175848641 -0.0149372956 -0.00261197891
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0193030369 -0.0146003636 -0.00762915239
+ vertex 0.0175848641 -0.0149372956 -0.00261197891
+ vertex 0.0161192454 -0.0152129941 -0.00948119815
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0104746334 -0.0130751589 -0.0108739845
+ vertex 0.0076833386 -0.0125499945 -0.008095528
+ vertex -0.00312809576 -0.00401181774 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0104746334 -0.0130751589 -0.0108739845
+ vertex -0.00312809576 -0.00401181774 -0.00954999961
+ vertex 0.00719717098 -0.00933754444 -0.0123852938
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0104746334 -0.0130751589 -0.0108739845
+ vertex 0.00719717098 -0.00933754444 -0.0123852938
+ vertex 0.0155541738 -0.0131858038 -0.0115278177
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0104746334 -0.0130751589 -0.0108739845
+ vertex 0.0155541738 -0.0131858038 -0.0115278177
+ vertex 0.0161192454 -0.0152129941 -0.00948119815
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0143942619 -0.0153388241 -0.0039044756
+ vertex 0.0161192454 -0.0152129941 -0.00948119815
+ vertex 0.0175848641 -0.0149372956 -0.00261197891
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0143942619 -0.0153388241 -0.0039044756
+ vertex 0.0175848641 -0.0149372956 -0.00261197891
+ vertex 0.0114938971 -0.0135084242 -0.00118722441
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0143942619 -0.0153388241 -0.0039044756
+ vertex 0.0076833386 -0.0125499945 -0.008095528
+ vertex 0.0104746334 -0.0130751589 -0.0108739845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0143942619 -0.0153388241 -0.0039044756
+ vertex 0.0104746334 -0.0130751589 -0.0108739845
+ vertex 0.0161192454 -0.0152129941 -0.00948119815
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00540134637 -0.000538525986 0.00110963604
+ vertex 0.00187790697 -0.00390737923 0.00105241139
+ vertex 0.016499022 -0.0135002108 -0.000708093226
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00540134637 -0.000538525986 0.00110963604
+ vertex 0.016499022 -0.0135002108 -0.000708093226
+ vertex 0.0187538359 -0.0104011679 -0.000944506261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00540134637 -0.000538525986 0.00110963604
+ vertex 0.0187538359 -0.0104011679 -0.000944506261
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00540134637 -0.000538525986 0.00110963604
+ vertex 0.0043730801 0.00669520022 -0.000304654066
+ vertex 0.00187790697 -0.00390737923 0.00105241139
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312809576 -0.00401181774 -0.00245000003
+ vertex -0.00312809576 -0.00401181774 -0.00954999961
+ vertex 0.0076833386 -0.0125499945 -0.008095528
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312809576 -0.00401181774 -0.00245000003
+ vertex 0.0076833386 -0.0125499945 -0.008095528
+ vertex 0.00610036775 -0.0113324719 -0.00276233954
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00610036775 -0.0113324719 -0.00276233954
+ vertex 0.0076833386 -0.0125499945 -0.008095528
+ vertex 0.0143942619 -0.0153388241 -0.0039044756
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00610036775 -0.0113324719 -0.00276233954
+ vertex 0.0143942619 -0.0153388241 -0.0039044756
+ vertex 0.0114938971 -0.0135084242 -0.00118722441
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 -0.000699626165 -0.00245000003
+ vertex -0.00312809576 -0.00401181774 -0.00245000003
+ vertex 0.00187790697 -0.00390737923 0.00105241139
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 -0.000699626165 -0.00245000003
+ vertex 0.00187790697 -0.00390737923 0.00105241139
+ vertex -0.00484760618 0.00193803303 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 -0.000699626165 -0.00245000003
+ vertex -0.00484760618 0.00193803303 -0.00245000003
+ vertex -0.00504786847 0.000576333841 -0.00445000036
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 -0.000699626165 -0.00245000003
+ vertex -0.00504786847 0.000576333841 -0.00445000036
+ vertex -0.00504786847 0.000576333841 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 -0.000699626165 -0.00245000003
+ vertex -0.00504786847 0.000576333841 -0.00954999961
+ vertex -0.00312809576 -0.00401181774 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 -0.000699626165 -0.00245000003
+ vertex -0.00312809576 -0.00401181774 -0.00954999961
+ vertex -0.00312809576 -0.00401181774 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0043116766 0.00327486126 -0.00913701672
+ vertex -0.00504786847 0.000576333841 -0.00954999961
+ vertex -0.00484760618 0.00193803303 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0043116766 0.00327486126 -0.00913701672
+ vertex -0.00484760618 0.00193803303 -0.00245000003
+ vertex -0.000304747809 0.00821762625 -0.00294999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0043116766 0.00327486126 -0.00913701672
+ vertex -0.000304747809 0.00821762625 -0.00294999988
+ vertex -0.000242706694 0.00825330801 -0.00905000139
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0043116766 0.00327486126 -0.00913701672
+ vertex -0.000242706694 0.00825330801 -0.00905000139
+ vertex 0.00407311833 0.005198495 -0.0122924624
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0043116766 0.00327486126 -0.00913701672
+ vertex 0.00407311833 0.005198495 -0.0122924624
+ vertex -0.00504786847 0.000576333841 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0219888613 -0.0103672091 -0.00832071621
+ vertex 0.0206866674 -0.0124441935 -0.0093129063
+ vertex 0.0178316291 -0.00983346161 -0.0113605987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0219888613 -0.0103672091 -0.00832071621
+ vertex 0.0178316291 -0.00983346161 -0.0113605987
+ vertex 0.020510653 -0.00824526604 -0.00912056118
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0219888613 -0.0103672091 -0.00832071621
+ vertex 0.020510653 -0.00824526604 -0.00912056118
+ vertex 0.0222715605 -0.0103677548 -0.0063738809
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0219888613 -0.0103672091 -0.00832071621
+ vertex 0.0222715605 -0.0103677548 -0.0063738809
+ vertex 0.0206866674 -0.0124441935 -0.0093129063
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 -0.00922832079 -0.000360598176
+ vertex 0.00187790697 -0.00390737923 0.00105241139
+ vertex -0.00312809576 -0.00401181774 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 -0.00922832079 -0.000360598176
+ vertex -0.00312809576 -0.00401181774 -0.00245000003
+ vertex 0.00610036775 -0.0113324719 -0.00276233954
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 -0.00922832079 -0.000360598176
+ vertex 0.00610036775 -0.0113324719 -0.00276233954
+ vertex 0.0114938971 -0.0135084242 -0.00118722441
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 -0.00922832079 -0.000360598176
+ vertex 0.0114938971 -0.0135084242 -0.00118722441
+ vertex 0.016499022 -0.0135002108 -0.000708093226
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 -0.00922832079 -0.000360598176
+ vertex 0.016499022 -0.0135002108 -0.000708093226
+ vertex 0.00187790697 -0.00390737923 0.00105241139
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link14_R.STL b/assets/inspire_hand/meshes/Link14_R.STL
new file mode 100644
index 0000000..13f98f8
Binary files /dev/null and b/assets/inspire_hand/meshes/Link14_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link14_R.STL.convex.stl b/assets/inspire_hand/meshes/Link14_R.STL.convex.stl
new file mode 100644
index 0000000..6c5bab6
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link14_R.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312809576 0.00401181774 -0.00245000003
+ vertex 0.00844539888 0.0102744075 0.000254117127
+ vertex 0.0114938971 0.0135084251 -0.00118722429
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312809576 0.00401181774 -0.00245000003
+ vertex 0.0114938971 0.0135084251 -0.00118722429
+ vertex 0.00867762603 0.0130432881 -0.00320307631
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00484760618 -0.00193803315 -0.00954999868
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00484760618 -0.00193803315 -0.00954999868
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ vertex -0.000242706723 -0.00825330894 -0.00905000046
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00484760618 -0.00193803315 -0.00954999868
+ vertex -0.00504786847 -0.000576333841 -0.00245000003
+ vertex -0.00504786847 -0.000576333841 -0.00754999975
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00533693377 -0.00863752514 -0.00917873066
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ vertex 0.00828528125 -0.0056570014 -0.00934534147
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00516385119 -0.00841722917 -0.00202040863
+ vertex -0.000304747809 -0.00821762625 -0.00294999988
+ vertex -0.000242706723 -0.00825330894 -0.00905000046
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00516385119 -0.00841722917 -0.00202040863
+ vertex -0.000242706723 -0.00825330894 -0.00905000046
+ vertex 0.00533693377 -0.00863752514 -0.00917873066
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00533693377 -0.00863752514 -0.00917873066
+ vertex -0.000242706723 -0.00825330894 -0.00905000046
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0164990537 0.0135001577 -0.000708083448
+ vertex 0.00844539888 0.0102744075 0.000254117127
+ vertex 0.00396200549 0.00156084588 0.00132731209
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0164990537 0.0135001577 -0.000708083448
+ vertex 0.00396200549 0.00156084588 0.00132731209
+ vertex 0.0192794092 0.00972571876 -0.00129629334
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0164990537 0.0135001577 -0.000708083448
+ vertex 0.0192794092 0.00972571876 -0.00129629334
+ vertex 0.0209506396 0.0126666781 -0.00326397689
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0164990537 0.0135001577 -0.000708083448
+ vertex 0.0209506396 0.0126666781 -0.00326397689
+ vertex 0.0164620057 0.0152845522 -0.00279510417
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00143230509 0.00423075259 0.000842975627
+ vertex 0.00844539888 0.0102744075 0.000254117127
+ vertex -0.00312809576 0.00401181774 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00143230509 0.00423075259 0.000842975627
+ vertex -0.00312809576 0.00401181774 -0.00245000003
+ vertex -0.00504786847 -0.000576333841 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00143230509 0.00423075259 0.000842975627
+ vertex 0.00396200549 0.00156084588 0.00132731209
+ vertex 0.00844539888 0.0102744075 0.000254117127
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0211814977 0.0084747551 -0.00363525026
+ vertex 0.0192794092 0.00972571876 -0.00129629334
+ vertex 0.00516385119 -0.00841722917 -0.00202040863
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0211814977 0.0084747551 -0.00363525026
+ vertex 0.00516385119 -0.00841722917 -0.00202040863
+ vertex 0.00533693377 -0.00863752514 -0.00917873066
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0211814977 0.0084747551 -0.00363525026
+ vertex 0.00533693377 -0.00863752514 -0.00917873066
+ vertex 0.00828528125 -0.0056570014 -0.00934534147
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209304895 0.00844585523 -0.00876971241
+ vertex 0.00828528125 -0.0056570014 -0.00934534147
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209304895 0.00844585523 -0.00876971241
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ vertex 0.0178316291 0.00983346254 -0.0113605987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209304895 0.00844585523 -0.00876971241
+ vertex 0.0178316291 0.00983346254 -0.0113605987
+ vertex 0.0206934288 0.0116302064 -0.00977565162
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209304895 0.00844585523 -0.00876971241
+ vertex 0.0206934288 0.0116302064 -0.00977565162
+ vertex 0.0222715605 0.0103677986 -0.00637385482
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209304895 0.00844585523 -0.00876971241
+ vertex 0.0222715605 0.0103677986 -0.00637385482
+ vertex 0.0211814977 0.0084747551 -0.00363525026
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0209304895 0.00844585523 -0.00876971241
+ vertex 0.0211814977 0.0084747551 -0.00363525026
+ vertex 0.00828528125 -0.0056570014 -0.00934534147
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0040774974 -0.00523231411 0.000282039575
+ vertex 0.00516385119 -0.00841722917 -0.00202040863
+ vertex 0.0192794092 0.00972571876 -0.00129629334
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0040774974 -0.00523231411 0.000282039575
+ vertex 0.0192794092 0.00972571876 -0.00129629334
+ vertex 0.00396200549 0.00156084588 0.00132731209
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0040774974 -0.00523231411 0.000282039575
+ vertex 0.00396200549 0.00156084588 0.00132731209
+ vertex 0.00143230509 0.00423075259 0.000842975627
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0040774974 -0.00523231411 0.000282039575
+ vertex 0.00143230509 0.00423075259 0.000842975627
+ vertex -0.00504786847 -0.000576333841 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0040774974 -0.00523231411 0.000282039575
+ vertex -0.000304747809 -0.00821762625 -0.00294999988
+ vertex 0.00516385119 -0.00841722917 -0.00202040863
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0164621435 0.0135565475 -0.0112799853
+ vertex 0.0179557018 0.0146923764 -0.00956679974
+ vertex 0.0206934288 0.0116302064 -0.00977565162
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0164621435 0.0135565475 -0.0112799853
+ vertex 0.0206934288 0.0116302064 -0.00977565162
+ vertex 0.0178316291 0.00983346254 -0.0113605987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144903483 0.015296259 -0.00866874587
+ vertex 0.0164620057 0.0152845522 -0.00279510417
+ vertex 0.0179557018 0.0146923764 -0.00956679974
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144903483 0.015296259 -0.00866874587
+ vertex 0.0179557018 0.0146923764 -0.00956679974
+ vertex 0.0164621435 0.0135565475 -0.0112799853
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144903483 0.015296259 -0.00866874587
+ vertex 0.0164621435 0.0135565475 -0.0112799853
+ vertex 0.0114938971 0.0135084251 -0.010812778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144903483 0.015296259 -0.00866874587
+ vertex 0.00867762603 0.0130432881 -0.00320307631
+ vertex 0.0164620057 0.0152845522 -0.00279510417
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0205947254 0.0135419331 -0.00788625237
+ vertex 0.0222715605 0.0103677986 -0.00637385482
+ vertex 0.0206934288 0.0116302064 -0.00977565162
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0205947254 0.0135419331 -0.00788625237
+ vertex 0.0206934288 0.0116302064 -0.00977565162
+ vertex 0.0179557018 0.0146923764 -0.00956679974
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0205947254 0.0135419331 -0.00788625237
+ vertex 0.0179557018 0.0146923764 -0.00956679974
+ vertex 0.0164620057 0.0152845522 -0.00279510417
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0205947254 0.0135419331 -0.00788625237
+ vertex 0.0164620057 0.0152845522 -0.00279510417
+ vertex 0.0209506396 0.0126666781 -0.00326397689
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312809576 0.00401181774 -0.00954999868
+ vertex -0.00312809576 0.00401181774 -0.00245000003
+ vertex 0.00867762603 0.0130432881 -0.00320307631
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00312809576 0.00401181774 -0.00954999868
+ vertex 0.00867762603 0.0130432881 -0.00320307631
+ vertex 0.00735053048 0.0122600608 -0.00882250816
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00735053048 0.0122600608 -0.00882250816
+ vertex 0.00867762603 0.0130432881 -0.00320307631
+ vertex 0.0144903483 0.015296259 -0.00866874587
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00735053048 0.0122600608 -0.00882250816
+ vertex 0.0144903483 0.015296259 -0.00866874587
+ vertex 0.0114938971 0.0135084251 -0.010812778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ vertex 0.0164621435 0.0135565475 -0.0112799853
+ vertex 0.0178316291 0.00983346254 -0.0113605987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ vertex 0.0178316291 0.00983346254 -0.0113605987
+ vertex 0.00540134637 0.000538526045 -0.0131096393
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00540134637 0.000538526045 -0.0131096393
+ vertex 0.0178316291 0.00983346254 -0.0113605987
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00540134637 0.000538526045 -0.0131096393
+ vertex 0.00434891228 -0.00660452293 -0.0117415087
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0114938971 0.0135084251 -0.00118722429
+ vertex 0.0164620057 0.0152845522 -0.00279510417
+ vertex 0.00867762603 0.0130432881 -0.00320307631
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0114938971 0.0135084251 -0.00118722429
+ vertex 0.00844539888 0.0102744075 0.000254117127
+ vertex 0.0164990537 0.0135001577 -0.000708083448
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0114938971 0.0135084251 -0.00118722429
+ vertex 0.0164990537 0.0135001577 -0.000708083448
+ vertex 0.0164620057 0.0152845522 -0.00279510417
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 0.000699626165 -0.00954999868
+ vertex -0.00312809576 0.00401181774 -0.00954999868
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 0.000699626165 -0.00954999868
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ vertex -0.00484760618 -0.00193803315 -0.00954999868
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 0.000699626165 -0.00954999868
+ vertex -0.00484760618 -0.00193803315 -0.00954999868
+ vertex -0.00504786847 -0.000576333841 -0.00754999975
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 0.000699626165 -0.00954999868
+ vertex -0.00504786847 -0.000576333841 -0.00754999975
+ vertex -0.00504786847 -0.000576333841 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 0.000699626165 -0.00954999868
+ vertex -0.00504786847 -0.000576333841 -0.00245000003
+ vertex -0.00312809576 0.00401181774 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00495100906 0.000699626165 -0.00954999868
+ vertex -0.00312809576 0.00401181774 -0.00245000003
+ vertex -0.00312809576 0.00401181774 -0.00954999868
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0221410356 0.0105005084 -0.00398013042
+ vertex 0.0209506396 0.0126666781 -0.00326397689
+ vertex 0.0192794092 0.00972571876 -0.00129629334
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0221410356 0.0105005084 -0.00398013042
+ vertex 0.0192794092 0.00972571876 -0.00129629334
+ vertex 0.0211814977 0.0084747551 -0.00363525026
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0221410356 0.0105005084 -0.00398013042
+ vertex 0.0211814977 0.0084747551 -0.00363525026
+ vertex 0.0222715605 0.0103677986 -0.00637385482
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0221410356 0.0105005084 -0.00398013042
+ vertex 0.0222715605 0.0103677986 -0.00637385482
+ vertex 0.0205947254 0.0135419331 -0.00788625237
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0221410356 0.0105005084 -0.00398013042
+ vertex 0.0205947254 0.0135419331 -0.00788625237
+ vertex 0.0209506396 0.0126666781 -0.00326397689
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00396492379 -0.0038324655 -0.00293883192
+ vertex -0.00504786847 -0.000576333841 -0.00245000003
+ vertex -0.00484760618 -0.00193803315 -0.00954999868
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00396492379 -0.0038324655 -0.00293883192
+ vertex -0.00484760618 -0.00193803315 -0.00954999868
+ vertex -0.000242706723 -0.00825330894 -0.00905000046
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00396492379 -0.0038324655 -0.00293883192
+ vertex -0.000242706723 -0.00825330894 -0.00905000046
+ vertex -0.000304747809 -0.00821762625 -0.00294999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00396492379 -0.0038324655 -0.00293883192
+ vertex -0.000304747809 -0.00821762625 -0.00294999988
+ vertex 0.0040774974 -0.00523231411 0.000282039575
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00396492379 -0.0038324655 -0.00293883192
+ vertex 0.0040774974 -0.00523231411 0.000282039575
+ vertex -0.00504786847 -0.000576333841 -0.00245000003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 0.00922832172 -0.0116394041
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ vertex -0.00312809576 0.00401181774 -0.00954999868
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 0.00922832172 -0.0116394041
+ vertex -0.00312809576 0.00401181774 -0.00954999868
+ vertex 0.00735053048 0.0122600608 -0.00882250816
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 0.00922832172 -0.0116394041
+ vertex 0.00735053048 0.0122600608 -0.00882250816
+ vertex 0.0114938971 0.0135084251 -0.010812778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 0.00922832172 -0.0116394041
+ vertex 0.0114938971 0.0135084251 -0.010812778
+ vertex 0.0164621435 0.0135565475 -0.0112799853
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00525678601 0.00922832172 -0.0116394041
+ vertex 0.0164621435 0.0135565475 -0.0112799853
+ vertex 0.0017748453 0.0039776261 -0.0130125638
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link15_L.STL b/assets/inspire_hand/meshes/Link15_L.STL
new file mode 100644
index 0000000..f899431
Binary files /dev/null and b/assets/inspire_hand/meshes/Link15_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link15_L.STL.convex.stl b/assets/inspire_hand/meshes/Link15_L.STL.convex.stl
new file mode 100644
index 0000000..c3a0b56
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link15_L.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.0108619863 0.000361838145 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0108619863 0.000361838145 -0.0082310643
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.0108619863 0.000361838145 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ vertex 0.0108619863 0.000361838145 -0.0082310643
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -8.95772318e-05 0.00956364814 -0.010644556
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -8.95772318e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex -8.95772318e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -8.95772318e-05 0.00956364814 -0.010644556
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491211 -0.0350654013 -0.0115261674
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491211 -0.0350654013 -0.0115261674
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108619863 0.000361838145 -0.0082310643
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00420491211 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00420491211 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00420491211 -0.0350654013 -0.0115261674
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00867131911 -0.0342117175 -0.00454189023
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081594 -0.00115589425
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081594 -0.00115589425
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081594 -0.00115589425
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081594 -0.00115589425
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081594 -0.00115589425
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081594 -0.00115589425
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link15_R.STL b/assets/inspire_hand/meshes/Link15_R.STL
new file mode 100644
index 0000000..cbfc711
Binary files /dev/null and b/assets/inspire_hand/meshes/Link15_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link15_R.STL.convex.stl b/assets/inspire_hand/meshes/Link15_R.STL.convex.stl
new file mode 100644
index 0000000..3b1d036
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link15_R.STL.convex.stl
@@ -0,0 +1,546 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110861389 -0.000378863217 -0.00735513913
+ vertex 0.00969857723 0.000339805934 -0.0103491098
+ vertex 0.00714588352 0.0312779732 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110861389 -0.000378863217 -0.00735513913
+ vertex 0.00714588352 0.0312779732 -0.0111587103
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ vertex -0.00294619892 0.0356219411 -0.00959999952
+ vertex -0.00237921625 0.0354530029 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ vertex 0.00839306135 0.0320879295 -0.00246613892
+ vertex 0.0108642885 -0.000297273858 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ vertex 0.0108642885 -0.000297273858 -0.00376997283
+ vertex 0.0110861389 -0.000378863217 -0.00735513913
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00240866793 -0.00912777707 0.00101274764
+ vertex -3.32920863e-05 -0.0095640095 -0.00135544734
+ vertex 0.00529770553 -0.00942438561 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00240866793 -0.00912777707 0.00101274764
+ vertex -0.00131760468 -0.00935053267 -0.0129493466
+ vertex -3.32920863e-05 -0.0095640095 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00454500411 0.0260760244 0.000795508327
+ vertex -0.00237921625 0.0354530029 -0.000235040148
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00952934101 -0.00374514144 -0.00194311794
+ vertex 0.00839306135 0.0320879295 -0.00246613892
+ vertex 0.00547963381 0.0319181234 -0.000330381503
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00952934101 -0.00374514144 -0.00194311794
+ vertex 0.00547963381 0.0319181234 -0.000330381503
+ vertex 0.00454500411 0.0260760244 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00529770553 -0.00942438561 -0.010652706
+ vertex 0.00529770553 -0.00942438561 -0.0013472935
+ vertex -3.32920863e-05 -0.0095640095 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00529770553 -0.00942438561 -0.010652706
+ vertex -3.32920863e-05 -0.0095640095 -0.00135544734
+ vertex -0.00131760468 -0.00935053267 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0100590708 0.00729298685 -0.00750395935
+ vertex -0.00989039615 0.00725485617 -0.0030129645
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0100590708 0.00729298685 -0.00750395935
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ vertex -0.00611816999 0.0328985304 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0100590708 0.00729298685 -0.00750395935
+ vertex -0.00857000705 -0.00407290878 -0.0120279966
+ vertex -0.00902691763 -0.00298983883 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00139594474 0.0351516195 -0.0118842013
+ vertex 0.00714588352 0.0312779732 -0.0111587103
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00139594474 0.0351516195 -0.0118842013
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ vertex -0.00471251877 0.0341851227 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00139594474 0.0351516195 -0.0118842013
+ vertex -0.00471251877 0.0341851227 -0.0120000001
+ vertex -0.00294619892 0.0356219411 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00139594474 0.0351516195 -0.0118842013
+ vertex -0.00294619892 0.0356219411 -0.00959999952
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794159342 0.0340190455 -0.00334804319
+ vertex 0.00839306135 0.0320879295 -0.00246613892
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794159342 0.0340190455 -0.00334804319
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ vertex -0.00237921625 0.0354530029 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00575273717 -0.00764227053 -0.0105823008
+ vertex -0.00131760468 -0.00935053267 -0.0129493466
+ vertex -0.00240866793 -0.00912777707 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606697379 -0.00723772869 -0.0128938593
+ vertex -0.00131760468 -0.00935053267 -0.0129493466
+ vertex -0.00575273717 -0.00764227053 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606697379 -0.00723772869 -0.0128938593
+ vertex -0.00471251877 0.0341851227 -0.0120000001
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606697379 -0.00723772869 -0.0128938593
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ vertex -0.00131760468 -0.00935053267 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615712348 -0.00716200285 0.000882193504
+ vertex -0.00902691763 -0.00298983883 -0.000362366845
+ vertex -0.00857000705 -0.00407290878 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615712348 -0.00716200285 0.000882193504
+ vertex -0.00857000705 -0.00407290878 -0.0120279966
+ vertex -0.00606697379 -0.00723772869 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615712348 -0.00716200285 0.000882193504
+ vertex -0.00606697379 -0.00723772869 -0.0128938593
+ vertex -0.00575273717 -0.00764227053 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615712348 -0.00716200285 0.000882193504
+ vertex -0.00575273717 -0.00764227053 -0.0105823008
+ vertex -0.00240866793 -0.00912777707 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615712348 -0.00716200285 0.000882193504
+ vertex -0.00240866793 -0.00912777707 0.00101274764
+ vertex 0.00454500411 0.0260760244 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615712348 -0.00716200285 0.000882193504
+ vertex 0.00454500411 0.0260760244 0.000795508327
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615712348 -0.00716200285 0.000882193504
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ vertex -0.00902691763 -0.00298983883 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00547963381 0.0319181234 -0.000330381503
+ vertex -0.00237921625 0.0354530029 -0.000235040148
+ vertex 0.00454500411 0.0260760244 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00547963381 0.0319181234 -0.000330381503
+ vertex 0.00839306135 0.0320879295 -0.00246613892
+ vertex 0.00794159342 0.0340190455 -0.00334804319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00547963381 0.0319181234 -0.000330381503
+ vertex 0.00794159342 0.0340190455 -0.00334804319
+ vertex -0.00237921625 0.0354530029 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00463572005 -0.00773072382 0.000137225317
+ vertex 0.00952934101 -0.00374514144 -0.00194311794
+ vertex 0.00454500411 0.0260760244 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00463572005 -0.00773072382 0.000137225317
+ vertex 0.00454500411 0.0260760244 0.000795508327
+ vertex -0.00240866793 -0.00912777707 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00463572005 -0.00773072382 0.000137225317
+ vertex -0.00240866793 -0.00912777707 0.00101274764
+ vertex 0.00529770553 -0.00942438561 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00463572005 -0.00773072382 0.000137225317
+ vertex 0.00529770553 -0.00942438561 -0.0013472935
+ vertex 0.00952934101 -0.00374514144 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00989039615 0.00725485617 -0.0030129645
+ vertex -0.0100590708 0.00729298685 -0.00750395935
+ vertex -0.00902691763 -0.00298983883 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00989039615 0.00725485617 -0.0030129645
+ vertex -0.00902691763 -0.00298983883 -0.000362366845
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00918386877 -0.00536073092 -0.00935241766
+ vertex 0.0110861389 -0.000378863217 -0.00735513913
+ vertex 0.0108642885 -0.000297273858 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00918386877 -0.00536073092 -0.00935241766
+ vertex 0.0108642885 -0.000297273858 -0.00376997283
+ vertex 0.00952934101 -0.00374514144 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00918386877 -0.00536073092 -0.00935241766
+ vertex 0.00952934101 -0.00374514144 -0.00194311794
+ vertex 0.00529770553 -0.00942438561 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00918386877 -0.00536073092 -0.00935241766
+ vertex 0.00529770553 -0.00942438561 -0.0013472935
+ vertex 0.00529770553 -0.00942438561 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00918386877 -0.00536073092 -0.00935241766
+ vertex 0.00529770553 -0.00942438561 -0.010652706
+ vertex 0.00766128488 -0.00578731857 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00969857723 0.000339805934 -0.0103491098
+ vertex 0.0110861389 -0.000378863217 -0.00735513913
+ vertex 0.00918386877 -0.00536073092 -0.00935241766
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00969857723 0.000339805934 -0.0103491098
+ vertex 0.00918386877 -0.00536073092 -0.00935241766
+ vertex 0.00766128488 -0.00578731857 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00969857723 0.000339805934 -0.0103491098
+ vertex 0.00766128488 -0.00578731857 -0.0112889735
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00969857723 0.000339805934 -0.0103491098
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ vertex 0.00714588352 0.0312779732 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460010022 0.0349203385 -0.000473832159
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ vertex -0.00237921625 0.0354530029 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460010022 0.0349203385 -0.000473832159
+ vertex -0.00237921625 0.0354530029 -0.000235040148
+ vertex -0.00294619892 0.0356219411 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460010022 0.0349203385 -0.000473832159
+ vertex -0.00294619892 0.0356219411 -0.00959999952
+ vertex -0.00471251877 0.0341851227 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460010022 0.0349203385 -0.000473832159
+ vertex -0.00471251877 0.0341851227 -0.0120000001
+ vertex -0.00611816999 0.0328985304 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460010022 0.0349203385 -0.000473832159
+ vertex -0.00611816999 0.0328985304 -0.00959999952
+ vertex -0.00577091472 0.0328120627 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00603099819 0.0323765352 -0.0117649594
+ vertex -0.00471251877 0.0341851227 -0.0120000001
+ vertex -0.00606697379 -0.00723772869 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00603099819 0.0323765352 -0.0117649594
+ vertex -0.00606697379 -0.00723772869 -0.0128938593
+ vertex -0.00857000705 -0.00407290878 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00603099819 0.0323765352 -0.0117649594
+ vertex -0.00857000705 -0.00407290878 -0.0120279966
+ vertex -0.0100590708 0.00729298685 -0.00750395935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00603099819 0.0323765352 -0.0117649594
+ vertex -0.0100590708 0.00729298685 -0.00750395935
+ vertex -0.00611816999 0.0328985304 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00603099819 0.0323765352 -0.0117649594
+ vertex -0.00611816999 0.0328985304 -0.00959999952
+ vertex -0.00471251877 0.0341851227 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108642885 -0.000297273858 -0.00376997283
+ vertex 0.00839306135 0.0320879295 -0.00246613892
+ vertex 0.00952934101 -0.00374514144 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00417021476 -0.00900808815 -0.0120935012
+ vertex 0.00766128488 -0.00578731857 -0.0112889735
+ vertex 0.00529770553 -0.00942438561 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00417021476 -0.00900808815 -0.0120935012
+ vertex 0.00529770553 -0.00942438561 -0.010652706
+ vertex -0.00131760468 -0.00935053267 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00417021476 -0.00900808815 -0.0120935012
+ vertex -0.00131760468 -0.00935053267 -0.0129493466
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00417021476 -0.00900808815 -0.0120935012
+ vertex 0.00361328642 0.0261948127 -0.0129556311
+ vertex 0.00766128488 -0.00578731857 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0072981366 0.0333599113 -0.0101199131
+ vertex 0.00714588352 0.0312779732 -0.0111587103
+ vertex -0.00139594474 0.0351516195 -0.0118842013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0072981366 0.0333599113 -0.0101199131
+ vertex -0.00139594474 0.0351516195 -0.0118842013
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0072981366 0.0333599113 -0.0101199131
+ vertex 0.00846727099 0.0342627876 -0.00745810941
+ vertex 0.00714588352 0.0312779732 -0.0111587103
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link16_L.STL b/assets/inspire_hand/meshes/Link16_L.STL
new file mode 100644
index 0000000..24a5a83
Binary files /dev/null and b/assets/inspire_hand/meshes/Link16_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link16_L.STL.convex.stl b/assets/inspire_hand/meshes/Link16_L.STL.convex.stl
new file mode 100644
index 0000000..0af258c
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link16_L.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00515188929 -0.0396574326 -0.00500000501
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499764 -0.024230402 -0.00135727332
+ vertex 0.0019755722 -0.0424995646 -0.00173989905
+ vertex 0.00175187166 -0.0442894101 -0.00325343711
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499764 -0.024230402 -0.00135727332
+ vertex 0.00175187166 -0.0442894101 -0.00325343711
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499764 -0.024230402 -0.00135727332
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ vertex 0.0109147215 -0.00338476407 -0.00599905197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499764 -0.024230402 -0.00135727332
+ vertex 0.0109147215 -0.00338476407 -0.00599905197
+ vertex 0.00980036985 -0.00276796333 -0.000782164396
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000478150789 -0.0445214137 -0.0078114639
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ vertex 0.00209764228 -0.0416203551 -0.0084653087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ vertex 0.0109147215 -0.00338476407 -0.00599905197
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ vertex 0.00980036985 -0.00276796333 -0.000782164396
+ vertex 0.0109147215 -0.00338476407 -0.00599905197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ vertex 0.0109147215 -0.00338476407 -0.00599905197
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000105201041 -0.0445730276 -0.00216108374
+ vertex 0.0019755722 -0.0424995646 -0.00173989905
+ vertex -0.00293275737 -0.0429493263 -0.00113914383
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00246403739 -0.0434137695 -0.00601525279
+ vertex 0.000478150789 -0.0445214137 -0.0078114639
+ vertex 0.00209764228 -0.0416203551 -0.0084653087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00246403739 -0.0434137695 -0.00601525279
+ vertex 0.00209764228 -0.0416203551 -0.0084653087
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00246403739 -0.0434137695 -0.00601525279
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695811
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ vertex -0.00515188929 -0.0396574326 -0.00500000501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695811
+ vertex -0.00515188929 -0.0396574326 -0.00500000501
+ vertex -0.00293275737 -0.0429493263 -0.00113914383
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695811
+ vertex -0.00293275737 -0.0429493263 -0.00113914383
+ vertex -0.00264506438 -0.0350661203 0.000425216655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695811
+ vertex -0.00264506438 -0.0350661203 0.000425216655
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501047261
+ vertex -0.00045522087 -0.0452524722 -0.00501047261
+ vertex 0.000105201041 -0.0445730276 -0.00216108374
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501047261
+ vertex 0.000105201041 -0.0445730276 -0.00216108374
+ vertex -0.00293275737 -0.0429493263 -0.00113914383
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501047261
+ vertex -0.00293275737 -0.0429493263 -0.00113914383
+ vertex -0.00515188929 -0.0396574326 -0.00500000501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501047261
+ vertex -0.00515188929 -0.0396574326 -0.00500000501
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ vertex 0.000478150789 -0.0445214137 -0.0078114639
+ vertex -0.00045522087 -0.0452524722 -0.00501047261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ vertex -0.00045522087 -0.0452524722 -0.00501047261
+ vertex -0.00283985701 -0.0443740748 -0.00501047261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00023808924 -0.00438925112 -0.0106756082
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00023808924 -0.00438925112 -0.0106756082
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00023808924 -0.00438925112 -0.0106756082
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex -0.00316523481 -0.0339629762 -0.0102867959
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00023808924 -0.00438925112 -0.0106756082
+ vertex -0.00316523481 -0.0339629762 -0.0102867959
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00980036985 -0.00276796333 -0.000782164396
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00736499764 -0.024230402 -0.00135727332
+ vertex 0.00980036985 -0.00276796333 -0.000782164396
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.0109147215 -0.00338476407 -0.00599905197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.0109147215 -0.00338476407 -0.00599905197
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ vertex 0.00914153177 -0.00528662559 -0.00953828637
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.00914153177 -0.00528662559 -0.00953828637
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371644
+ vertex -0.00316523481 -0.0339629762 -0.0102867959
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371644
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ vertex -0.00515188929 -0.0396574326 -0.00500000501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371644
+ vertex -0.00515188929 -0.0396574326 -0.00500000501
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371644
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex -0.00316523481 -0.0339629762 -0.0102867959
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832282
+ vertex -0.00316523481 -0.0339629762 -0.0102867959
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.00914153177 -0.00528662559 -0.00953828637
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ vertex 0.00119875174 -0.0344842672 -0.0101832282
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832282
+ vertex 0.00736499764 -0.024230402 -0.00864272658
+ vertex 0.00209764228 -0.0416203551 -0.0084653087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832282
+ vertex 0.00209764228 -0.0416203551 -0.0084653087
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832282
+ vertex -0.00262691779 -0.0428678356 -0.00908724591
+ vertex -0.00316523481 -0.0339629762 -0.0102867959
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000147928309 -0.00439034216 0.000526889577
+ vertex -0.00264506438 -0.0350661203 0.000425216655
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000147928309 -0.00439034216 0.000526889577
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000147928309 -0.00439034216 0.000526889577
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000147928309 -0.00439034216 0.000526889577
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ vertex -0.00264506438 -0.0350661203 0.000425216655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 -0.0344835073 0.000181889976
+ vertex 0.0019755722 -0.0424995646 -0.00173989905
+ vertex 0.00736499764 -0.024230402 -0.00135727332
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 -0.0344835073 0.000181889976
+ vertex 0.00736499764 -0.024230402 -0.00135727332
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 -0.0344835073 0.000181889976
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 -0.0344835073 0.000181889976
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ vertex -0.00264506438 -0.0350661203 0.000425216655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 -0.0344835073 0.000181889976
+ vertex -0.00264506438 -0.0350661203 0.000425216655
+ vertex -0.00293275737 -0.0429493263 -0.00113914383
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 -0.0344835073 0.000181889976
+ vertex -0.00293275737 -0.0429493263 -0.00113914383
+ vertex 0.0019755722 -0.0424995646 -0.00173989905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175187166 -0.0442894101 -0.00325343711
+ vertex 0.000105201041 -0.0445730276 -0.00216108374
+ vertex -0.00045522087 -0.0452524722 -0.00501047261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175187166 -0.0442894101 -0.00325343711
+ vertex -0.00045522087 -0.0452524722 -0.00501047261
+ vertex 0.000478150789 -0.0445214137 -0.0078114639
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175187166 -0.0442894101 -0.00325343711
+ vertex 0.000478150789 -0.0445214137 -0.0078114639
+ vertex 0.00246403739 -0.0434137695 -0.00601525279
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175187166 -0.0442894101 -0.00325343711
+ vertex 0.00246403739 -0.0434137695 -0.00601525279
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175187166 -0.0442894101 -0.00325343711
+ vertex 0.0019755722 -0.0424995646 -0.00173989905
+ vertex 0.000105201041 -0.0445730276 -0.00216108374
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link16_R.STL b/assets/inspire_hand/meshes/Link16_R.STL
new file mode 100644
index 0000000..0cf0f8d
Binary files /dev/null and b/assets/inspire_hand/meshes/Link16_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link16_R.STL.convex.stl b/assets/inspire_hand/meshes/Link16_R.STL.convex.stl
new file mode 100644
index 0000000..2991589
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link16_R.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000533694401 -0.00646588905 -0.00795523357
+ vertex 0.00461455388 -0.0078816954 -0.00655000005
+ vertex 0.0045981491 -0.00775775034 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000533694401 -0.00646588905 -0.00795523357
+ vertex 0.0045981491 -0.00775775034 -0.00196253764
+ vertex -0.000246249343 -0.00587138068 -0.00204476598
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00556799024 0.0396011546 -0.00500000501
+ vertex -0.00286245858 -0.00181369204 -0.0080374619
+ vertex -0.00310016423 -0.000868190255 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000246249343 -0.00587138068 -0.00204476598
+ vertex 0.0045981491 -0.00775775034 -0.00196253764
+ vertex 0.00413053343 0.00183538313 0.00130476139
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000246249343 -0.00587138068 -0.00204476598
+ vertex -0.00310016423 -0.000868190255 -0.00196253764
+ vertex -0.00286245858 -0.00181369204 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000533694401 -0.00646588905 -0.00795523357
+ vertex -0.000246249343 -0.00587138068 -0.00204476598
+ vertex -0.00286245858 -0.00181369204 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00711019058 0.024306396 -0.00135728763
+ vertex 0.00766667956 0.0255492143 -0.00501046749
+ vertex 0.00128678093 0.0443053357 -0.00325343665
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00711019058 0.024306396 -0.00135728763
+ vertex 0.00128678093 0.0443053357 -0.00325343665
+ vertex 0.00152923691 0.0425179712 -0.00173989905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00977063458 0.00287061604 -0.000782011193
+ vertex 0.0108776335 0.00349663245 -0.0059987749
+ vertex 0.00766667956 0.0255492143 -0.00501046749
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00977063458 0.00287061604 -0.000782011193
+ vertex 0.00766667956 0.0255492143 -0.00501046749
+ vertex 0.00711019058 0.024306396 -0.00135728763
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 1.06695788e-05 0.0445239805 -0.00781146344
+ vertex 0.00166053197 0.0416400842 -0.00846530776
+ vertex -0.00307686627 0.0428378917 -0.00908724498
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00711019058 0.024306396 -0.00864271168
+ vertex 0.00766667956 0.0255492143 -0.00501046749
+ vertex 0.0108776335 0.00349663245 -0.0059987749
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00702064112 -0.00595007278 -0.00204476598
+ vertex 0.0045981491 -0.00775775034 -0.00196253764
+ vertex 0.00461455388 -0.0078816954 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00702064112 -0.00595007278 -0.00204476598
+ vertex 0.00461455388 -0.0078816954 -0.00655000005
+ vertex 0.00702064112 -0.00595007278 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00702064112 -0.00595007278 -0.00204476598
+ vertex 0.00702064112 -0.00595007278 -0.00795523357
+ vertex 0.0108776335 0.00349663245 -0.0059987749
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00702064112 -0.00595007278 -0.00204476598
+ vertex 0.0108776335 0.00349663245 -0.0059987749
+ vertex 0.00977063458 0.00287061604 -0.000782011193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000362801569 0.0445716791 -0.00216108351
+ vertex -0.00338354497 0.042916175 -0.00113914383
+ vertex 0.00152923691 0.0425179712 -0.00173989905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00200807629 0.0434372537 -0.00601525279
+ vertex 0.00166053197 0.0416400842 -0.00846530776
+ vertex 1.06695788e-05 0.0445239805 -0.00781146344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00200807629 0.0434372537 -0.00601525279
+ vertex 0.00766667956 0.0255492143 -0.00501046749
+ vertex 0.00711019058 0.024306396 -0.00864271168
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00200807629 0.0434372537 -0.00601525279
+ vertex 0.00711019058 0.024306396 -0.00864271168
+ vertex 0.00166053197 0.0416400842 -0.00846530776
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0045981491 -0.00775775034 -0.0080374619
+ vertex 0.00461455388 -0.0078816954 -0.00655000005
+ vertex 0.000533694401 -0.00646588905 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0045981491 -0.00775775034 -0.0080374619
+ vertex 0.000533694401 -0.00646588905 -0.00795523357
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0045981491 -0.00775775034 -0.0080374619
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ vertex 0.00702064112 -0.00595007278 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0045981491 -0.00775775034 -0.0080374619
+ vertex 0.00702064112 -0.00595007278 -0.00795523357
+ vertex 0.00461455388 -0.0078816954 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00498324633 0.0355757214 -0.00131695799
+ vertex -0.00301309722 0.0350364186 0.000425216625
+ vertex -0.00338354497 0.042916175 -0.00113914383
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00498324633 0.0355757214 -0.00131695799
+ vertex -0.00338354497 0.042916175 -0.00113914383
+ vertex -0.00556799024 0.0396011546 -0.00500000501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00498324633 0.0355757214 -0.00131695799
+ vertex -0.00556799024 0.0396011546 -0.00500000501
+ vertex -0.00310016423 -0.000868190255 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00498324633 0.0355757214 -0.00131695799
+ vertex -0.00310016423 -0.000868190255 -0.00196253764
+ vertex -0.00301309722 0.0350364186 0.000425216625
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00330580538 0.0443420075 -0.00500000501
+ vertex -0.00307686627 0.0428378917 -0.00908724498
+ vertex -0.00556799024 0.0396011546 -0.00500000501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00330580538 0.0443420075 -0.00500000501
+ vertex -0.00556799024 0.0396011546 -0.00500000501
+ vertex -0.00338354497 0.042916175 -0.00113914383
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00330580538 0.0443420075 -0.00500000501
+ vertex -0.00338354497 0.042916175 -0.00113914383
+ vertex -0.000362801569 0.0445716791 -0.00216108351
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00330580538 0.0443420075 -0.00500000501
+ vertex -0.000362801569 0.0445716791 -0.00216108351
+ vertex -0.000930326583 0.0452452041 -0.00501047214
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00330580538 0.0443420075 -0.00500000501
+ vertex -0.000930326583 0.0452452041 -0.00501047214
+ vertex 1.06695788e-05 0.0445239805 -0.00781146344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00330580538 0.0443420075 -0.00500000501
+ vertex 1.06695788e-05 0.0445239805 -0.00781146344
+ vertex -0.00307686627 0.0428378917 -0.00908724498
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000191967585 0.00439150631 -0.0106755998
+ vertex -0.00352165638 0.0339278691 -0.010286795
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000191967585 0.00439150631 -0.0106755998
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ vertex 0.000533694401 -0.00646588905 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000191967585 0.00439150631 -0.0106755998
+ vertex 0.000533694401 -0.00646588905 -0.00795523357
+ vertex -0.00286245858 -0.00181369204 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000191967585 0.00439150631 -0.0106755998
+ vertex -0.00286245858 -0.00181369204 -0.0080374619
+ vertex -0.00352165638 0.0339278691 -0.010286795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00720940065 0.00093961641 0.000908746268
+ vertex 0.00413053343 0.00183538313 0.00130476139
+ vertex 0.0045981491 -0.00775775034 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00720940065 0.00093961641 0.000908746268
+ vertex 0.0045981491 -0.00775775034 -0.00196253764
+ vertex 0.00702064112 -0.00595007278 -0.00204476598
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00720940065 0.00093961641 0.000908746268
+ vertex 0.00702064112 -0.00595007278 -0.00204476598
+ vertex 0.00977063458 0.00287061604 -0.000782011193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00720940065 0.00093961641 0.000908746268
+ vertex 0.00977063458 0.00287061604 -0.000782011193
+ vertex 0.00711019058 0.024306396 -0.00135728763
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00996286701 0.00295509654 -0.00897325575
+ vertex 0.00908555463 0.00538199767 -0.00953829568
+ vertex 0.00711019058 0.024306396 -0.00864271168
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00996286701 0.00295509654 -0.00897325575
+ vertex 0.00711019058 0.024306396 -0.00864271168
+ vertex 0.0108776335 0.00349663245 -0.0059987749
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00996286701 0.00295509654 -0.00897325575
+ vertex 0.0108776335 0.00349663245 -0.0059987749
+ vertex 0.00702064112 -0.00595007278 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00996286701 0.00295509654 -0.00897325575
+ vertex 0.00702064112 -0.00595007278 -0.00795523357
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00996286701 0.00295509654 -0.00897325575
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ vertex 0.00908555463 0.00538199767 -0.00953829568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00486271596 0.0387601182 -0.00850408617
+ vertex -0.00556799024 0.0396011546 -0.00500000501
+ vertex -0.00307686627 0.0428378917 -0.00908724498
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00486271596 0.0387601182 -0.00850408617
+ vertex -0.00307686627 0.0428378917 -0.00908724498
+ vertex -0.00352165638 0.0339278691 -0.010286795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00486271596 0.0387601182 -0.00850408617
+ vertex -0.00352165638 0.0339278691 -0.010286795
+ vertex -0.00286245858 -0.00181369204 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00486271596 0.0387601182 -0.00850408617
+ vertex -0.00286245858 -0.00181369204 -0.0080374619
+ vertex -0.00556799024 0.0396011546 -0.00500000501
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000836616324 0.0344949514 -0.0101832282
+ vertex 0.00166053197 0.0416400842 -0.00846530776
+ vertex 0.00711019058 0.024306396 -0.00864271168
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000836616324 0.0344949514 -0.0101832282
+ vertex 0.00711019058 0.024306396 -0.00864271168
+ vertex 0.00908555463 0.00538199767 -0.00953829568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000836616324 0.0344949514 -0.0101832282
+ vertex 0.00908555463 0.00538199767 -0.00953829568
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000836616324 0.0344949514 -0.0101832282
+ vertex 0.00562526798 0.000733521942 -0.0112177758
+ vertex -0.00352165638 0.0339278691 -0.010286795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000836616324 0.0344949514 -0.0101832282
+ vertex -0.00352165638 0.0339278691 -0.010286795
+ vertex -0.00307686627 0.0428378917 -0.00908724498
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000836616324 0.0344949514 -0.0101832282
+ vertex -0.00307686627 0.0428378917 -0.00908724498
+ vertex 0.00166053197 0.0416400842 -0.00846530776
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000552989659 0.00435586227 0.000362147897
+ vertex -0.00310016423 -0.000868190255 -0.00196253764
+ vertex -0.000246249343 -0.00587138068 -0.00204476598
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000552989659 0.00435586227 0.000362147897
+ vertex -0.000246249343 -0.00587138068 -0.00204476598
+ vertex 0.00413053343 0.00183538313 0.00130476139
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000552989659 0.00435586227 0.000362147897
+ vertex 0.00413053343 0.00183538313 0.00130476139
+ vertex -0.00301309722 0.0350364186 0.000425216625
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000552989659 0.00435586227 0.000362147897
+ vertex -0.00301309722 0.0350364186 0.000425216625
+ vertex -0.00310016423 -0.000868190255 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000841794594 0.034494251 0.000181889976
+ vertex -0.00301309722 0.0350364186 0.000425216625
+ vertex 0.00413053343 0.00183538313 0.00130476139
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000841794594 0.034494251 0.000181889976
+ vertex 0.00413053343 0.00183538313 0.00130476139
+ vertex 0.00720940065 0.00093961641 0.000908746268
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000841794594 0.034494251 0.000181889976
+ vertex 0.00720940065 0.00093961641 0.000908746268
+ vertex 0.00711019058 0.024306396 -0.00135728763
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000841794594 0.034494251 0.000181889976
+ vertex 0.00711019058 0.024306396 -0.00135728763
+ vertex 0.00152923691 0.0425179712 -0.00173989905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00152923691 0.0425179712 -0.00173989905
+ vertex -0.00338354497 0.042916175 -0.00113914383
+ vertex -0.00301309722 0.0350364186 0.000425216625
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00152923691 0.0425179712 -0.00173989905
+ vertex -0.00301309722 0.0350364186 0.000425216625
+ vertex 0.000841794594 0.034494251 0.000181889976
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00128678093 0.0443053357 -0.00325343665
+ vertex 0.00766667956 0.0255492143 -0.00501046749
+ vertex 0.00200807629 0.0434372537 -0.00601525279
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00128678093 0.0443053357 -0.00325343665
+ vertex 0.00200807629 0.0434372537 -0.00601525279
+ vertex 1.06695788e-05 0.0445239805 -0.00781146344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00128678093 0.0443053357 -0.00325343665
+ vertex 1.06695788e-05 0.0445239805 -0.00781146344
+ vertex -0.000930326583 0.0452452041 -0.00501047214
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00128678093 0.0443053357 -0.00325343665
+ vertex -0.000930326583 0.0452452041 -0.00501047214
+ vertex -0.000362801569 0.0445716791 -0.00216108351
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00128678093 0.0443053357 -0.00325343665
+ vertex -0.000362801569 0.0445716791 -0.00216108351
+ vertex 0.00152923691 0.0425179712 -0.00173989905
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link17_L.STL b/assets/inspire_hand/meshes/Link17_L.STL
new file mode 100644
index 0000000..8f0aca6
Binary files /dev/null and b/assets/inspire_hand/meshes/Link17_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link17_L.STL.convex.stl b/assets/inspire_hand/meshes/Link17_L.STL.convex.stl
new file mode 100644
index 0000000..2d8b7ae
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link17_L.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00479577668 -0.0338946246 5.2154045e-11
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link17_R.STL b/assets/inspire_hand/meshes/Link17_R.STL
new file mode 100644
index 0000000..3f630a3
Binary files /dev/null and b/assets/inspire_hand/meshes/Link17_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link17_R.STL.convex.stl b/assets/inspire_hand/meshes/Link17_R.STL.convex.stl
new file mode 100644
index 0000000..d2327d5
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link17_R.STL.convex.stl
@@ -0,0 +1,546 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link18_L.STL b/assets/inspire_hand/meshes/Link18_L.STL
new file mode 100644
index 0000000..c498cd7
Binary files /dev/null and b/assets/inspire_hand/meshes/Link18_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link18_L.STL.convex.stl b/assets/inspire_hand/meshes/Link18_L.STL.convex.stl
new file mode 100644
index 0000000..aa109fa
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link18_L.STL.convex.stl
@@ -0,0 +1,562 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00785195176 -0.00114718347 0.000622928434
+ vertex 0.00684994413 0.00625092397 -0.00194999995
+ vertex 0.00352098979 0.00781226018 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00785195176 -0.00114718347 0.000622928434
+ vertex 0.00352098979 0.00781226018 -0.00194999995
+ vertex 0.00425272947 -0.00136824825 0.0012896586
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00348394318 -0.0464657098 -0.00866564829
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ vertex 0.000945500098 -0.045971062 -0.00847050827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 0.00625092397 -0.00194999995
+ vertex 0.00482661044 0.00780385919 -0.0080500003
+ vertex 0.00352098979 0.00781226018 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00179568853 0.00400286447 -0.0080500003
+ vertex -0.00329021341 -0.000294465688 -0.0080500003
+ vertex -0.00297910022 0.00163070788 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108309751 -0.00338516408 -0.00382230268
+ vertex 0.00741339987 -0.0274300165 -0.00640348811
+ vertex 0.00956390705 -0.0024317808 -0.009397652
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ vertex 0.00741339987 -0.0274300165 -0.00640348811
+ vertex 0.0108309751 -0.00338516408 -0.00382230268
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00170417153 -0.0470251665 -0.00432559848
+ vertex 0.000945500098 -0.045971062 -0.00847050827
+ vertex 0.00741339987 -0.0274300165 -0.00640348811
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00170417153 -0.0470251665 -0.00432559848
+ vertex 0.00741339987 -0.0274300165 -0.00640348811
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00170417153 -0.0470251665 -0.00432559848
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ vertex 0.000803421717 -0.0448982716 -0.0011340176
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00785195176 -0.00114718347 0.000622928434
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ vertex 0.00945101306 -0.00639001559 -0.000988014159
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000231103302 -0.0479141213 -0.00217640051
+ vertex 0.000803421717 -0.0448982716 -0.0011340176
+ vertex -0.00362309464 -0.0460432917 -0.00114539859
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000231103302 -0.0479141213 -0.00217640051
+ vertex -0.00106206862 -0.0486834012 -0.00498936092
+ vertex 0.00170417153 -0.0470251665 -0.00432559848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000231103302 -0.0479141213 -0.00217640051
+ vertex 0.00170417153 -0.0470251665 -0.00432559848
+ vertex 0.000803421717 -0.0448982716 -0.0011340176
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00660658581 -0.0260562394 -0.00903558172
+ vertex 0.00741339987 -0.0274300165 -0.00640348811
+ vertex 0.000945500098 -0.045971062 -0.00847050827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00660658581 -0.0260562394 -0.00903558172
+ vertex 0.000945500098 -0.045971062 -0.00847050827
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00660658581 -0.0260562394 -0.00903558172
+ vertex 0.00956390705 -0.0024317808 -0.009397652
+ vertex 0.00741339987 -0.0274300165 -0.00640348811
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075171 -0.0379645266 -0.00386957778
+ vertex -0.00297910022 0.00163070788 -0.00194999995
+ vertex -0.00329021341 -0.000294465688 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075171 -0.0379645266 -0.00386957778
+ vertex -0.00537315896 -0.0438657291 -0.00609957427
+ vertex -0.00362309464 -0.0460432917 -0.00114539859
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075171 -0.0379645266 -0.00386957778
+ vertex -0.00362309464 -0.0460432917 -0.00114539859
+ vertex -0.00429608254 -0.0362734646 -8.88538707e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075171 -0.0379645266 -0.00386957778
+ vertex -0.00429608254 -0.0362734646 -8.88538707e-05
+ vertex -0.00297910022 0.00163070788 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 0.00625092397 -0.0080500003
+ vertex 0.00482661044 0.00780385919 -0.0080500003
+ vertex 0.00684994413 0.00625092397 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 0.00625092397 -0.0080500003
+ vertex 0.00684994413 0.00625092397 -0.00194999995
+ vertex 0.0108309751 -0.00338516408 -0.00382230268
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 0.00625092397 -0.0080500003
+ vertex 0.0108309751 -0.00338516408 -0.00382230268
+ vertex 0.00956390705 -0.0024317808 -0.009397652
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019712052 -0.0482121818 -0.00742312986
+ vertex -0.00106206862 -0.0486834012 -0.00498936092
+ vertex -0.00346547272 -0.0476887561 -0.00498895114
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019712052 -0.0482121818 -0.00742312986
+ vertex -0.00346547272 -0.0476887561 -0.00498895114
+ vertex -0.00348394318 -0.0464657098 -0.00866564829
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019712052 -0.0482121818 -0.00742312986
+ vertex -0.00348394318 -0.0464657098 -0.00866564829
+ vertex 0.000945500098 -0.045971062 -0.00847050827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019712052 -0.0482121818 -0.00742312986
+ vertex 0.000945500098 -0.045971062 -0.00847050827
+ vertex 0.00170417153 -0.0470251665 -0.00432559848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019712052 -0.0482121818 -0.00742312986
+ vertex 0.00170417153 -0.0470251665 -0.00432559848
+ vertex -0.00106206862 -0.0486834012 -0.00498936092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 -0.0379122607 -0.00868305005
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ vertex -0.00348394318 -0.0464657098 -0.00866564829
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 -0.0379122607 -0.00868305005
+ vertex -0.00348394318 -0.0464657098 -0.00866564829
+ vertex -0.00537315896 -0.0438657291 -0.00609957427
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 -0.0379122607 -0.00868305005
+ vertex -0.00537315896 -0.0438657291 -0.00609957427
+ vertex -0.00601075171 -0.0379645266 -0.00386957778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 -0.0379122607 -0.00868305005
+ vertex -0.00601075171 -0.0379645266 -0.00386957778
+ vertex -0.00329021341 -0.000294465688 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 -0.0379122607 -0.00868305005
+ vertex -0.00329021341 -0.000294465688 -0.0080500003
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346547272 -0.0476887561 -0.00498895114
+ vertex -0.00362309464 -0.0460432917 -0.00114539859
+ vertex -0.00537315896 -0.0438657291 -0.00609957427
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346547272 -0.0476887561 -0.00498895114
+ vertex -0.00537315896 -0.0438657291 -0.00609957427
+ vertex -0.00348394318 -0.0464657098 -0.00866564829
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346547272 -0.0476887561 -0.00498895114
+ vertex -0.00106206862 -0.0486834012 -0.00498936092
+ vertex -0.000231103302 -0.0479141213 -0.00217640051
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346547272 -0.0476887561 -0.00498895114
+ vertex -0.000231103302 -0.0479141213 -0.00217640051
+ vertex -0.00362309464 -0.0460432917 -0.00114539859
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00694435043 -0.000579302781 -0.0109616714
+ vertex 0.00425273553 -0.00136823952 -0.011289659
+ vertex 0.00482661044 0.00780385919 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00694435043 -0.000579302781 -0.0109616714
+ vertex 0.00482661044 0.00780385919 -0.0080500003
+ vertex 0.00684994413 0.00625092397 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00694435043 -0.000579302781 -0.0109616714
+ vertex 0.00684994413 0.00625092397 -0.0080500003
+ vertex 0.00956390705 -0.0024317808 -0.009397652
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00694435043 -0.000579302781 -0.0109616714
+ vertex 0.00956390705 -0.0024317808 -0.009397652
+ vertex 0.00660658581 -0.0260562394 -0.00903558172
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00694435043 -0.000579302781 -0.0109616714
+ vertex 0.00660658581 -0.0260562394 -0.00903558172
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00694435043 -0.000579302781 -0.0109616714
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ vertex 0.00425273553 -0.00136823952 -0.011289659
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00179568853 0.00400286447 -0.00194999995
+ vertex -0.00179568853 0.00400286447 -0.0080500003
+ vertex -0.00297910022 0.00163070788 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00179568853 0.00400286447 -0.00194999995
+ vertex 0.00425272947 -0.00136824825 0.0012896586
+ vertex 0.00352098979 0.00781226018 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000332680356 -0.00416069012 0.00049520086
+ vertex 0.00425272947 -0.00136824825 0.0012896586
+ vertex -0.00179568853 0.00400286447 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000332680356 -0.00416069012 0.00049520086
+ vertex -0.00179568853 0.00400286447 -0.00194999995
+ vertex -0.00297910022 0.00163070788 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000332680356 -0.00416069012 0.00049520086
+ vertex -0.00297910022 0.00163070788 -0.00194999995
+ vertex -0.00429608254 -0.0362734646 -8.88538707e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887298 -0.0371798053 0.000454035471
+ vertex 0.000803421717 -0.0448982716 -0.0011340176
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887298 -0.0371798053 0.000454035471
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ vertex 0.00785195176 -0.00114718347 0.000622928434
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887298 -0.0371798053 0.000454035471
+ vertex 0.00785195176 -0.00114718347 0.000622928434
+ vertex 0.00425272947 -0.00136824825 0.0012896586
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00425272947 -0.00136824825 0.0012896586
+ vertex -0.000332680356 -0.00416069012 0.00049520086
+ vertex -0.00429608254 -0.0362734646 -8.88538707e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00425272947 -0.00136824825 0.0012896586
+ vertex -0.00429608254 -0.0362734646 -8.88538707e-05
+ vertex -0.00135887298 -0.0371798053 0.000454035471
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887298 -0.0371798053 0.000454035471
+ vertex -0.00429608254 -0.0362734646 -8.88538707e-05
+ vertex -0.00362309464 -0.0460432917 -0.00114539859
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887298 -0.0371798053 0.000454035471
+ vertex -0.00362309464 -0.0460432917 -0.00114539859
+ vertex 0.000803421717 -0.0448982716 -0.0011340176
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000594260986 -0.00412405981 -0.0103763435
+ vertex -0.00329021341 -0.000294465688 -0.0080500003
+ vertex -0.00179568853 0.00400286447 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000594260986 -0.00412405981 -0.0103763435
+ vertex -0.00179568853 0.00400286447 -0.0080500003
+ vertex 0.00425273553 -0.00136823952 -0.011289659
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000594260986 -0.00412405981 -0.0103763435
+ vertex 0.00425273553 -0.00136823952 -0.011289659
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000594260986 -0.00412405981 -0.0103763435
+ vertex -0.0032280439 -0.0374012291 -0.0104252258
+ vertex -0.00329021341 -0.000294465688 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100857047 -0.00282484386 -0.00126572093
+ vertex 0.0108309751 -0.00338516408 -0.00382230268
+ vertex 0.00684994413 0.00625092397 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100857047 -0.00282484386 -0.00126572093
+ vertex 0.00684994413 0.00625092397 -0.00194999995
+ vertex 0.00785195176 -0.00114718347 0.000622928434
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100857047 -0.00282484386 -0.00126572093
+ vertex 0.00785195176 -0.00114718347 0.000622928434
+ vertex 0.00945101306 -0.00639001559 -0.000988014159
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100857047 -0.00282484386 -0.00126572093
+ vertex 0.00945101306 -0.00639001559 -0.000988014159
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100857047 -0.00282484386 -0.00126572093
+ vertex 0.0071618217 -0.0260333885 -0.00165918644
+ vertex 0.0108309751 -0.00338516408 -0.00382230268
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00284345518 0.00753048901 -0.0080500003
+ vertex 0.00482661044 0.00780385919 -0.0080500003
+ vertex 0.00425273553 -0.00136823952 -0.011289659
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00284345518 0.00753048901 -0.0080500003
+ vertex 0.00425273553 -0.00136823952 -0.011289659
+ vertex -0.00179568853 0.00400286447 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00284345518 0.00753048901 -0.0080500003
+ vertex -0.00179568853 0.00400286447 -0.0080500003
+ vertex -0.00179568853 0.00400286447 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00284345518 0.00753048901 -0.0080500003
+ vertex -0.00179568853 0.00400286447 -0.00194999995
+ vertex 0.00352098979 0.00781226018 -0.00194999995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00284345518 0.00753048901 -0.0080500003
+ vertex 0.00352098979 0.00781226018 -0.00194999995
+ vertex 0.00482661044 0.00780385919 -0.0080500003
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link18_R.STL b/assets/inspire_hand/meshes/Link18_R.STL
new file mode 100644
index 0000000..ebc2616
Binary files /dev/null and b/assets/inspire_hand/meshes/Link18_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link18_R.STL.convex.stl b/assets/inspire_hand/meshes/Link18_R.STL.convex.stl
new file mode 100644
index 0000000..3b16fa2
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link18_R.STL.convex.stl
@@ -0,0 +1,562 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00425203284 0.00136753358 0.00128968828
+ vertex 0.00352098979 -0.00781226018 -0.00195000006
+ vertex 0.00684994413 -0.00625092397 -0.00195000006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00425203284 0.00136753358 0.00128968828
+ vertex 0.00684994413 -0.00625092397 -0.00195000006
+ vertex 0.00789308175 0.00117731874 0.000602744869
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00348394318 0.0464657098 -0.00866564829
+ vertex 0.000945500156 0.045971062 -0.0084705092
+ vertex -0.00322804367 0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 -0.00625092397 -0.00195000006
+ vertex 0.00352098979 -0.00781226018 -0.00195000006
+ vertex 0.00482660998 -0.00780385919 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00179568853 -0.00400286447 -0.0080500003
+ vertex -0.00297909998 -0.00163070788 -0.00195000006
+ vertex -0.00329021341 0.000294465688 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.010830109 0.00338448002 -0.00381393521
+ vertex 0.00954072271 0.00241398718 -0.00942106359
+ vertex 0.00741339941 0.0274300165 -0.00640348811
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ vertex 0.010830109 0.00338448002 -0.00381393521
+ vertex 0.00741339941 0.0274300165 -0.00640348811
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00170418224 0.0470251404 -0.00432557892
+ vertex 0.000803428993 0.0448982716 -0.00113402226
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00170418224 0.0470251404 -0.00432557892
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ vertex 0.00741339941 0.0274300165 -0.00640348811
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00170418224 0.0470251404 -0.00432557892
+ vertex 0.00741339941 0.0274300165 -0.00640348811
+ vertex 0.000945500156 0.045971062 -0.0084705092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00789308175 0.00117731874 0.000602744869
+ vertex 0.00945102237 0.00639002165 -0.000988031388
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000229901198 0.0479248092 -0.00218855543
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ vertex 0.000803428993 0.0448982716 -0.00113402226
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000229901198 0.0479248092 -0.00218855543
+ vertex 0.000803428993 0.0448982716 -0.00113402226
+ vertex 0.00170418224 0.0470251404 -0.00432557892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000229901198 0.0479248092 -0.00218855543
+ vertex 0.00170418224 0.0470251404 -0.00432557892
+ vertex -0.00106206862 0.0486834012 -0.00498936092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00660658581 0.0260562394 -0.00903558079
+ vertex 0.000945500156 0.045971062 -0.0084705092
+ vertex 0.00741339941 0.0274300165 -0.00640348811
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00660658581 0.0260562394 -0.00903558079
+ vertex 0.00741339941 0.0274300165 -0.00640348811
+ vertex 0.00954072271 0.00241398718 -0.00942106359
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075124 0.0379645266 -0.00386957778
+ vertex -0.00429608254 0.0362734646 -8.88538707e-05
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075124 0.0379645266 -0.00386957778
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ vertex -0.00537315477 0.0438657515 -0.00609957427
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075124 0.0379645266 -0.00386957778
+ vertex -0.00329021341 0.000294465688 -0.0080500003
+ vertex -0.00297909998 -0.00163070788 -0.00195000006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00601075124 0.0379645266 -0.00386957778
+ vertex -0.00297909998 -0.00163070788 -0.00195000006
+ vertex -0.00429608254 0.0362734646 -8.88538707e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 -0.00625092397 -0.0080500003
+ vertex 0.00954072271 0.00241398718 -0.00942106359
+ vertex 0.010830109 0.00338448002 -0.00381393521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 -0.00625092397 -0.0080500003
+ vertex 0.010830109 0.00338448002 -0.00381393521
+ vertex 0.00684994413 -0.00625092397 -0.00195000006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684994413 -0.00625092397 -0.0080500003
+ vertex 0.00684994413 -0.00625092397 -0.00195000006
+ vertex 0.00482660998 -0.00780385919 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019711908 0.0482121892 -0.00742312474
+ vertex 0.000945500156 0.045971062 -0.0084705092
+ vertex -0.00348394318 0.0464657098 -0.00866564829
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019711908 0.0482121892 -0.00742312474
+ vertex -0.00348394318 0.0464657098 -0.00866564829
+ vertex -0.00346547249 0.0476887561 -0.00498895068
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019711908 0.0482121892 -0.00742312474
+ vertex -0.00346547249 0.0476887561 -0.00498895068
+ vertex -0.00106206862 0.0486834012 -0.00498936092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019711908 0.0482121892 -0.00742312474
+ vertex -0.00106206862 0.0486834012 -0.00498936092
+ vertex 0.00170418224 0.0470251404 -0.00432557892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00019711908 0.0482121892 -0.00742312474
+ vertex 0.00170418224 0.0470251404 -0.00432557892
+ vertex 0.000945500156 0.045971062 -0.0084705092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 0.0379122607 -0.00868305098
+ vertex -0.00329021341 0.000294465688 -0.0080500003
+ vertex -0.00601075124 0.0379645266 -0.00386957778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 0.0379122607 -0.00868305098
+ vertex -0.00601075124 0.0379645266 -0.00386957778
+ vertex -0.00537315477 0.0438657515 -0.00609957427
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 0.0379122607 -0.00868305098
+ vertex -0.00537315477 0.0438657515 -0.00609957427
+ vertex -0.00348394318 0.0464657098 -0.00866564829
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 0.0379122607 -0.00868305098
+ vertex -0.00348394318 0.0464657098 -0.00866564829
+ vertex -0.00322804367 0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00520672044 0.0379122607 -0.00868305098
+ vertex -0.00322804367 0.0374012291 -0.0104252258
+ vertex -0.00329021341 0.000294465688 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex 0.00954072271 0.00241398718 -0.00942106359
+ vertex 0.00684994413 -0.00625092397 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex 0.00684994413 -0.00625092397 -0.0080500003
+ vertex 0.00482660998 -0.00780385919 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex 0.00482660998 -0.00780385919 -0.0080500003
+ vertex 0.00284345518 -0.00753048901 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex 0.00284345518 -0.00753048901 -0.0080500003
+ vertex 0.00384663767 0.00182680297 -0.011280518
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex 0.00384663767 0.00182680297 -0.011280518
+ vertex -0.00322804367 0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex -0.00322804367 0.0374012291 -0.0104252258
+ vertex 0.000945500156 0.045971062 -0.0084705092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex 0.000945500156 0.045971062 -0.0084705092
+ vertex 0.00660658581 0.0260562394 -0.00903558079
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0069610551 0.000587038114 -0.0109570958
+ vertex 0.00660658581 0.0260562394 -0.00903558079
+ vertex 0.00954072271 0.00241398718 -0.00942106359
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346547249 0.0476887561 -0.00498895068
+ vertex -0.00348394318 0.0464657098 -0.00866564829
+ vertex -0.00537315477 0.0438657515 -0.00609957427
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00346547249 0.0476887561 -0.00498895068
+ vertex -0.00537315477 0.0438657515 -0.00609957427
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ vertex -0.000229901198 0.0479248092 -0.00218855543
+ vertex -0.00106206862 0.0486834012 -0.00498936092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ vertex -0.00106206862 0.0486834012 -0.00498936092
+ vertex -0.00346547249 0.0476887561 -0.00498895068
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00179568853 -0.00400286447 -0.00195000006
+ vertex -0.00297909998 -0.00163070788 -0.00195000006
+ vertex -0.00179568853 -0.00400286447 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00179568853 -0.00400286447 -0.00195000006
+ vertex 0.00352098979 -0.00781226018 -0.00195000006
+ vertex 0.00425203284 0.00136753358 0.00128968828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000328785944 0.00416125171 0.000496497261
+ vertex -0.00297909998 -0.00163070788 -0.00195000006
+ vertex -0.00179568853 -0.00400286447 -0.00195000006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000328785944 0.00416125171 0.000496497261
+ vertex -0.00179568853 -0.00400286447 -0.00195000006
+ vertex 0.00425203284 0.00136753358 0.00128968828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000328785944 0.00416125171 0.000496497261
+ vertex -0.00429608254 0.0362734646 -8.88538707e-05
+ vertex -0.00297909998 -0.00163070788 -0.00195000006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887286 0.0371798053 0.000454035471
+ vertex -0.00429608254 0.0362734646 -8.88538707e-05
+ vertex -0.000328785944 0.00416125171 0.000496497261
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887286 0.0371798053 0.000454035471
+ vertex -0.000328785944 0.00416125171 0.000496497261
+ vertex 0.00425203284 0.00136753358 0.00128968828
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887286 0.0371798053 0.000454035471
+ vertex 0.00425203284 0.00136753358 0.00128968828
+ vertex 0.00789308175 0.00117731874 0.000602744869
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887286 0.0371798053 0.000454035471
+ vertex 0.00789308175 0.00117731874 0.000602744869
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887286 0.0371798053 0.000454035471
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ vertex 0.000803428993 0.0448982716 -0.00113402226
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887286 0.0371798053 0.000454035471
+ vertex 0.000803428993 0.0448982716 -0.00113402226
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00135887286 0.0371798053 0.000454035471
+ vertex -0.00362309464 0.0460432917 -0.00114539848
+ vertex -0.00429608254 0.0362734646 -8.88538707e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000704927836 0.00410383474 -0.0103216479
+ vertex -0.00322804367 0.0374012291 -0.0104252258
+ vertex 0.00384663767 0.00182680297 -0.011280518
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000704927836 0.00410383474 -0.0103216479
+ vertex 0.00384663767 0.00182680297 -0.011280518
+ vertex -0.00179568853 -0.00400286447 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000704927836 0.00410383474 -0.0103216479
+ vertex -0.00179568853 -0.00400286447 -0.0080500003
+ vertex -0.00329021341 0.000294465688 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000704927836 0.00410383474 -0.0103216479
+ vertex -0.00329021341 0.000294465688 -0.0080500003
+ vertex -0.00322804367 0.0374012291 -0.0104252258
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00352098979 -0.00781226018 -0.00195000006
+ vertex -0.00179568853 -0.00400286447 -0.00195000006
+ vertex -0.00179568853 -0.00400286447 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00352098979 -0.00781226018 -0.00195000006
+ vertex -0.00179568853 -0.00400286447 -0.0080500003
+ vertex 0.00284345518 -0.00753048901 -0.0080500003
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00284345518 -0.00753048901 -0.0080500003
+ vertex -0.00179568853 -0.00400286447 -0.0080500003
+ vertex 0.00384663767 0.00182680297 -0.011280518
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00284345518 -0.00753048901 -0.0080500003
+ vertex 0.00482660998 -0.00780385919 -0.0080500003
+ vertex 0.00352098979 -0.00781226018 -0.00195000006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100740874 0.00281593273 -0.00124576711
+ vertex 0.00945102237 0.00639002165 -0.000988031388
+ vertex 0.00789308175 0.00117731874 0.000602744869
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100740874 0.00281593273 -0.00124576711
+ vertex 0.00789308175 0.00117731874 0.000602744869
+ vertex 0.00684994413 -0.00625092397 -0.00195000006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100740874 0.00281593273 -0.00124576711
+ vertex 0.00684994413 -0.00625092397 -0.00195000006
+ vertex 0.010830109 0.00338448002 -0.00381393521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100740874 0.00281593273 -0.00124576711
+ vertex 0.010830109 0.00338448002 -0.00381393521
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100740874 0.00281593273 -0.00124576711
+ vertex 0.00716182869 0.0260333885 -0.00165920611
+ vertex 0.00945102237 0.00639002165 -0.000988031388
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link19_L.STL b/assets/inspire_hand/meshes/Link19_L.STL
new file mode 100644
index 0000000..c3cabb9
Binary files /dev/null and b/assets/inspire_hand/meshes/Link19_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link19_L.STL.convex.stl b/assets/inspire_hand/meshes/Link19_L.STL.convex.stl
new file mode 100644
index 0000000..c2e5dae
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link19_L.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00479577668 -0.0338946246 5.21540693e-11
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link19_R.STL b/assets/inspire_hand/meshes/Link19_R.STL
new file mode 100644
index 0000000..5c3703e
Binary files /dev/null and b/assets/inspire_hand/meshes/Link19_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link19_R.STL.convex.stl b/assets/inspire_hand/meshes/Link19_R.STL.convex.stl
new file mode 100644
index 0000000..d2327d5
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link19_R.STL.convex.stl
@@ -0,0 +1,546 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link20_L.STL b/assets/inspire_hand/meshes/Link20_L.STL
new file mode 100644
index 0000000..23c4efa
Binary files /dev/null and b/assets/inspire_hand/meshes/Link20_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link20_L.STL.convex.stl b/assets/inspire_hand/meshes/Link20_L.STL.convex.stl
new file mode 100644
index 0000000..7cc68a4
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link20_L.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00515188929 -0.0396574326 -0.00500000035
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0073649832 -0.0242304057 -0.00135725073
+ vertex 0.0019755722 -0.0424995646 -0.00173989416
+ vertex 0.00175182836 -0.0442894548 -0.00325343222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0073649832 -0.0242304057 -0.00135725073
+ vertex 0.00175182836 -0.0442894548 -0.00325343222
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0073649832 -0.0242304057 -0.00135725073
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ vertex 0.0109100407 -0.00338321831 -0.00604098616
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0073649832 -0.0242304057 -0.00135725073
+ vertex 0.0109100407 -0.00338321831 -0.00604098616
+ vertex 0.00980036985 -0.00276796333 -0.000782165327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000478150701 -0.0445214137 -0.00781145925
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ vertex 0.00209764205 -0.0416203551 -0.00846530404
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ vertex 0.0109100407 -0.00338321831 -0.00604098616
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ vertex 0.00980036985 -0.00276796333 -0.000782165327
+ vertex 0.0109100407 -0.00338321831 -0.00604098616
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ vertex 0.0109100407 -0.00338321831 -0.00604098616
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000105200954 -0.0445730276 -0.00216107885
+ vertex 0.0019755722 -0.0424995646 -0.00173989416
+ vertex -0.0029327576 -0.0429493263 -0.00113913917
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00245129457 -0.0434379876 -0.00601699995
+ vertex 0.000478150701 -0.0445214137 -0.00781145925
+ vertex 0.00209764205 -0.0416203551 -0.00846530404
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00245129457 -0.0434379876 -0.00601699995
+ vertex 0.00209764205 -0.0416203551 -0.00846530404
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00245129457 -0.0434379876 -0.00601699995
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 0.00780560076 -0.0080374619
+ vertex 0.0045315451 0.00792971067 -0.00655000005
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695333
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ vertex -0.00515188929 -0.0396574326 -0.00500000035
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695333
+ vertex -0.00515188929 -0.0396574326 -0.00500000035
+ vertex -0.0029327576 -0.0429493263 -0.00113913917
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695333
+ vertex -0.0029327576 -0.0429493263 -0.00113913917
+ vertex -0.00264506438 -0.0350661203 0.000425221282
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 -0.0356260799 -0.00131695333
+ vertex -0.00264506438 -0.0350661203 0.000425221282
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501046795
+ vertex -0.000455220958 -0.0452524722 -0.00501046749
+ vertex 0.000105200954 -0.0445730276 -0.00216107885
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501046795
+ vertex 0.000105200954 -0.0445730276 -0.00216107885
+ vertex -0.0029327576 -0.0429493263 -0.00113913917
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501046795
+ vertex -0.0029327576 -0.0429493263 -0.00113913917
+ vertex -0.00515188929 -0.0396574326 -0.00500000035
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00283985701 -0.0443740748 -0.00501046795
+ vertex -0.00515188929 -0.0396574326 -0.00500000035
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ vertex 0.000478150701 -0.0445214137 -0.00781145925
+ vertex -0.000455220958 -0.0452524722 -0.00501046749
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ vertex -0.000455220958 -0.0452524722 -0.00501046749
+ vertex -0.00283985701 -0.0443740748 -0.00501046795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238119916 -0.00438925205 -0.0106756203
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238119916 -0.00438925205 -0.0106756203
+ vertex 0.000465776073 0.00647113612 -0.00795523357
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238119916 -0.00438925205 -0.0106756203
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex -0.00316523481 -0.0339629762 -0.0102867903
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238119916 -0.00438925205 -0.0106756203
+ vertex -0.00316523481 -0.0339629762 -0.0102867903
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00980036985 -0.00276796333 -0.000782165327
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00695778104 0.00602345867 -0.00204476621
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00451644277 0.00780560076 -0.00196253788
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.0073649832 -0.0242304057 -0.00135725073
+ vertex 0.00980036985 -0.00276796333 -0.000782165327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ vertex 0.0109100407 -0.00338321831 -0.00604098616
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.0109100407 -0.00338321831 -0.00604098616
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ vertex 0.00914153084 -0.00528662559 -0.00953828637
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.00914153084 -0.00528662559 -0.00953828637
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999800581 -0.00285271578 -0.00896661635
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.00695778104 0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371271
+ vertex -0.00316523481 -0.0339629762 -0.0102867903
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371271
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ vertex -0.00515188929 -0.0396574326 -0.00500000035
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371271
+ vertex -0.00515188929 -0.0396574326 -0.00500000035
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044548288 -0.0388166755 -0.00850371271
+ vertex -0.00288134371 0.00178353756 -0.0080374619
+ vertex -0.00316523481 -0.0339629762 -0.0102867903
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832235
+ vertex -0.00316523481 -0.0339629762 -0.0102867903
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.00914153084 -0.00528662559 -0.00953828637
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00562954973 -0.00067555462 -0.0112180943
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ vertex 0.00119875174 -0.0344842672 -0.0101832235
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832235
+ vertex 0.0073649832 -0.0242304057 -0.00864274986
+ vertex 0.00209764205 -0.0416203551 -0.00846530404
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832235
+ vertex 0.00209764205 -0.0416203551 -0.00846530404
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 -0.0344842672 -0.0101832235
+ vertex -0.00262691779 -0.0428678356 -0.00908724219
+ vertex -0.00316523481 -0.0339629762 -0.0102867903
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000138802352 -0.0043906956 0.000530735939
+ vertex -0.00264506438 -0.0350661203 0.000425221282
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000138802352 -0.0043906956 0.000530735939
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000138802352 -0.0043906956 0.000530735939
+ vertex -0.000307882641 0.00586847169 -0.00204476621
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000138802352 -0.0043906956 0.000530735939
+ vertex -0.00310910842 0.000835592044 -0.00196253788
+ vertex -0.00264506438 -0.0350661203 0.000425221282
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392221 -0.0344835073 0.000181894633
+ vertex 0.0019755722 -0.0424995646 -0.00173989416
+ vertex 0.0073649832 -0.0242304057 -0.00135725073
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392221 -0.0344835073 0.000181894633
+ vertex 0.0073649832 -0.0242304057 -0.00135725073
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392221 -0.0344835073 0.000181894633
+ vertex 0.00721886847 -0.000863869151 0.000908752787
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392221 -0.0344835073 0.000181894633
+ vertex 0.00408238173 -0.00187340903 0.00130375288
+ vertex -0.00264506438 -0.0350661203 0.000425221282
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392221 -0.0344835073 0.000181894633
+ vertex -0.00264506438 -0.0350661203 0.000425221282
+ vertex -0.0029327576 -0.0429493263 -0.00113913917
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392221 -0.0344835073 0.000181894633
+ vertex -0.0029327576 -0.0429493263 -0.00113913917
+ vertex 0.0019755722 -0.0424995646 -0.00173989416
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175182836 -0.0442894548 -0.00325343222
+ vertex 0.000105200954 -0.0445730276 -0.00216107885
+ vertex -0.000455220958 -0.0452524722 -0.00501046749
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175182836 -0.0442894548 -0.00325343222
+ vertex -0.000455220958 -0.0452524722 -0.00501046749
+ vertex 0.000478150701 -0.0445214137 -0.00781145925
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175182836 -0.0442894548 -0.00325343222
+ vertex 0.000478150701 -0.0445214137 -0.00781145925
+ vertex 0.00245129457 -0.0434379876 -0.00601699995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175182836 -0.0442894548 -0.00325343222
+ vertex 0.00245129457 -0.0434379876 -0.00601699995
+ vertex 0.00793468021 -0.0254673474 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175182836 -0.0442894548 -0.00325343222
+ vertex 0.0019755722 -0.0424995646 -0.00173989416
+ vertex 0.000105200954 -0.0445730276 -0.00216107885
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link20_R.STL b/assets/inspire_hand/meshes/Link20_R.STL
new file mode 100644
index 0000000..5fed852
Binary files /dev/null and b/assets/inspire_hand/meshes/Link20_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link20_R.STL.convex.stl b/assets/inspire_hand/meshes/Link20_R.STL.convex.stl
new file mode 100644
index 0000000..a957587
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link20_R.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000465776073 -0.00647113612 -0.00795523357
+ vertex 0.00453154556 -0.00792971067 -0.00655000005
+ vertex 0.00451644277 -0.00780560076 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000465776073 -0.00647113612 -0.00795523357
+ vertex 0.00451644277 -0.00780560076 -0.00196253764
+ vertex -0.000307882641 -0.00586847169 -0.00204476598
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00515188929 0.0396574326 -0.00500000035
+ vertex -0.00288134371 -0.00178353756 -0.0080374619
+ vertex -0.00310910866 -0.000835592044 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 -0.00586847169 -0.00204476598
+ vertex 0.00451644277 -0.00780560076 -0.00196253764
+ vertex 0.00414960086 0.00179188512 0.00130476186
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000307882641 -0.00586847169 -0.00204476598
+ vertex -0.00310910866 -0.000835592044 -0.00196253764
+ vertex -0.00288134371 -0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000465776073 -0.00647113612 -0.00795523357
+ vertex -0.000307882641 -0.00586847169 -0.00204476598
+ vertex -0.00288134371 -0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499019 0.0242304038 -0.00135726656
+ vertex 0.00793451164 0.0254673064 -0.00501046749
+ vertex 0.00175186014 0.0442894287 -0.00325343176
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499019 0.0242304038 -0.00135726656
+ vertex 0.00175186014 0.0442894287 -0.00325343176
+ vertex 0.0019755722 0.0424995646 -0.00173989416
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00980023574 0.0027678702 -0.000782012125
+ vertex 0.0109102502 0.00338376779 -0.00604102202
+ vertex 0.00793451164 0.0254673064 -0.00501046749
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00980023574 0.0027678702 -0.000782012125
+ vertex 0.00793451164 0.0254673064 -0.00501046749
+ vertex 0.00736499019 0.0242304038 -0.00135726656
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000478150789 0.0445214137 -0.00781145878
+ vertex 0.00209764251 0.0416203551 -0.00846530404
+ vertex -0.00263238722 0.0428635553 -0.00908712484
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00736499019 0.0242304038 -0.00864273403
+ vertex 0.00793451164 0.0254673064 -0.00501046749
+ vertex 0.0109102502 0.00338376779 -0.00604102202
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 -0.00602345867 -0.00204476598
+ vertex 0.00451644277 -0.00780560076 -0.00196253764
+ vertex 0.00453154556 -0.00792971067 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 -0.00602345867 -0.00204476598
+ vertex 0.00453154556 -0.00792971067 -0.00655000005
+ vertex 0.00695778104 -0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 -0.00602345867 -0.00204476598
+ vertex 0.00695778104 -0.00602345867 -0.00795523357
+ vertex 0.0109102502 0.00338376779 -0.00604102202
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00695778104 -0.00602345867 -0.00204476598
+ vertex 0.0109102502 0.00338376779 -0.00604102202
+ vertex 0.00980023574 0.0027678702 -0.000782012125
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000105201041 0.0445730276 -0.00216107885
+ vertex -0.0029327576 0.0429493263 -0.00113913917
+ vertex 0.0019755722 0.0424995646 -0.00173989416
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00245129503 0.0434379876 -0.00601699995
+ vertex 0.00209764251 0.0416203551 -0.00846530404
+ vertex 0.000478150789 0.0445214137 -0.00781145878
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00245129503 0.0434379876 -0.00601699995
+ vertex 0.00793451164 0.0254673064 -0.00501046749
+ vertex 0.00736499019 0.0242304038 -0.00864273403
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00245129503 0.0434379876 -0.00601699995
+ vertex 0.00736499019 0.0242304038 -0.00864273403
+ vertex 0.00209764251 0.0416203551 -0.00846530404
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 -0.00780560076 -0.0080374619
+ vertex 0.00453154556 -0.00792971067 -0.00655000005
+ vertex 0.000465776073 -0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 -0.00780560076 -0.0080374619
+ vertex 0.000465776073 -0.00647113612 -0.00795523357
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 -0.00780560076 -0.0080374619
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ vertex 0.00695778104 -0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00451644277 -0.00780560076 -0.0080374619
+ vertex 0.00695778104 -0.00602345867 -0.00795523357
+ vertex 0.00453154556 -0.00792971067 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 0.0356260799 -0.00131695333
+ vertex -0.00264506461 0.0350661203 0.000425221253
+ vertex -0.0029327576 0.0429493263 -0.00113913917
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 0.0356260799 -0.00131695333
+ vertex -0.0029327576 0.0429493263 -0.00113913917
+ vertex -0.00515188929 0.0396574326 -0.00500000035
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 0.0356260799 -0.00131695333
+ vertex -0.00515188929 0.0396574326 -0.00500000035
+ vertex -0.00310910866 -0.000835592044 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00460944278 0.0356260799 -0.00131695333
+ vertex -0.00310910866 -0.000835592044 -0.00196253764
+ vertex -0.00264506461 0.0350661203 0.000425221253
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00284005166 0.0443742685 -0.00500000035
+ vertex -0.00263238722 0.0428635553 -0.00908712484
+ vertex -0.00515188929 0.0396574326 -0.00500000035
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00284005166 0.0443742685 -0.00500000035
+ vertex -0.00515188929 0.0396574326 -0.00500000035
+ vertex -0.0029327576 0.0429493263 -0.00113913917
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00284005166 0.0443742685 -0.00500000035
+ vertex -0.0029327576 0.0429493263 -0.00113913917
+ vertex 0.000105201041 0.0445730276 -0.00216107885
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00284005166 0.0443742685 -0.00500000035
+ vertex 0.000105201041 0.0445730276 -0.00216107885
+ vertex -0.000455220899 0.0452524722 -0.00501046795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00284005166 0.0443742685 -0.00500000035
+ vertex -0.000455220899 0.0452524722 -0.00501046795
+ vertex 0.000478150789 0.0445214137 -0.00781145878
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00284005166 0.0443742685 -0.00500000035
+ vertex 0.000478150789 0.0445214137 -0.00781145878
+ vertex -0.00263238722 0.0428635553 -0.00908712484
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238096531 0.00438924972 -0.010675611
+ vertex -0.00316523504 0.0339629762 -0.0102867903
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238096531 0.00438924972 -0.010675611
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ vertex 0.000465776073 -0.00647113612 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238096531 0.00438924972 -0.010675611
+ vertex 0.000465776073 -0.00647113612 -0.00795523357
+ vertex -0.00288134371 -0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000238096531 0.00438924972 -0.010675611
+ vertex -0.00288134371 -0.00178353756 -0.0080374619
+ vertex -0.00316523504 0.0339629762 -0.0102867903
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 0.000863869151 0.000908746268
+ vertex 0.00414960086 0.00179188512 0.00130476186
+ vertex 0.00451644277 -0.00780560076 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 0.000863869151 0.000908746268
+ vertex 0.00451644277 -0.00780560076 -0.00196253764
+ vertex 0.00695778104 -0.00602345867 -0.00204476598
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 0.000863869151 0.000908746268
+ vertex 0.00695778104 -0.00602345867 -0.00204476598
+ vertex 0.00980023574 0.0027678702 -0.000782012125
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00721886847 0.000863869151 0.000908746268
+ vertex 0.00980023574 0.0027678702 -0.000782012125
+ vertex 0.00736499019 0.0242304038 -0.00135726656
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999334455 0.00285032811 -0.00897325575
+ vertex 0.00914156251 0.00528630661 -0.00953829568
+ vertex 0.00736499019 0.0242304038 -0.00864273403
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999334455 0.00285032811 -0.00897325575
+ vertex 0.00736499019 0.0242304038 -0.00864273403
+ vertex 0.0109102502 0.00338376779 -0.00604102202
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999334455 0.00285032811 -0.00897325575
+ vertex 0.0109102502 0.00338376779 -0.00604102202
+ vertex 0.00695778104 -0.00602345867 -0.00795523357
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999334455 0.00285032811 -0.00897325575
+ vertex 0.00695778104 -0.00602345867 -0.00795523357
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999334455 0.00285032811 -0.00897325575
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ vertex 0.00914156251 0.00528630661 -0.00953829568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00445548398 0.0388090387 -0.00850408152
+ vertex -0.00515188929 0.0396574326 -0.00500000035
+ vertex -0.00263238722 0.0428635553 -0.00908712484
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00445548398 0.0388090387 -0.00850408152
+ vertex -0.00263238722 0.0428635553 -0.00908712484
+ vertex -0.00316523504 0.0339629762 -0.0102867903
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00445548398 0.0388090387 -0.00850408152
+ vertex -0.00316523504 0.0339629762 -0.0102867903
+ vertex -0.00288134371 -0.00178353756 -0.0080374619
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00445548398 0.0388090387 -0.00850408152
+ vertex -0.00288134371 -0.00178353756 -0.0080374619
+ vertex -0.00515188929 0.0396574326 -0.00500000035
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 0.0344842672 -0.0101832235
+ vertex 0.00209764251 0.0416203551 -0.00846530404
+ vertex 0.00736499019 0.0242304038 -0.00864273403
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 0.0344842672 -0.0101832235
+ vertex 0.00736499019 0.0242304038 -0.00864273403
+ vertex 0.00914156251 0.00528630661 -0.00953829568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 0.0344842672 -0.0101832235
+ vertex 0.00914156251 0.00528630661 -0.00953829568
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 0.0344842672 -0.0101832235
+ vertex 0.00563265942 0.000674418698 -0.0112177758
+ vertex -0.00316523504 0.0339629762 -0.0102867903
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 0.0344842672 -0.0101832235
+ vertex -0.00316523504 0.0339629762 -0.0102867903
+ vertex -0.00263238722 0.0428635553 -0.00908712484
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00119875174 0.0344842672 -0.0101832235
+ vertex -0.00263238722 0.0428635553 -0.00908712484
+ vertex 0.00209764251 0.0416203551 -0.00846530404
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000507224584 0.00436142832 0.000362147897
+ vertex -0.00310910866 -0.000835592044 -0.00196253764
+ vertex -0.000307882641 -0.00586847169 -0.00204476598
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000507224584 0.00436142832 0.000362147897
+ vertex -0.000307882641 -0.00586847169 -0.00204476598
+ vertex 0.00414960086 0.00179188512 0.00130476186
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000507224584 0.00436142832 0.000362147897
+ vertex 0.00414960086 0.00179188512 0.00130476186
+ vertex -0.00264506461 0.0350661203 0.000425221253
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000507224584 0.00436142832 0.000362147897
+ vertex -0.00264506461 0.0350661203 0.000425221253
+ vertex -0.00310910866 -0.000835592044 -0.00196253764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 0.0344835073 0.000181894618
+ vertex -0.00264506461 0.0350661203 0.000425221253
+ vertex 0.00414960086 0.00179188512 0.00130476186
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 0.0344835073 0.000181894618
+ vertex 0.00414960086 0.00179188512 0.00130476186
+ vertex 0.00721886847 0.000863869151 0.000908746268
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 0.0344835073 0.000181894618
+ vertex 0.00721886847 0.000863869151 0.000908746268
+ vertex 0.00736499019 0.0242304038 -0.00135726656
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00120392232 0.0344835073 0.000181894618
+ vertex 0.00736499019 0.0242304038 -0.00135726656
+ vertex 0.0019755722 0.0424995646 -0.00173989416
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0019755722 0.0424995646 -0.00173989416
+ vertex -0.0029327576 0.0429493263 -0.00113913917
+ vertex -0.00264506461 0.0350661203 0.000425221253
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0019755722 0.0424995646 -0.00173989416
+ vertex -0.00264506461 0.0350661203 0.000425221253
+ vertex 0.00120392232 0.0344835073 0.000181894618
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175186014 0.0442894287 -0.00325343176
+ vertex 0.00793451164 0.0254673064 -0.00501046749
+ vertex 0.00245129503 0.0434379876 -0.00601699995
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175186014 0.0442894287 -0.00325343176
+ vertex 0.00245129503 0.0434379876 -0.00601699995
+ vertex 0.000478150789 0.0445214137 -0.00781145878
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175186014 0.0442894287 -0.00325343176
+ vertex 0.000478150789 0.0445214137 -0.00781145878
+ vertex -0.000455220899 0.0452524722 -0.00501046795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175186014 0.0442894287 -0.00325343176
+ vertex -0.000455220899 0.0452524722 -0.00501046795
+ vertex 0.000105201041 0.0445730276 -0.00216107885
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00175186014 0.0442894287 -0.00325343176
+ vertex 0.000105201041 0.0445730276 -0.00216107885
+ vertex 0.0019755722 0.0424995646 -0.00173989416
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link21_L.STL b/assets/inspire_hand/meshes/Link21_L.STL
new file mode 100644
index 0000000..ccb63bf
Binary files /dev/null and b/assets/inspire_hand/meshes/Link21_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link21_L.STL.convex.stl b/assets/inspire_hand/meshes/Link21_L.STL.convex.stl
new file mode 100644
index 0000000..800f2f7
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link21_L.STL.convex.stl
@@ -0,0 +1,578 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -8.95772246e-05 0.00956364814 -0.010644556
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00528134033 0.00782435481 0.000980281737
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619973568 0.00712514762 -0.012882188
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00620628009 -0.0307127293 -0.0118967975
+ vertex 0.00814419705 -0.0339711122 -0.00865195692
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00168019475 -0.0353947729 -0.0117649594
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.00469024293 -0.0258794762 -0.0128043657
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex -0.00245324406 0.00911482889 -0.0130123673
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00549842604 0.00772650121 -0.0118709719
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.010652706
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108619863 0.000361838116 -0.0082310643
+ vertex 0.00859882869 -0.0320471004 -0.00950245839
+ vertex 0.00948811043 0.0037748625 -0.0100879287
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.00554241985 -0.0329650044 -0.0119373091
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00870714523 0.00640626019 -0.00598953292
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950312894 0.00461286493 -0.00238404726
+ vertex 0.00979297794 -0.000237770757 -0.0017522797
+ vertex 0.0110836849 0.000444926991 -0.00464487588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00588553818 -0.0330666415 -0.00239999988
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00358415442 -0.0352738127 -0.000235040148
+ vertex -0.00420491258 -0.0350654013 -0.0115261674
+ vertex -0.00298846234 -0.0356077217 -0.00239999988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex -0.00118642545 -0.0351593159 -0.000115798735
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749985129 -0.0333133452 -0.00187939638
+ vertex 0.00867131725 -0.0342117175 -0.00454189023
+ vertex 0.00732633192 -0.0312311966 -0.000836168358
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0052414448 0.00945578981 -0.0013472935
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex -0.000471164734 0.00943676289 0.00084743608
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 0.00903278124 9.35034404e-05
+ vertex 0.0037693365 -0.026172813 0.000955631083
+ vertex 0.00767573016 0.00588637171 -0.000752015447
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00923808385 -0.0071737715 -0.0015976117
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00479577668 -0.0338946246 5.21540588e-11
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00823408179 0.00469105458 0.000259628578
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00904458947 0.00293594948 -0.0116376197
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00954843778 0.000176081609 -0.00115589425
+ vertex -0.00984699838 -0.00731367478 -0.00898697134
+ vertex -0.010015429 -0.00735280709 -0.00449603936
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link21_R.STL b/assets/inspire_hand/meshes/Link21_R.STL
new file mode 100644
index 0000000..d4710f1
Binary files /dev/null and b/assets/inspire_hand/meshes/Link21_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link21_R.STL.convex.stl b/assets/inspire_hand/meshes/Link21_R.STL.convex.stl
new file mode 100644
index 0000000..d2327d5
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link21_R.STL.convex.stl
@@ -0,0 +1,546 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex -9.02905376e-05 -0.00956364162 -0.00135544734
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00579818152 -0.00760784978 -0.0105823008
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00619969796 -0.00712518021 0.000882193504
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00566976098 0.0318848938 -0.000330381503
+ vertex 0.00814419705 0.0339711122 -0.00334804319
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.00470032962 0.0260484722 0.000795508327
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex -0.00246302434 -0.00911326054 0.00101274764
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00458956463 -0.00775821414 0.000137225317
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00984698441 0.00731367059 -0.0030129645
+ vertex -0.0090445755 -0.00293598743 -0.000362366845
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0052414448 -0.00945578888 -0.0013472935
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.0110836849 -0.000444926991 -0.00735513913
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00915175769 -0.00541536883 -0.00935241766
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00970043056 0.000281998888 -0.0103491098
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00216788356 0.0354665518 -0.000235040148
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00273384899 0.0356388651 -0.00959999952
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00439190213 0.0349471308 -0.000473832159
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ vertex -0.00557526108 0.0328458734 -6.26900655e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00611000136 -0.00720144203 -0.0128938593
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.00859412923 -0.00402176147 -0.0120279966
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.010015429 0.00735280709 -0.00750395935
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00583793502 0.0324119031 -0.0117649594
+ vertex -0.0059219948 0.0329344086 -0.00959999952
+ vertex -0.00450870115 0.0342126004 -0.0120000001
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0108623253 -0.000362016901 -0.00376997283
+ vertex 0.00858414825 0.0320373364 -0.00246613892
+ vertex 0.00950685237 -0.00380186713 -0.00194311794
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.0052414448 -0.00945578888 -0.010652706
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex -0.00137330801 -0.00934251398 -0.0129493466
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00411645509 -0.0090327803 -0.0120935012
+ vertex 0.0037693365 0.026172813 -0.0129556311
+ vertex 0.00762665784 -0.00583287515 -0.0112889735
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex -0.00118642545 0.0351593159 -0.0118842013
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00749682449 0.0333158225 -0.0101199131
+ vertex 0.00867131911 0.0342117138 -0.00745810941
+ vertex 0.00733216526 0.0312348269 -0.0111587103
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link22_L.STL b/assets/inspire_hand/meshes/Link22_L.STL
new file mode 100644
index 0000000..6b9cdad
Binary files /dev/null and b/assets/inspire_hand/meshes/Link22_L.STL differ
diff --git a/assets/inspire_hand/meshes/Link22_L.STL.convex.stl b/assets/inspire_hand/meshes/Link22_L.STL.convex.stl
new file mode 100644
index 0000000..8b3908e
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link22_L.STL.convex.stl
@@ -0,0 +1,626 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000620731618 0.00541405519 -0.00214476418
+ vertex 0.00449590292 0.00763689075 -0.00197592867
+ vertex 0.00399954524 0.00772637874 -0.00795300771
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000620731618 0.00541405519 -0.00214476418
+ vertex 0.00399954524 0.00772637874 -0.00795300771
+ vertex 0.000424946018 0.00627886783 -0.00792301539
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0044268351 -0.0322108492 -0.00499999989
+ vertex -0.00301018823 0.00065022608 -0.00200673961
+ vertex -0.0026906007 0.0019602722 -0.0079932604
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000620731618 0.00541405519 -0.00214476418
+ vertex 0.00399830472 -0.00144497002 0.00133481983
+ vertex 0.00449590292 0.00763689075 -0.00197592867
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000620731618 0.00541405519 -0.00214476418
+ vertex -0.0026906007 0.0019602722 -0.0079932604
+ vertex -0.00301018823 0.00065022608 -0.00200673961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000424946018 0.00627886783 -0.00792301539
+ vertex -0.0026906007 0.0019602722 -0.0079932604
+ vertex -0.000620731618 0.00541405519 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000424946018 0.00627886783 -0.00792301539
+ vertex 0.00399830472 -0.00144497002 -0.0113348197
+ vertex -0.000313410972 -0.00404750742 -0.0104054036
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000424946018 0.00627886783 -0.00792301539
+ vertex -0.000313410972 -0.00404750742 -0.0104054036
+ vertex -0.0026906007 0.0019602722 -0.0079932604
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00621925993 0.00676024007 -0.00802407134
+ vertex 0.00451228907 0.00777152041 -0.00655000005
+ vertex 0.00449590292 0.00763689075 -0.00197592867
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684741791 0.00597661454 -0.00214476418
+ vertex 0.00621925993 0.00676024007 -0.00802407134
+ vertex 0.00449590292 0.00763689075 -0.00197592867
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874702 -0.000724797661 0.000906558998
+ vertex 0.00983401109 -0.00297323661 -0.00100598682
+ vertex 0.00684741791 0.00597661454 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874702 -0.000724797661 0.000906558998
+ vertex 0.00684741791 0.00597661454 -0.00214476418
+ vertex 0.00449590292 0.00763689075 -0.00197592867
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874702 -0.000724797661 0.000906558998
+ vertex 0.00449590292 0.00763689075 -0.00197592867
+ vertex 0.00399830472 -0.00144497002 0.00133481983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874702 -0.000724797661 0.000906558998
+ vertex 0.00578834303 -0.0208070129 -0.000150235006
+ vertex 0.00784449745 -0.0195092522 -0.00136756524
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874702 -0.000724797661 0.000906558998
+ vertex 0.00784449745 -0.0195092522 -0.00136756524
+ vertex 0.00983401109 -0.00297323661 -0.00100598682
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874702 -0.000724797661 -0.0109065594
+ vertex 0.00621925993 0.00676024007 -0.00802407134
+ vertex 0.0098417215 -0.00292899809 -0.00896925386
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874702 -0.000724797661 -0.0109065594
+ vertex 0.0098417215 -0.00292899809 -0.00896925386
+ vertex 0.00765117025 -0.0167496912 -0.00928046182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 -0.0369406752 -0.00257229945
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ vertex -0.000420921337 -0.0374701358 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 -0.0369406752 -0.00257229945
+ vertex -0.000420921337 -0.0374701358 -0.00501046702
+ vertex 0.00257614674 -0.0367346704 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 -0.0369406752 -0.00257229945
+ vertex 0.00257614674 -0.0367346704 -0.00501046702
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 -0.0369406752 -0.00257229945
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00302059087 -0.0357560329 -0.00498953229
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ vertex -0.000420921337 -0.0374701358 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00302059087 -0.0357560329 -0.00498953229
+ vertex -0.000420921337 -0.0374701358 -0.00501046702
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00302059087 -0.0357560329 -0.00498953229
+ vertex -0.0044268351 -0.0322108492 -0.00499999989
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107919974 -0.00369101367 -0.00499996869
+ vertex 0.00983401109 -0.00297323661 -0.00100598682
+ vertex 0.00784449745 -0.0195092522 -0.00136756524
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107919974 -0.00369101367 -0.00499996869
+ vertex 0.00784449745 -0.0195092522 -0.00136756524
+ vertex 0.00864904933 -0.0192879438 -0.00395921897
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107919974 -0.00369101367 -0.00499996869
+ vertex 0.0098417215 -0.00292899809 -0.00896925386
+ vertex 0.00621925993 0.00676024007 -0.00802407134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107919974 -0.00369101367 -0.00499996869
+ vertex 0.00621925993 0.00676024007 -0.00802407134
+ vertex 0.00684741791 0.00597661454 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107919974 -0.00369101367 -0.00499996869
+ vertex 0.00684741791 0.00597661454 -0.00214476418
+ vertex 0.00983401109 -0.00297323661 -0.00100598682
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00369461509 -0.0290614646 -0.00127628434
+ vertex -0.00301018823 0.00065022608 -0.00200673961
+ vertex -0.0044268351 -0.0322108492 -0.00499999989
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681369 -0.0369183198 -0.00782407355
+ vertex -0.000420921337 -0.0374701358 -0.00501046702
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681369 -0.0369183198 -0.00782407355
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ vertex 0.00217980309 -0.0353009887 -0.00865814555
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681369 -0.0369183198 -0.00782407355
+ vertex 0.00217980309 -0.0353009887 -0.00865814555
+ vertex 0.00358761172 -0.0350559726 -0.00674667163
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681369 -0.0369183198 -0.00782407355
+ vertex 0.00358761172 -0.0350559726 -0.00674667163
+ vertex 0.00257614674 -0.0367346704 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681369 -0.0369183198 -0.00782407355
+ vertex 0.00257614674 -0.0367346704 -0.00501046702
+ vertex -0.000420921337 -0.0374701358 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 -0.0206090417 -0.00777530856
+ vertex 0.00765117025 -0.0167496912 -0.00928046182
+ vertex 0.0098417215 -0.00292899809 -0.00896925386
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 -0.0206090417 -0.00777530856
+ vertex 0.0098417215 -0.00292899809 -0.00896925386
+ vertex 0.0107919974 -0.00369101367 -0.00499996869
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 -0.0206090417 -0.00777530856
+ vertex 0.0107919974 -0.00369101367 -0.00499996869
+ vertex 0.00864904933 -0.0192879438 -0.00395921897
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 -0.0206090417 -0.00777530856
+ vertex 0.00217980309 -0.0353009887 -0.00865814555
+ vertex 0.00765117025 -0.0167496912 -0.00928046182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 0.00772637874 -0.00795300771
+ vertex 0.00451228907 0.00777152041 -0.00655000005
+ vertex 0.00621925993 0.00676024007 -0.00802407134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 0.00772637874 -0.00795300771
+ vertex 0.00621925993 0.00676024007 -0.00802407134
+ vertex 0.00716874702 -0.000724797661 -0.0109065594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 0.00772637874 -0.00795300771
+ vertex 0.00716874702 -0.000724797661 -0.0109065594
+ vertex 0.00399830472 -0.00144497002 -0.0113348197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 0.00772637874 -0.00795300771
+ vertex 0.00399830472 -0.00144497002 -0.0113348197
+ vertex 0.000424946018 0.00627886783 -0.00792301539
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 0.00772637874 -0.00795300771
+ vertex 0.00449590292 0.00763689075 -0.00197592867
+ vertex 0.00451228907 0.00777152041 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 -0.0301329885 -0.00868304726
+ vertex -0.00220466289 -0.0275486708 -0.0103293415
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 -0.0301329885 -0.00868304726
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ vertex -0.0044268351 -0.0322108492 -0.00499999989
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 -0.0301329885 -0.00868304726
+ vertex -0.0044268351 -0.0322108492 -0.00499999989
+ vertex -0.0026906007 0.0019602722 -0.0079932604
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 -0.0301329885 -0.00868304726
+ vertex -0.0026906007 0.0019602722 -0.0079932604
+ vertex -0.00220466289 -0.0275486708 -0.0103293415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 -0.0287368521 -0.0103536993
+ vertex 0.00765117025 -0.0167496912 -0.00928046182
+ vertex 0.00217980309 -0.0353009887 -0.00865814555
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 -0.0287368521 -0.0103536993
+ vertex 0.00217980309 -0.0353009887 -0.00865814555
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 -0.0287368521 -0.0103536993
+ vertex -0.00202913512 -0.0355549455 -0.0089844279
+ vertex -0.00220466289 -0.0275486708 -0.0103293415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 -0.0287368521 -0.0103536993
+ vertex -0.00220466289 -0.0275486708 -0.0103293415
+ vertex 0.00399830472 -0.00144497002 -0.0113348197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 -0.0287368521 -0.0103536993
+ vertex 0.00399830472 -0.00144497002 -0.0113348197
+ vertex 0.00716874702 -0.000724797661 -0.0109065594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 -0.0287368521 -0.0103536993
+ vertex 0.00716874702 -0.000724797661 -0.0109065594
+ vertex 0.00765117025 -0.0167496912 -0.00928046182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00784449745 -0.0195092522 -0.00136756524
+ vertex 0.00578834303 -0.0208070129 -0.000150235006
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00784449745 -0.0195092522 -0.00136756524
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ vertex 0.00864904933 -0.0192879438 -0.00395921897
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313410972 -0.00404750742 0.000405404135
+ vertex -0.00178322627 -0.0294491332 0.000425221719
+ vertex 0.00399830472 -0.00144497002 0.00133481983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313410972 -0.00404750742 0.000405404135
+ vertex 0.00399830472 -0.00144497002 0.00133481983
+ vertex -0.000620731618 0.00541405519 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313410972 -0.00404750742 0.000405404135
+ vertex -0.000620731618 0.00541405519 -0.00214476418
+ vertex -0.00301018823 0.00065022608 -0.00200673961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313410972 -0.00404750742 0.000405404135
+ vertex -0.00301018823 0.00065022608 -0.00200673961
+ vertex -0.00369461509 -0.0290614646 -0.00127628434
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313410972 -0.00404750742 0.000405404135
+ vertex -0.00369461509 -0.0290614646 -0.00127628434
+ vertex -0.00178322627 -0.0294491332 0.000425221719
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313410972 -0.00404750742 -0.0104054036
+ vertex 0.00399830472 -0.00144497002 -0.0113348197
+ vertex -0.00220466289 -0.0275486708 -0.0103293415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313410972 -0.00404750742 -0.0104054036
+ vertex -0.00220466289 -0.0275486708 -0.0103293415
+ vertex -0.0026906007 0.0019602722 -0.0079932604
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358761172 -0.0350559726 -0.00674667163
+ vertex 0.00217980309 -0.0353009887 -0.00865814555
+ vertex 0.00794922467 -0.0206090417 -0.00777530856
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358761172 -0.0350559726 -0.00674667163
+ vertex 0.00794922467 -0.0206090417 -0.00777530856
+ vertex 0.00864904933 -0.0192879438 -0.00395921897
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358761172 -0.0350559726 -0.00674667163
+ vertex 0.00864904933 -0.0192879438 -0.00395921897
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358761172 -0.0350559726 -0.00674667163
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ vertex 0.00257614674 -0.0367346704 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ vertex -0.00178322627 -0.0294491332 0.000425221719
+ vertex -0.00369461509 -0.0290614646 -0.00127628434
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ vertex -0.00369461509 -0.0290614646 -0.00127628434
+ vertex -0.00350565487 -0.0339018703 -0.0021057087
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565487 -0.0339018703 -0.0021057087
+ vertex -0.00369461509 -0.0290614646 -0.00127628434
+ vertex -0.0044268351 -0.0322108492 -0.00499999989
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565487 -0.0339018703 -0.0021057087
+ vertex -0.0044268351 -0.0322108492 -0.00499999989
+ vertex -0.00302059087 -0.0357560329 -0.00498953229
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565487 -0.0339018703 -0.0021057087
+ vertex -0.00302059087 -0.0357560329 -0.00498953229
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 -0.0305631813 -3.98206721e-05
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ vertex 0.00578834303 -0.0208070129 -0.000150235006
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 -0.0305631813 -3.98206721e-05
+ vertex 0.00578834303 -0.0208070129 -0.000150235006
+ vertex 0.00716874702 -0.000724797661 0.000906558998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 -0.0305631813 -3.98206721e-05
+ vertex 0.00716874702 -0.000724797661 0.000906558998
+ vertex 0.00399830472 -0.00144497002 0.00133481983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 -0.0305631813 -3.98206721e-05
+ vertex 0.00399830472 -0.00144497002 0.00133481983
+ vertex -0.00178322627 -0.0294491332 0.000425221719
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 -0.0305631813 -3.98206721e-05
+ vertex -0.00178322627 -0.0294491332 0.000425221719
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 -0.0305631813 -3.98206721e-05
+ vertex -0.00159868796 -0.0357633345 -0.000914852193
+ vertex 0.00322755706 -0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/Link22_R.STL b/assets/inspire_hand/meshes/Link22_R.STL
new file mode 100644
index 0000000..c2cf58b
Binary files /dev/null and b/assets/inspire_hand/meshes/Link22_R.STL differ
diff --git a/assets/inspire_hand/meshes/Link22_R.STL.convex.stl b/assets/inspire_hand/meshes/Link22_R.STL.convex.stl
new file mode 100644
index 0000000..f3bd51b
--- /dev/null
+++ b/assets/inspire_hand/meshes/Link22_R.STL.convex.stl
@@ -0,0 +1,626 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ vertex 0.00399830472 0.00144497002 0.00133481983
+ vertex 0.00716874655 0.000724797661 0.000906558998
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ vertex 0.00716874655 0.000724797661 0.000906558998
+ vertex 0.00572999008 0.020759929 -0.000123515827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ vertex 0.00572999008 0.020759929 -0.000123515827
+ vertex 0.00179571763 0.0305631813 -3.98206721e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00442683464 0.0322108492 -0.00499999989
+ vertex -0.00269060046 -0.0019602722 -0.0079932604
+ vertex -0.003010188 -0.00065022608 -0.00200673961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000620731618 -0.00541405519 -0.00214476418
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ vertex 0.00399830472 0.00144497002 0.00133481983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000620731618 -0.00541405519 -0.00214476418
+ vertex -0.003010188 -0.00065022608 -0.00200673961
+ vertex -0.00269060046 -0.0019602722 -0.0079932604
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00042494596 -0.00627886783 -0.00792301539
+ vertex 0.00399954524 -0.00772637874 -0.00795300771
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00042494596 -0.00627886783 -0.00792301539
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ vertex -0.000620731618 -0.00541405519 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00042494596 -0.00627886783 -0.00792301539
+ vertex -0.000620731618 -0.00541405519 -0.00214476418
+ vertex -0.00269060046 -0.0019602722 -0.0079932604
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00042494596 -0.00627886783 -0.00792301539
+ vertex -0.00269060046 -0.0019602722 -0.0079932604
+ vertex -0.000313784782 0.00404747901 -0.0104052192
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00042494596 -0.00627886783 -0.00792301539
+ vertex -0.000313784782 0.00404747901 -0.0104052192
+ vertex 0.00399830472 0.00144497002 -0.0113348197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00621925946 -0.00676024007 -0.00802407134
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ vertex 0.00451228861 -0.00777152041 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00684741745 -0.00597661454 -0.00214476418
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ vertex 0.00621925946 -0.00676024007 -0.00802407134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874655 0.000724797661 0.000906558998
+ vertex 0.00399830472 0.00144497002 0.00133481983
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874655 0.000724797661 0.000906558998
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ vertex 0.00684741745 -0.00597661454 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874655 0.000724797661 0.000906558998
+ vertex 0.00684741745 -0.00597661454 -0.00214476418
+ vertex 0.00982958917 0.00296913739 -0.000999847078
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874655 0.000724797661 0.000906558998
+ vertex 0.00982958917 0.00296913739 -0.000999847078
+ vertex 0.00784468744 0.0195092093 -0.00136782846
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874655 0.000724797661 0.000906558998
+ vertex 0.00784468744 0.0195092093 -0.00136782846
+ vertex 0.00572999008 0.020759929 -0.000123515827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874655 0.000724797661 -0.0109065594
+ vertex 0.00983742345 0.00292518805 -0.00897551514
+ vertex 0.00621925946 -0.00676024007 -0.00802407134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00716874655 0.000724797661 -0.0109065594
+ vertex 0.00764033338 0.0167477541 -0.00928799529
+ vertex 0.00983742345 0.00292518805 -0.00897551514
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 0.0369406752 -0.00257229945
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ vertex 0.00254756794 0.0367584564 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 0.0369406752 -0.00257229945
+ vertex 0.00254756794 0.0367584564 -0.00501046702
+ vertex -0.000420921278 0.0374701358 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 0.0369406752 -0.00257229945
+ vertex -0.000420921278 0.0374701358 -0.00501046702
+ vertex -0.00159872253 0.0357632451 -0.000914807082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00154150021 0.0369406752 -0.00257229945
+ vertex -0.00159872253 0.0357632451 -0.000914807082
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00301370677 0.0357657261 -0.00498953229
+ vertex -0.00159872253 0.0357632451 -0.000914807082
+ vertex -0.000420921278 0.0374701358 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00301370677 0.0357657261 -0.00498953229
+ vertex -0.000420921278 0.0374701358 -0.00501046702
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00301370677 0.0357657261 -0.00498953229
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ vertex -0.00442683464 0.0322108492 -0.00499999989
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107918605 0.00369099947 -0.00499476632
+ vertex 0.00864649843 0.0192871764 -0.00393117871
+ vertex 0.00784468744 0.0195092093 -0.00136782846
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107918605 0.00369099947 -0.00499476632
+ vertex 0.00784468744 0.0195092093 -0.00136782846
+ vertex 0.00982958917 0.00296913739 -0.000999847078
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107918605 0.00369099947 -0.00499476632
+ vertex 0.00982958917 0.00296913739 -0.000999847078
+ vertex 0.00684741745 -0.00597661454 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107918605 0.00369099947 -0.00499476632
+ vertex 0.00684741745 -0.00597661454 -0.00214476418
+ vertex 0.00621925946 -0.00676024007 -0.00802407134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0107918605 0.00369099947 -0.00499476632
+ vertex 0.00621925946 -0.00676024007 -0.00802407134
+ vertex 0.00983742345 0.00292518805 -0.00897551514
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00369461486 0.0290614646 -0.00127628434
+ vertex -0.00442683464 0.0322108492 -0.00499999989
+ vertex -0.003010188 -0.00065022608 -0.00200673961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681427 0.0369183198 -0.00782407355
+ vertex 0.00217980286 0.0353009887 -0.00865814555
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681427 0.0369183198 -0.00782407355
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ vertex -0.000420921278 0.0374701358 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681427 0.0369183198 -0.00782407355
+ vertex -0.000420921278 0.0374701358 -0.00501046702
+ vertex 0.00254756794 0.0367584564 -0.00501046702
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681427 0.0369183198 -0.00782407355
+ vertex 0.00254756794 0.0367584564 -0.00501046702
+ vertex 0.00358808646 0.0350547694 -0.00674667116
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000572681427 0.0369183198 -0.00782407355
+ vertex 0.00358808646 0.0350547694 -0.00674667116
+ vertex 0.00217980286 0.0353009887 -0.00865814555
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 0.0206090417 -0.00777530856
+ vertex 0.00864649843 0.0192871764 -0.00393117871
+ vertex 0.0107918605 0.00369099947 -0.00499476632
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 0.0206090417 -0.00777530856
+ vertex 0.0107918605 0.00369099947 -0.00499476632
+ vertex 0.00983742345 0.00292518805 -0.00897551514
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 0.0206090417 -0.00777530856
+ vertex 0.00983742345 0.00292518805 -0.00897551514
+ vertex 0.00764033338 0.0167477541 -0.00928799529
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00794922467 0.0206090417 -0.00777530856
+ vertex 0.00764033338 0.0167477541 -0.00928799529
+ vertex 0.00217980286 0.0353009887 -0.00865814555
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 -0.00772637874 -0.00795300771
+ vertex 0.00042494596 -0.00627886783 -0.00792301539
+ vertex 0.00399830472 0.00144497002 -0.0113348197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 -0.00772637874 -0.00795300771
+ vertex 0.00399830472 0.00144497002 -0.0113348197
+ vertex 0.00716874655 0.000724797661 -0.0109065594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 -0.00772637874 -0.00795300771
+ vertex 0.00716874655 0.000724797661 -0.0109065594
+ vertex 0.00621925946 -0.00676024007 -0.00802407134
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 -0.00772637874 -0.00795300771
+ vertex 0.00621925946 -0.00676024007 -0.00802407134
+ vertex 0.00451228861 -0.00777152041 -0.00655000005
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00399954524 -0.00772637874 -0.00795300771
+ vertex 0.00451228861 -0.00777152041 -0.00655000005
+ vertex 0.00449590292 -0.00763689075 -0.00197592867
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 0.0301329885 -0.00868304726
+ vertex -0.00442683464 0.0322108492 -0.00499999989
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 0.0301329885 -0.00868304726
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ vertex -0.00220466265 0.0275486708 -0.0103293415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 0.0301329885 -0.00868304726
+ vertex -0.00220466265 0.0275486708 -0.0103293415
+ vertex -0.00269060046 -0.0019602722 -0.0079932604
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00370620866 0.0301329885 -0.00868304726
+ vertex -0.00269060046 -0.0019602722 -0.0079932604
+ vertex -0.00442683464 0.0322108492 -0.00499999989
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00784468744 0.0195092093 -0.00136782846
+ vertex 0.00864649843 0.0192871764 -0.00393117871
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00784468744 0.0195092093 -0.00136782846
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ vertex 0.00572999008 0.020759929 -0.000123515827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 0.0287368521 -0.0103536993
+ vertex -0.00220466265 0.0275486708 -0.0103293415
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 0.0287368521 -0.0103536993
+ vertex -0.00202873861 0.0355547331 -0.00898484141
+ vertex 0.00217980286 0.0353009887 -0.00865814555
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 0.0287368521 -0.0103536993
+ vertex 0.00217980286 0.0353009887 -0.00865814555
+ vertex 0.00764033338 0.0167477541 -0.00928799529
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 0.0287368521 -0.0103536993
+ vertex 0.00764033338 0.0167477541 -0.00928799529
+ vertex 0.00716874655 0.000724797661 -0.0109065594
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 0.0287368521 -0.0103536993
+ vertex 0.00716874655 0.000724797661 -0.0109065594
+ vertex 0.00399830472 0.00144497002 -0.0113348197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00111844286 0.0287368521 -0.0103536993
+ vertex 0.00399830472 0.00144497002 -0.0113348197
+ vertex -0.00220466265 0.0275486708 -0.0103293415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313784782 0.00404747901 0.000405219267
+ vertex -0.003010188 -0.00065022608 -0.00200673961
+ vertex -0.000620731618 -0.00541405519 -0.00214476418
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313784782 0.00404747901 0.000405219267
+ vertex -0.000620731618 -0.00541405519 -0.00214476418
+ vertex 0.00399830472 0.00144497002 0.00133481983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313784782 0.00404747901 0.000405219267
+ vertex 0.00399830472 0.00144497002 0.00133481983
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313784782 0.00404747901 0.000405219267
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ vertex -0.00369461486 0.0290614646 -0.00127628434
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313784782 0.00404747901 0.000405219267
+ vertex -0.00369461486 0.0290614646 -0.00127628434
+ vertex -0.003010188 -0.00065022608 -0.00200673961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313784782 0.00404747901 -0.0104052192
+ vertex -0.00220466265 0.0275486708 -0.0103293415
+ vertex 0.00399830472 0.00144497002 -0.0113348197
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000313784782 0.00404747901 -0.0104052192
+ vertex -0.00269060046 -0.0019602722 -0.0079932604
+ vertex -0.00220466265 0.0275486708 -0.0103293415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358808646 0.0350547694 -0.00674667116
+ vertex 0.00254756794 0.0367584564 -0.00501046702
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358808646 0.0350547694 -0.00674667116
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ vertex 0.00864649843 0.0192871764 -0.00393117871
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358808646 0.0350547694 -0.00674667116
+ vertex 0.00864649843 0.0192871764 -0.00393117871
+ vertex 0.00794922467 0.0206090417 -0.00777530856
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00358808646 0.0350547694 -0.00674667116
+ vertex 0.00794922467 0.0206090417 -0.00777530856
+ vertex 0.00217980286 0.0353009887 -0.00865814555
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565673 0.0339018591 -0.00210570847
+ vertex -0.00442683464 0.0322108492 -0.00499999989
+ vertex -0.00369461486 0.0290614646 -0.00127628434
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565673 0.0339018591 -0.00210570847
+ vertex -0.00369461486 0.0290614646 -0.00127628434
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565673 0.0339018591 -0.00210570847
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ vertex -0.00159872253 0.0357632451 -0.000914807082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565673 0.0339018591 -0.00210570847
+ vertex -0.00159872253 0.0357632451 -0.000914807082
+ vertex -0.00301370677 0.0357657261 -0.00498953229
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350565673 0.0339018591 -0.00210570847
+ vertex -0.00301370677 0.0357657261 -0.00498953229
+ vertex -0.00442683464 0.0322108492 -0.00499999989
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 0.0305631813 -3.98206721e-05
+ vertex 0.00572999008 0.020759929 -0.000123515827
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 0.0305631813 -3.98206721e-05
+ vertex 0.00322755682 0.0347205065 -0.00198169984
+ vertex -0.00159872253 0.0357632451 -0.000914807082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00179571763 0.0305631813 -3.98206721e-05
+ vertex -0.00159872253 0.0357632451 -0.000914807082
+ vertex -0.00178322615 0.0294491332 0.000425221719
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/R_hand_base_link.STL b/assets/inspire_hand/meshes/R_hand_base_link.STL
new file mode 100644
index 0000000..3478a98
Binary files /dev/null and b/assets/inspire_hand/meshes/R_hand_base_link.STL differ
diff --git a/assets/inspire_hand/meshes/R_hand_base_link.STL.convex.stl b/assets/inspire_hand/meshes/R_hand_base_link.STL.convex.stl
new file mode 100644
index 0000000..fb48c12
--- /dev/null
+++ b/assets/inspire_hand/meshes/R_hand_base_link.STL.convex.stl
@@ -0,0 +1,1554 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0 -4.32133662e-10 0.0259999987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0 -4.32133662e-10 0.0259999987
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ vertex 0.0260000005 -4.32133662e-10 -6.9388939e-17
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.0260000005 -4.32133662e-10 -6.9388939e-17
+ vertex 0.0255223047 -4.32133662e-10 -0.00496103382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.0255223047 -4.32133662e-10 -0.00496103382
+ vertex 0.0218054354 -4.32133662e-10 -0.0141606145
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.0218054354 -4.32133662e-10 -0.0141606145
+ vertex 0.0149129862 -4.32133662e-10 -0.021297954
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.0149129862 -4.32133662e-10 -0.021297954
+ vertex 0.00584872719 -4.32133662e-10 -0.0253336206
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0.00584872719 -4.32133662e-10 -0.0253336206
+ vertex 0 -4.32133662e-10 -0.0259999987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex 0 -4.32133662e-10 -0.0259999987
+ vertex -0.00584872719 -4.32133662e-10 -0.0253336206
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.00584872719 -4.32133662e-10 -0.0253336206
+ vertex -0.0149129862 -4.32133662e-10 -0.021297954
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.0149129862 -4.32133662e-10 -0.021297954
+ vertex -0.0218054354 -4.32133662e-10 -0.0141606145
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.0218054354 -4.32133662e-10 -0.0141606145
+ vertex -0.0255223047 -4.32133662e-10 -0.00496103382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.0255223047 -4.32133662e-10 -0.00496103382
+ vertex -0.0255223047 -4.32133662e-10 0.00496103382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00610646559 -0.0589670315 0.0368851013
+ vertex 0 -4.32133662e-10 0.0259999987
+ vertex -0.00918240473 -0.0585404932 0.0388909318
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00882619713 -0.0679832771 -0.0353268236
+ vertex 0.0102642206 -0.00809999928 -0.025404837
+ vertex 0.0149129862 -4.32133662e-10 -0.021297954
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00882619713 -0.0679832771 -0.0353268236
+ vertex 0.0149129862 -4.32133662e-10 -0.021297954
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0207397547 -0.0680999979 -0.0225905795
+ vertex -0.0111047151 -0.124200799 -0.0346445888
+ vertex -0.0248217955 -0.0667093098 -0.00540350098
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ vertex 4.00000536e-05 -0.141044259 -0.0304242466
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ vertex 0.00606429204 -0.124342725 -0.0385328978
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125459097 -0.124702446 0.00402649352
+ vertex -0.011254359 -0.122295901 0.0356877372
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125459097 -0.124702446 0.00402649352
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ vertex -0.0248217955 -0.0667093098 -0.00540350098
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125459097 -0.124702446 0.00402649352
+ vertex -0.0248217955 -0.0667093098 -0.00540350098
+ vertex -0.0111047151 -0.124200799 -0.0346445888
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0125459097 -0.124702446 0.00402649352
+ vertex -0.0111047151 -0.124200799 -0.0346445888
+ vertex -0.00650519738 -0.137646362 -0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0 -4.32133662e-10 0.0259999987
+ vertex 0.00610646559 -0.0589670315 0.0368851013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex -0.00918240473 -0.0585404932 0.0388909318
+ vertex 0 -4.32133662e-10 0.0259999987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218054354 -4.32133662e-10 -0.0141606145
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ vertex 0.0149129862 -4.32133662e-10 -0.021297954
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 -0.0141606145
+ vertex -0.0149129862 -4.32133662e-10 -0.021297954
+ vertex -0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0119094839 -0.133188874 0.031678021
+ vertex 0.00207073404 -0.138791963 0.0358665772
+ vertex 0.0118852062 -0.135262638 0.0125494506
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0119094839 -0.133188874 0.031678021
+ vertex 0.0132410703 -0.130027235 0.0350185521
+ vertex 0.0109678274 -0.129425094 0.0390811898
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0119094839 -0.133188874 0.031678021
+ vertex 0.0109678274 -0.129425094 0.0390811898
+ vertex 0.00207073404 -0.138791963 0.0358665772
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0133587075 -0.0975683331 -0.0333538204
+ vertex 0.0136941085 -0.128463626 -0.0313546881
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0133587075 -0.0975683331 -0.0333538204
+ vertex 0.00882619713 -0.0679832771 -0.0353268236
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0140761351 -0.124878258 0.0363072902
+ vertex 0.0148074683 -0.128393143 0.0305835977
+ vertex 0.0269811135 -0.0153944725 0.00477277534
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0104187205 -0.0740708858 -0.0366509333
+ vertex -0.00261319615 -0.0755207092 -0.0383646116
+ vertex -0.00508599356 -0.12383718 -0.0385894775
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0104187205 -0.0740708858 -0.0366509333
+ vertex -0.00508599356 -0.12383718 -0.0385894775
+ vertex -0.0101985633 -0.112879418 -0.03760086
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0273340046 -0.0173235666 -0.00190075045
+ vertex -0.0248217955 -0.0667093098 -0.00540350098
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.027383307 -0.00809999928 -0.000956246222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ vertex -0.027383307 -0.00809999928 -0.000956246222
+ vertex -0.0273340046 -0.0173235666 -0.00190075045
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0273340046 -0.0173235666 -0.00190075045
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ vertex -0.0207397547 -0.0680999979 -0.0225905795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0273340046 -0.0173235666 -0.00190075045
+ vertex -0.0207397547 -0.0680999979 -0.0225905795
+ vertex -0.0248217955 -0.0667093098 -0.00540350098
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0157182682 -0.0556166768 0.0361930132
+ vertex -0.00918240473 -0.0585404932 0.0388909318
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0157182682 -0.0556166768 0.0361930132
+ vertex -0.0105751529 -4.32133662e-10 0.0237521827
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ vertex -0.0255223047 -4.32133662e-10 -0.00496103382
+ vertex -0.0218054354 -4.32133662e-10 -0.0141606145
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00918240473 -0.0585404932 0.0388909318
+ vertex -0.0157182682 -0.0556166768 0.0361930132
+ vertex -0.0140070468 -0.0764443204 0.0390844345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00918240473 -0.0585404932 0.0388909318
+ vertex -0.0140070468 -0.0764443204 0.0390844345
+ vertex -0.0092670396 -0.0801111534 0.0412327386
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.011254359 -0.122295901 0.0356877372
+ vertex -0.0125459097 -0.124702446 0.00402649352
+ vertex -0.00767645938 -0.133238018 0.0352828316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0111610377 -0.134130195 -0.0317227021
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ vertex 0.0136941085 -0.128463626 -0.0313546881
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 -0.0383646116
+ vertex -0.0104187205 -0.0740708858 -0.0366509333
+ vertex -0.00895999651 -0.0610967763 -0.0359849855
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00261319615 -0.0755207092 -0.0383646116
+ vertex -0.00895999651 -0.0610967763 -0.0359849855
+ vertex -0.00452458998 -0.0607422665 -0.0368810222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149987014 -0.130909085 -0.00694603985
+ vertex 0.0144784767 -0.130661398 -0.0260582734
+ vertex 0.0162261464 -0.12460582 -0.00690309471
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149987014 -0.130909085 -0.00694603985
+ vertex 0.0162261464 -0.12460582 -0.00690309471
+ vertex 0.0148074683 -0.128393143 0.0305835977
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149987014 -0.130909085 -0.00694603985
+ vertex 0.0148074683 -0.128393143 0.0305835977
+ vertex 0.0119094839 -0.133188874 0.031678021
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149987014 -0.130909085 -0.00694603985
+ vertex 0.0119094839 -0.133188874 0.031678021
+ vertex 0.0118852062 -0.135262638 0.0125494506
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149987014 -0.130909085 -0.00694603985
+ vertex 0.0118852062 -0.135262638 0.0125494506
+ vertex 0.0118030375 -0.13570255 -0.0262240786
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0216429979 -0.0626868457 0.0306501053
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0103843873 -0.124664545 0.0407904722
+ vertex 0.0140761351 -0.124878258 0.0363072902
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0103843873 -0.124664545 0.0407904722
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0102947233 -0.0831697062 0.0371937528
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00584872719 -4.32133662e-10 -0.0253336206
+ vertex 0 -4.32133662e-10 -0.0259999987
+ vertex -0.00452458998 -0.0607422665 -0.0368810222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00950194523 -0.122374527 0.0402224213
+ vertex -0.011254359 -0.122295901 0.0356877372
+ vertex -0.00767645938 -0.133238018 0.0352828316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00950194523 -0.122374527 0.0402224213
+ vertex -0.00767645938 -0.133238018 0.0352828316
+ vertex -0.00456004171 -0.137647942 0.035746336
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00950194523 -0.122374527 0.0402224213
+ vertex -0.00456004171 -0.137647942 0.035746336
+ vertex -0.0059071756 -0.12638855 0.0415144153
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00950194523 -0.122374527 0.0402224213
+ vertex -0.0059071756 -0.12638855 0.0415144153
+ vertex -0.0092960922 -0.116773739 0.0412444361
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584872719 -4.32133662e-10 -0.0253336206
+ vertex 0.0149129862 -4.32133662e-10 -0.021297954
+ vertex 0.0102642206 -0.00809999928 -0.025404837
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ vertex 0.0218054354 -4.32133662e-10 -0.0141606145
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.0218054354 -4.32133662e-10 -0.0141606145
+ vertex 0.0255223047 -4.32133662e-10 -0.00496103382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.0255223047 -4.32133662e-10 -0.00496103382
+ vertex 0.027383307 -0.00809999928 0.000956246222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.027383307 -0.00809999928 0.000956246222
+ vertex 0.026516512 -0.0163385347 -0.00690177921
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.026516512 -0.0163385347 -0.00690177921
+ vertex 0.0136941085 -0.128463626 -0.0313546881
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.0136941085 -0.128463626 -0.0313546881
+ vertex 0.0133587075 -0.0975683331 -0.0333538204
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 -0.011144584
+ vertex 0.0133587075 -0.0975683331 -0.0333538204
+ vertex 0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00390022597 -0.120740585 0.042694781
+ vertex -0.0092670396 -0.0801111534 0.0412327386
+ vertex -0.0092960922 -0.116773739 0.0412444361
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00390022597 -0.120740585 0.042694781
+ vertex -0.0092960922 -0.116773739 0.0412444361
+ vertex -0.0059071756 -0.12638855 0.0415144153
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00390022597 -0.120740585 0.042694781
+ vertex -0.0059071756 -0.12638855 0.0415144153
+ vertex 0.00647685537 -0.123415522 0.0423916616
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 4.00000536e-05 -0.140831023 0.0165063459
+ vertex -0.00207098434 -0.138812795 0.0358687639
+ vertex -0.00456004171 -0.138484195 0.027790159
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 4.00000536e-05 -0.140831023 0.0165063459
+ vertex -0.00456004171 -0.138484195 0.027790159
+ vertex -0.00456004171 -0.140095204 -0.00294999941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 4.00000536e-05 -0.140831023 0.0165063459
+ vertex -0.00456004171 -0.140095204 -0.00294999941
+ vertex 0.000540000095 -0.141550004 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0200802907 -0.052877482 -0.0238302965
+ vertex -0.0104187205 -0.0740708858 -0.0366509333
+ vertex -0.0101985633 -0.112879418 -0.03760086
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0200802907 -0.052877482 -0.0238302965
+ vertex -0.0101985633 -0.112879418 -0.03760086
+ vertex -0.0207397547 -0.0680999979 -0.0225905795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0200802907 -0.052877482 -0.0238302965
+ vertex -0.0207397547 -0.0680999979 -0.0225905795
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0200802907 -0.052877482 -0.0238302965
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ vertex -0.0218054354 -4.32133662e-10 -0.0141606145
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0200802907 -0.052877482 -0.0238302965
+ vertex -0.0218054354 -4.32133662e-10 -0.0141606145
+ vertex -0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0200802907 -0.052877482 -0.0238302965
+ vertex -0.0190336388 -0.00809999928 -0.0197099112
+ vertex -0.0104187205 -0.0740708858 -0.0366509333
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0209639873 -0.0722595677 0.0318062119
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ vertex -0.011254359 -0.122295901 0.0356877372
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0209639873 -0.0722595677 0.0318062119
+ vertex -0.011254359 -0.122295901 0.0356877372
+ vertex -0.00950194523 -0.122374527 0.0402224213
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0209639873 -0.0722595677 0.0318062119
+ vertex -0.00950194523 -0.122374527 0.0402224213
+ vertex -0.0092960922 -0.116773739 0.0412444361
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0209639873 -0.0722595677 0.0318062119
+ vertex -0.0092960922 -0.116773739 0.0412444361
+ vertex -0.0190757066 -0.0661247447 0.0348557718
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0209639873 -0.0722595677 0.0318062119
+ vertex -0.0190757066 -0.0661247447 0.0348557718
+ vertex -0.0216429979 -0.0626868457 0.0306501053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0209639873 -0.0722595677 0.0318062119
+ vertex -0.0216429979 -0.0626868457 0.0306501053
+ vertex -0.0224542413 -0.0724598542 0.0259524435
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 -0.0260582734
+ vertex 0.0149987014 -0.130909085 -0.00694603985
+ vertex 0.0118030375 -0.13570255 -0.0262240786
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 -0.0260582734
+ vertex 0.0118030375 -0.13570255 -0.0262240786
+ vertex 0.0111610377 -0.134130195 -0.0317227021
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0144784767 -0.130661398 -0.0260582734
+ vertex 0.0111610377 -0.134130195 -0.0317227021
+ vertex 0.0136941085 -0.128463626 -0.0313546881
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0216429979 -0.0626868457 0.0306501053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ vertex -0.0255223047 -4.32133662e-10 0.00496103382
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00610646559 -0.0589670315 0.0368851013
+ vertex -0.00918240473 -0.0585404932 0.0388909318
+ vertex -0.0092670396 -0.0801111534 0.0412327386
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00610646559 -0.0589670315 0.0368851013
+ vertex -0.0092670396 -0.0801111534 0.0412327386
+ vertex 0.00419739075 -0.0827994943 0.0402534939
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00419739075 -0.0827994943 0.0402534939
+ vertex -0.0092670396 -0.0801111534 0.0412327386
+ vertex -0.00390022597 -0.120740585 0.042694781
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00419739075 -0.0827994943 0.0402534939
+ vertex -0.00390022597 -0.120740585 0.042694781
+ vertex 0.00647685537 -0.123415522 0.0423916616
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102947233 -0.0831697062 0.0371937528
+ vertex 0.00610646559 -0.0589670315 0.0368851013
+ vertex 0.00419739075 -0.0827994943 0.0402534939
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102947233 -0.0831697062 0.0371937528
+ vertex 0.00419739075 -0.0827994943 0.0402534939
+ vertex 0.00647685537 -0.123415522 0.0423916616
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102947233 -0.0831697062 0.0371937528
+ vertex 0.00647685537 -0.123415522 0.0423916616
+ vertex 0.0103843873 -0.124664545 0.0407904722
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00508599356 -0.12383718 -0.0385894775
+ vertex -0.00261319615 -0.0755207092 -0.0383646116
+ vertex 0.00606429204 -0.124342725 -0.0385328978
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00508599356 -0.12383718 -0.0385894775
+ vertex 0.00606429204 -0.124342725 -0.0385328978
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101397848 -0.124162696 -0.0367597491
+ vertex -0.0111047151 -0.124200799 -0.0346445888
+ vertex -0.0207397547 -0.0680999979 -0.0225905795
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101397848 -0.124162696 -0.0367597491
+ vertex -0.0207397547 -0.0680999979 -0.0225905795
+ vertex -0.0101985633 -0.112879418 -0.03760086
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101985633 -0.112879418 -0.03760086
+ vertex -0.00508599356 -0.12383718 -0.0385894775
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101985633 -0.112879418 -0.03760086
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ vertex -0.0101397848 -0.124162696 -0.0367597491
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101397848 -0.124162696 -0.0367597491
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ vertex -0.00650519738 -0.137646362 -0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0101397848 -0.124162696 -0.0367597491
+ vertex -0.00650519738 -0.137646362 -0.0303055886
+ vertex -0.0111047151 -0.124200799 -0.0346445888
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00185933313 -0.0605261698 -0.0365209356
+ vertex -0.00452458998 -0.0607422665 -0.0368810222
+ vertex 0 -4.32133662e-10 -0.0259999987
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00185933313 -0.0605261698 -0.0365209356
+ vertex 0 -4.32133662e-10 -0.0259999987
+ vertex 0.00584872719 -4.32133662e-10 -0.0253336206
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00185933313 -0.0605261698 -0.0365209356
+ vertex 0.00584872719 -4.32133662e-10 -0.0253336206
+ vertex 0.0102642206 -0.00809999928 -0.025404837
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00185933313 -0.0605261698 -0.0365209356
+ vertex 0.0102642206 -0.00809999928 -0.025404837
+ vertex 0.00882619713 -0.0679832771 -0.0353268236
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00185933313 -0.0605261698 -0.0365209356
+ vertex -0.00261319615 -0.0755207092 -0.0383646116
+ vertex -0.00452458998 -0.0607422665 -0.0368810222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.027383307 -0.00809999928 -0.000956246222
+ vertex -0.0255223047 -4.32133662e-10 -0.00496103382
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.027383307 -0.00809999928 -0.000956246222
+ vertex -0.0250311457 -0.00809999928 -0.011144584
+ vertex -0.0273340046 -0.0173235666 -0.00190075045
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.027383307 -0.00809999928 -0.000956246222
+ vertex -0.02669774 -0.00809999928 0.00616365904
+ vertex -0.0255223047 -4.32133662e-10 0.00496103382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.027383307 -0.00809999928 -0.000956246222
+ vertex -0.0255223047 -4.32133662e-10 0.00496103382
+ vertex -0.0255223047 -4.32133662e-10 -0.00496103382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00895999651 -0.0610967763 -0.0359849855
+ vertex -0.0149129862 -4.32133662e-10 -0.021297954
+ vertex -0.00584872719 -4.32133662e-10 -0.0253336206
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00895999651 -0.0610967763 -0.0359849855
+ vertex -0.00584872719 -4.32133662e-10 -0.0253336206
+ vertex -0.00452458998 -0.0607422665 -0.0368810222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00895999651 -0.0610967763 -0.0359849855
+ vertex -0.0104187205 -0.0740708858 -0.0366509333
+ vertex -0.0190336388 -0.00809999928 -0.0197099112
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00895999651 -0.0610967763 -0.0359849855
+ vertex -0.0190336388 -0.00809999928 -0.0197099112
+ vertex -0.0149129862 -4.32133662e-10 -0.021297954
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0260000005 -4.32133662e-10 -6.9388939e-17
+ vertex 0.027383307 -0.00809999928 0.000956246222
+ vertex 0.0255223047 -4.32133662e-10 -0.00496103382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.0255223047 -4.32133662e-10 0.00496103382
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0192147028 -0.0557070896 0.0333674178
+ vertex -0.0190757066 -0.0661247447 0.0348557718
+ vertex -0.0157182682 -0.0556166768 0.0361930132
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0192147028 -0.0557070896 0.0333674178
+ vertex -0.0157182682 -0.0556166768 0.0361930132
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0192147028 -0.0557070896 0.0333674178
+ vertex -0.0187028348 -4.32133662e-10 0.0180611182
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0192147028 -0.0557070896 0.0333674178
+ vertex -0.0218054354 -4.32133662e-10 0.0141606145
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0192147028 -0.0557070896 0.0333674178
+ vertex -0.0250311457 -0.00809999928 0.011144584
+ vertex -0.0216429979 -0.0626868457 0.0306501053
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0192147028 -0.0557070896 0.0333674178
+ vertex -0.0216429979 -0.0626868457 0.0306501053
+ vertex -0.0190757066 -0.0661247447 0.0348557718
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132410703 -0.130027235 0.0350185521
+ vertex 0.0119094839 -0.133188874 0.031678021
+ vertex 0.0148074683 -0.128393143 0.0305835977
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132410703 -0.130027235 0.0350185521
+ vertex 0.0148074683 -0.128393143 0.0305835977
+ vertex 0.0140761351 -0.124878258 0.0363072902
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132410703 -0.130027235 0.0350185521
+ vertex 0.0140761351 -0.124878258 0.0363072902
+ vertex 0.0109678274 -0.129425094 0.0390811898
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0109678274 -0.129425094 0.0390811898
+ vertex 0.0140761351 -0.124878258 0.0363072902
+ vertex 0.0103843873 -0.124664545 0.0407904722
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0109678274 -0.129425094 0.0390811898
+ vertex 0.0103843873 -0.124664545 0.0407904722
+ vertex 0.00969055761 -0.127307639 0.0410738997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00969055761 -0.127307639 0.0410738997
+ vertex 0.0103843873 -0.124664545 0.0407904722
+ vertex 0.00647685537 -0.123415522 0.0423916616
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00969055761 -0.127307639 0.0410738997
+ vertex 0.00647685537 -0.123415522 0.0423916616
+ vertex -0.0059071756 -0.12638855 0.0415144153
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00969055761 -0.127307639 0.0410738997
+ vertex 0.00207073404 -0.138791963 0.0358665772
+ vertex 0.0109678274 -0.129425094 0.0390811898
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 0.011144584
+ vertex 0.0269811135 -0.0153944725 0.00477277534
+ vertex 0.027383307 -0.00809999928 0.000956246222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 0.011144584
+ vertex 0.027383307 -0.00809999928 0.000956246222
+ vertex 0.0260000005 -4.32133662e-10 -6.9388939e-17
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 0.011144584
+ vertex 0.0260000005 -4.32133662e-10 -6.9388939e-17
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 0.011144584
+ vertex 0.0241067782 -4.32133662e-10 0.00973977149
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 0.011144584
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0140761351 -0.124878258 0.0363072902
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0250311457 -0.00809999928 0.011144584
+ vertex 0.0140761351 -0.124878258 0.0363072902
+ vertex 0.0269811135 -0.0153944725 0.00477277534
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 -0.0303734709
+ vertex 4.00000536e-05 -0.141044259 -0.0304242466
+ vertex 0.000540000095 -0.141550004 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 -0.0303734709
+ vertex 0.000540000095 -0.141550004 -0.00954999961
+ vertex -0.00456004171 -0.140095204 -0.00294999941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 -0.0303734709
+ vertex -0.00456004171 -0.140095204 -0.00294999941
+ vertex -0.00650519738 -0.137646362 -0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 -0.0303734709
+ vertex -0.00650519738 -0.137646362 -0.0303055886
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00456004171 -0.139590338 -0.0303734709
+ vertex -0.00716353394 -0.128624678 -0.0372513905
+ vertex 4.00000536e-05 -0.141044259 -0.0304242466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00952712633 -0.0973969027 -0.0366516709
+ vertex 0.00882619713 -0.0679832771 -0.0353268236
+ vertex 0.0133587075 -0.0975683331 -0.0333538204
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00952712633 -0.0973969027 -0.0366516709
+ vertex 0.0133587075 -0.0975683331 -0.0333538204
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00952712633 -0.0973969027 -0.0366516709
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ vertex 0.00606429204 -0.124342725 -0.0385328978
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00606429204 -0.124342725 -0.0385328978
+ vertex -0.00261319615 -0.0755207092 -0.0383646116
+ vertex 0.00185933313 -0.0605261698 -0.0365209356
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00606429204 -0.124342725 -0.0385328978
+ vertex 0.00185933313 -0.0605261698 -0.0365209356
+ vertex 0.00882619713 -0.0679832771 -0.0353268236
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00606429204 -0.124342725 -0.0385328978
+ vertex 0.00882619713 -0.0679832771 -0.0353268236
+ vertex 0.00952712633 -0.0973969027 -0.0366516709
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.0297625195 -0.00132007245
+ vertex 0.0269811135 -0.0153944725 0.00477277534
+ vertex 0.0148074683 -0.128393143 0.0305835977
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.0297625195 -0.00132007245
+ vertex 0.0148074683 -0.128393143 0.0305835977
+ vertex 0.0162261464 -0.12460582 -0.00690309471
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.0297625195 -0.00132007245
+ vertex 0.0162261464 -0.12460582 -0.00690309471
+ vertex 0.0144784767 -0.130661398 -0.0260582734
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.0297625195 -0.00132007245
+ vertex 0.0144784767 -0.130661398 -0.0260582734
+ vertex 0.0136941085 -0.128463626 -0.0313546881
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.0297625195 -0.00132007245
+ vertex 0.0136941085 -0.128463626 -0.0313546881
+ vertex 0.026516512 -0.0163385347 -0.00690177921
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.0297625195 -0.00132007245
+ vertex 0.026516512 -0.0163385347 -0.00690177921
+ vertex 0.027383307 -0.00809999928 0.000956246222
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262385644 -0.0297625195 -0.00132007245
+ vertex 0.027383307 -0.00809999928 0.000956246222
+ vertex 0.0269811135 -0.0153944725 0.00477277534
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00650519738 -0.137854412 0.00833936967
+ vertex -0.00650519738 -0.137646362 -0.0303055886
+ vertex -0.00456004171 -0.140095204 -0.00294999941
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00650519738 -0.137854412 0.00833936967
+ vertex -0.00456004171 -0.140095204 -0.00294999941
+ vertex -0.00456004171 -0.138484195 0.027790159
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00650519738 -0.137854412 0.00833936967
+ vertex -0.00456004171 -0.138484195 0.027790159
+ vertex -0.00456004171 -0.137647942 0.035746336
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00650519738 -0.137854412 0.00833936967
+ vertex -0.00456004171 -0.137647942 0.035746336
+ vertex -0.00767645938 -0.133238018 0.0352828316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00650519738 -0.137854412 0.00833936967
+ vertex -0.00767645938 -0.133238018 0.0352828316
+ vertex -0.0125459097 -0.124702446 0.00402649352
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00650519738 -0.137854412 0.00833936967
+ vertex -0.0125459097 -0.124702446 0.00402649352
+ vertex -0.00650519738 -0.137646362 -0.0303055886
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140070468 -0.0764443204 0.0390844345
+ vertex -0.0092960922 -0.116773739 0.0412444361
+ vertex -0.0092670396 -0.0801111534 0.0412327386
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140070468 -0.0764443204 0.0390844345
+ vertex -0.0157182682 -0.0556166768 0.0361930132
+ vertex -0.0190757066 -0.0661247447 0.0348557718
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140070468 -0.0764443204 0.0390844345
+ vertex -0.0190757066 -0.0661247447 0.0348557718
+ vertex -0.0092960922 -0.116773739 0.0412444361
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00207098434 -0.138812795 0.0358687639
+ vertex -0.00456004171 -0.137647942 0.035746336
+ vertex -0.00456004171 -0.138484195 0.027790159
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00207098434 -0.138812795 0.0358687639
+ vertex 4.00000536e-05 -0.140831023 0.0165063459
+ vertex 0.00207073404 -0.138791963 0.0358665772
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00207098434 -0.138812795 0.0358687639
+ vertex 0.00207073404 -0.138791963 0.0358665772
+ vertex 0.00969055761 -0.127307639 0.0410738997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00207098434 -0.138812795 0.0358687639
+ vertex 0.00969055761 -0.127307639 0.0410738997
+ vertex -0.0059071756 -0.12638855 0.0415144153
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00207098434 -0.138812795 0.0358687639
+ vertex -0.0059071756 -0.12638855 0.0415144153
+ vertex -0.00456004171 -0.137647942 0.035746336
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149231097 -0.00809999928 0.0229795743
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149231097 -0.00809999928 0.0229795743
+ vertex 0.0105751529 -4.32133662e-10 0.0237521827
+ vertex 0.00610646559 -0.0589670315 0.0368851013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0149231097 -0.00809999928 0.0229795743
+ vertex 0.00610646559 -0.0589670315 0.0368851013
+ vertex 0.0102947233 -0.0831697062 0.0371937528
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102947233 -0.0831697062 0.0371937528
+ vertex 0.0224447642 -0.00809999928 0.0157159939
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0102947233 -0.0831697062 0.0371937528
+ vertex 0.0187028348 -4.32133662e-10 0.0180611182
+ vertex 0.0149231097 -0.00809999928 0.0229795743
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 -0.0304136146
+ vertex 4.00000536e-05 -0.141044259 -0.0304242466
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 -0.0304136146
+ vertex 0.0094899321 -0.129924372 -0.0364001319
+ vertex 0.0111610377 -0.134130195 -0.0317227021
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 -0.0304136146
+ vertex 0.0111610377 -0.134130195 -0.0317227021
+ vertex 0.0118030375 -0.13570255 -0.0262240786
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 -0.0304136146
+ vertex 0.000540000095 -0.141550004 -0.00954999961
+ vertex 4.00000536e-05 -0.141044259 -0.0304242466
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00254000025 -0.140714556 0.00848926418
+ vertex 0.0118852062 -0.135262638 0.0125494506
+ vertex 0.00207073404 -0.138791963 0.0358665772
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00254000025 -0.140714556 0.00848926418
+ vertex 0.00207073404 -0.138791963 0.0358665772
+ vertex 4.00000536e-05 -0.140831023 0.0165063459
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00254000025 -0.140714556 0.00848926418
+ vertex 4.00000536e-05 -0.140831023 0.0165063459
+ vertex 0.000540000095 -0.141550004 -0.00954999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00254000025 -0.140714556 0.00848926418
+ vertex 0.000540000095 -0.141550004 -0.00954999961
+ vertex 0.00207073404 -0.140739962 -0.0304136146
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 -0.0304136146
+ vertex 0.0118030375 -0.13570255 -0.0262240786
+ vertex 0.0118852062 -0.135262638 0.0125494506
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00207073404 -0.140739962 -0.0304136146
+ vertex 0.0118852062 -0.135262638 0.0125494506
+ vertex 0.00254000025 -0.140714556 0.00848926418
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/inspire_hand/meshes/left_ankle_pitch_link.STL b/assets/inspire_hand/meshes/left_ankle_pitch_link.STL
new file mode 100644
index 0000000..827fb2c
Binary files /dev/null and b/assets/inspire_hand/meshes/left_ankle_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_ankle_roll_link.STL b/assets/inspire_hand/meshes/left_ankle_roll_link.STL
new file mode 100644
index 0000000..83e7de1
Binary files /dev/null and b/assets/inspire_hand/meshes/left_ankle_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_elbow_pitch_link.STL b/assets/inspire_hand/meshes/left_elbow_pitch_link.STL
new file mode 100644
index 0000000..47ae65c
Binary files /dev/null and b/assets/inspire_hand/meshes/left_elbow_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_elbow_roll_link.STL b/assets/inspire_hand/meshes/left_elbow_roll_link.STL
new file mode 100644
index 0000000..112437b
Binary files /dev/null and b/assets/inspire_hand/meshes/left_elbow_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_hand_link.STL b/assets/inspire_hand/meshes/left_hand_link.STL
new file mode 100644
index 0000000..6ce2dcf
Binary files /dev/null and b/assets/inspire_hand/meshes/left_hand_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_hip_pitch_link.STL b/assets/inspire_hand/meshes/left_hip_pitch_link.STL
new file mode 100644
index 0000000..e5898ab
Binary files /dev/null and b/assets/inspire_hand/meshes/left_hip_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_hip_roll_link.STL b/assets/inspire_hand/meshes/left_hip_roll_link.STL
new file mode 100644
index 0000000..5ade02b
Binary files /dev/null and b/assets/inspire_hand/meshes/left_hip_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_hip_yaw_link.STL b/assets/inspire_hand/meshes/left_hip_yaw_link.STL
new file mode 100644
index 0000000..3bcc4b8
Binary files /dev/null and b/assets/inspire_hand/meshes/left_hip_yaw_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_knee_link.STL b/assets/inspire_hand/meshes/left_knee_link.STL
new file mode 100644
index 0000000..e470aee
Binary files /dev/null and b/assets/inspire_hand/meshes/left_knee_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_shoulder_pitch_link.STL b/assets/inspire_hand/meshes/left_shoulder_pitch_link.STL
new file mode 100644
index 0000000..be81370
Binary files /dev/null and b/assets/inspire_hand/meshes/left_shoulder_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_shoulder_roll_link.STL b/assets/inspire_hand/meshes/left_shoulder_roll_link.STL
new file mode 100644
index 0000000..a59bb64
Binary files /dev/null and b/assets/inspire_hand/meshes/left_shoulder_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_shoulder_yaw_link.STL b/assets/inspire_hand/meshes/left_shoulder_yaw_link.STL
new file mode 100644
index 0000000..01d3c75
Binary files /dev/null and b/assets/inspire_hand/meshes/left_shoulder_yaw_link.STL differ
diff --git a/assets/inspire_hand/meshes/left_wrist_pitch_link.STL b/assets/inspire_hand/meshes/left_wrist_pitch_link.STL
new file mode 100644
index 0000000..83d6d87
Binary files /dev/null and b/assets/inspire_hand/meshes/left_wrist_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/logo_link.STL b/assets/inspire_hand/meshes/logo_link.STL
new file mode 100644
index 0000000..c396d51
Binary files /dev/null and b/assets/inspire_hand/meshes/logo_link.STL differ
diff --git a/assets/inspire_hand/meshes/pelvis.STL b/assets/inspire_hand/meshes/pelvis.STL
new file mode 100644
index 0000000..05e5512
Binary files /dev/null and b/assets/inspire_hand/meshes/pelvis.STL differ
diff --git a/assets/inspire_hand/meshes/right_ankle_pitch_link.STL b/assets/inspire_hand/meshes/right_ankle_pitch_link.STL
new file mode 100644
index 0000000..827fb2c
Binary files /dev/null and b/assets/inspire_hand/meshes/right_ankle_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_ankle_roll_link.STL b/assets/inspire_hand/meshes/right_ankle_roll_link.STL
new file mode 100644
index 0000000..83e7de1
Binary files /dev/null and b/assets/inspire_hand/meshes/right_ankle_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_elbow_pitch_link.STL b/assets/inspire_hand/meshes/right_elbow_pitch_link.STL
new file mode 100644
index 0000000..360fb7f
Binary files /dev/null and b/assets/inspire_hand/meshes/right_elbow_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_elbow_roll_link.STL b/assets/inspire_hand/meshes/right_elbow_roll_link.STL
new file mode 100644
index 0000000..5f7f228
Binary files /dev/null and b/assets/inspire_hand/meshes/right_elbow_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_hand_link.STL b/assets/inspire_hand/meshes/right_hand_link.STL
new file mode 100644
index 0000000..6ce2dcf
Binary files /dev/null and b/assets/inspire_hand/meshes/right_hand_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_hip_pitch_link.STL b/assets/inspire_hand/meshes/right_hip_pitch_link.STL
new file mode 100644
index 0000000..1d4e515
Binary files /dev/null and b/assets/inspire_hand/meshes/right_hip_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_hip_roll_link.STL b/assets/inspire_hand/meshes/right_hip_roll_link.STL
new file mode 100644
index 0000000..d2a0af9
Binary files /dev/null and b/assets/inspire_hand/meshes/right_hip_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_hip_yaw_link.STL b/assets/inspire_hand/meshes/right_hip_yaw_link.STL
new file mode 100644
index 0000000..6c8ffd5
Binary files /dev/null and b/assets/inspire_hand/meshes/right_hip_yaw_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_knee_link.STL b/assets/inspire_hand/meshes/right_knee_link.STL
new file mode 100644
index 0000000..e470aee
Binary files /dev/null and b/assets/inspire_hand/meshes/right_knee_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_shoulder_pitch_link.STL b/assets/inspire_hand/meshes/right_shoulder_pitch_link.STL
new file mode 100644
index 0000000..f77ab2b
Binary files /dev/null and b/assets/inspire_hand/meshes/right_shoulder_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_shoulder_roll_link.STL b/assets/inspire_hand/meshes/right_shoulder_roll_link.STL
new file mode 100644
index 0000000..a98398f
Binary files /dev/null and b/assets/inspire_hand/meshes/right_shoulder_roll_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_shoulder_yaw_link.STL b/assets/inspire_hand/meshes/right_shoulder_yaw_link.STL
new file mode 100644
index 0000000..7943bab
Binary files /dev/null and b/assets/inspire_hand/meshes/right_shoulder_yaw_link.STL differ
diff --git a/assets/inspire_hand/meshes/right_wrist_pitch_link.STL b/assets/inspire_hand/meshes/right_wrist_pitch_link.STL
new file mode 100644
index 0000000..f21d1f0
Binary files /dev/null and b/assets/inspire_hand/meshes/right_wrist_pitch_link.STL differ
diff --git a/assets/inspire_hand/meshes/torso_link.STL b/assets/inspire_hand/meshes/torso_link.STL
new file mode 100644
index 0000000..649d870
Binary files /dev/null and b/assets/inspire_hand/meshes/torso_link.STL differ
diff --git a/assets/inspire_hand/meshes/wrist_yaw_link.STL b/assets/inspire_hand/meshes/wrist_yaw_link.STL
new file mode 100644
index 0000000..eaff5db
Binary files /dev/null and b/assets/inspire_hand/meshes/wrist_yaw_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_five_link.STL b/assets/unitree_hand/meshes/left_hand_five_link.STL
new file mode 100644
index 0000000..d574489
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_five_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_five_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_five_link.STL.convex.stl
new file mode 100644
index 0000000..dbc476c
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_five_link.STL.convex.stl
@@ -0,0 +1,514 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00549999904 -4.17232499e-10 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ vertex -0.00549999904 -4.17232499e-10 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00549999904 -4.17232499e-10 -0.0127999997
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/left_hand_four_link.STL b/assets/unitree_hand/meshes/left_hand_four_link.STL
new file mode 100644
index 0000000..31990c1
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_four_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_four_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_four_link.STL.convex.stl
new file mode 100644
index 0000000..3fc0a48
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_four_link.STL.convex.stl
@@ -0,0 +1,690 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.067726776 0.002401951 0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ vertex 0.067726776 0.002401951 0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/left_hand_one_link.STL b/assets/unitree_hand/meshes/left_hand_one_link.STL
new file mode 100644
index 0000000..ab486df
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_one_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_one_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_one_link.STL.convex.stl
new file mode 100644
index 0000000..a0c470b
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_one_link.STL.convex.stl
@@ -0,0 +1,514 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex 0.00657784799 0.00239414047 -0.0128999986
+ vertex 0.0142848082 -0.0279263519 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex 0.0142848082 -0.0279263519 -0.0128999986
+ vertex 0.0142848082 -0.0462736487 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex 0.0142848082 -0.0462736487 -0.0128999986
+ vertex -0.000857979583 -0.0616396926 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex -0.000857979583 -0.0616396926 -0.0128999986
+ vertex -0.00453977613 -0.0615910105 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex -0.00453977613 -0.0615910105 -0.0128999986
+ vertex -0.00698768906 -0.0589422211 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex -0.00698768906 -0.0589422211 -0.0128999986
+ vertex -0.00689365482 0.00121553685 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex -0.00689365482 0.00121553685 -0.0128999986
+ vertex -0.00449951272 0.00536231231 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex -0.00449951272 0.00536231231 -0.0128999986
+ vertex 4.17232499e-10 0.00700000208 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0195229407 -0.0493873209 -0.00874405634
+ vertex 0.0195752457 -0.0292240847 -0.00902805198
+ vertex 0.0198698081 -0.0292285774 0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0195229407 -0.0493873209 -0.00874405634
+ vertex 0.0198698081 -0.0292285774 0.00704996567
+ vertex 0.0198519398 -0.0485116169 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0198698081 -0.0292285774 0.00704996567
+ vertex 0.0195752457 -0.0292240847 -0.00902805198
+ vertex 0.00657784799 0.00239414047 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0198698081 -0.0292285774 0.00704996567
+ vertex 0.00657784799 0.00239414047 -0.0128999986
+ vertex 0.00476313988 0.00275000068 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0198698081 -0.0292285774 0.00704996567
+ vertex 0.00476313988 0.00275000068 0.0127999997
+ vertex 0.0143848071 -0.0268263537 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0142848082 -0.0462736487 -0.0128999986
+ vertex 0.0142848082 -0.0279263519 -0.0128999986
+ vertex 0.0195752457 -0.0292240847 -0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0142848082 -0.0462736487 -0.0128999986
+ vertex 0.0195752457 -0.0292240847 -0.00902805198
+ vertex 0.0195229407 -0.0493873209 -0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0112850871 -0.0596943982 -0.00900000054
+ vertex 0.0142848082 -0.0462736487 -0.0128999986
+ vertex 0.0195229407 -0.0493873209 -0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0112850871 -0.0596943982 -0.00900000054
+ vertex 0.0195229407 -0.0493873209 -0.00874405634
+ vertex 0.0198519398 -0.0485116169 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0112850871 -0.0596943982 -0.00900000054
+ vertex 0.0198519398 -0.0485116169 0.00720310537
+ vertex 0.0125870351 -0.0582380779 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000857979583 -0.0616396926 -0.0128999986
+ vertex 0.0142848082 -0.0462736487 -0.0128999986
+ vertex 0.0112850871 -0.0596943982 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000857979583 -0.0616396926 -0.0128999986
+ vertex 0.0112850871 -0.0596943982 -0.00900000054
+ vertex 0.00550000044 -0.0617999993 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536602503 -0.0355000049 0.0127999997
+ vertex -0.00703301234 -0.0588857867 0.00925000012
+ vertex -0.00434222026 -0.0617876872 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951272 0.00536231231 -0.00990000088
+ vertex -0.00689365482 0.00121553685 -0.0128999986
+ vertex -0.00476313895 0.00275000068 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951272 0.00536231231 -0.0128999986
+ vertex -0.00689365482 0.00121553685 -0.0128999986
+ vertex -0.00449951272 0.00536231231 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00453977613 -0.0615910105 -0.0128999986
+ vertex -0.000857979583 -0.0616396926 -0.0128999986
+ vertex 0.00550000044 -0.0617999993 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00453977613 -0.0615910105 -0.0128999986
+ vertex 0.00550000044 -0.0617999993 -0.00900000054
+ vertex 0.00550000044 -0.0617924035 0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00453977613 -0.0615910105 -0.0128999986
+ vertex 0.00550000044 -0.0617924035 0.00908682402
+ vertex -0.00434222026 -0.0617876872 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00434222026 -0.0617876872 0.00899999961
+ vertex -0.00703301234 -0.0588857867 0.00925000012
+ vertex -0.00698768906 -0.0589422211 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00434222026 -0.0617876872 0.00899999961
+ vertex -0.00698768906 -0.0589422211 -0.0128999986
+ vertex -0.00453977613 -0.0615910105 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.00990000088
+ vertex 0.00476313988 0.00275000068 0.0127999997
+ vertex 0.00657784799 0.00239414047 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0142848082 -0.0279263519 -0.0128999986
+ vertex 0.00657784799 0.00239414047 -0.0128999986
+ vertex 0.0195752457 -0.0292240847 -0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex 0.00449951272 0.00536231231 -0.00990000088
+ vertex 0.00657784799 0.00239414047 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00710000051 -0.0280000027 0.00899999961
+ vertex -0.00476313895 0.00275000068 0.0127999997
+ vertex -0.00689365482 0.00121553685 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00689365482 0.00121553685 -0.0128999986
+ vertex -0.00698768906 -0.0589422211 -0.0128999986
+ vertex -0.00703301234 -0.0588857867 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00689365482 0.00121553685 -0.0128999986
+ vertex -0.00703301234 -0.0588857867 0.00925000012
+ vertex -0.00710000051 -0.0280000027 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00710000051 -0.0280000027 0.00899999961
+ vertex -0.00703301234 -0.0588857867 0.00925000012
+ vertex -0.00536602503 -0.0355000049 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00710000051 -0.0280000027 0.00899999961
+ vertex -0.00536602503 -0.0355000049 0.0127999997
+ vertex -0.00476313895 0.00275000068 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0182656925 -0.0492131189 0.00899499655
+ vertex 0.0125870351 -0.0582380779 0.00925000012
+ vertex 0.0198519398 -0.0485116169 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0182656925 -0.0492131189 0.00899499655
+ vertex 0.0198519398 -0.0485116169 0.00720310537
+ vertex 0.0198698081 -0.0292285774 0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0182656925 -0.0492131189 0.00899499655
+ vertex 0.0198698081 -0.0292285774 0.00704996567
+ vertex 0.0143848071 -0.0268263537 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ vertex -0.00536602503 -0.0355000049 0.0127999997
+ vertex -0.00434222026 -0.0617876872 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ vertex -0.00434222026 -0.0617876872 0.00899999961
+ vertex 0.00550000044 -0.0617924035 0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ vertex 0.00550000044 -0.0617924035 0.00908682402
+ vertex 0.00999999978 -0.0605942272 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ vertex 0.00999999978 -0.0605942272 0.00899999961
+ vertex 0.0125870351 -0.0582380779 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ vertex 0.0125870351 -0.0582380779 0.00925000012
+ vertex 0.0182656925 -0.0492131189 0.00899499655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ vertex 0.0182656925 -0.0492131189 0.00899499655
+ vertex 0.0143848071 -0.0268263537 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999999978 -0.0605942272 0.00899999961
+ vertex 0.00550000044 -0.0617924035 0.00908682402
+ vertex 0.00550000044 -0.0617999993 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999999978 -0.0605942272 0.00899999961
+ vertex 0.00550000044 -0.0617999993 -0.00900000054
+ vertex 0.0112850871 -0.0596943982 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999999978 -0.0605942272 0.00899999961
+ vertex 0.0112850871 -0.0596943982 -0.00900000054
+ vertex 0.0125870351 -0.0582380779 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 0.00476314034 0.0127999997
+ vertex 4.17232499e-10 0.00549999904 0.0127999997
+ vertex 4.17232499e-10 0.00700000208 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 0.00476314034 0.0127999997
+ vertex 4.17232499e-10 0.00700000208 -0.00990000088
+ vertex 4.17232499e-10 0.00700000208 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 0.00476314034 0.0127999997
+ vertex 4.17232499e-10 0.00700000208 -0.0128999986
+ vertex -0.00449951272 0.00536231231 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 0.00476314034 0.0127999997
+ vertex -0.00449951272 0.00536231231 -0.0128999986
+ vertex -0.00449951272 0.00536231231 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 0.00476314034 0.0127999997
+ vertex -0.00449951272 0.00536231231 -0.00990000088
+ vertex -0.00476313895 0.00275000068 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 0.00476313988 0.00275000068 0.0127999997
+ vertex 0.00449951272 0.00536231231 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 0.00449951272 0.00536231231 -0.00990000088
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 0.00449951272 0.00536231231 -0.0128999986
+ vertex 4.17232499e-10 0.00700000208 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 4.17232499e-10 0.00700000208 -0.0128999986
+ vertex 4.17232499e-10 0.00700000208 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 4.17232499e-10 0.00700000208 -0.00990000088
+ vertex 4.17232499e-10 0.00549999904 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 4.17232499e-10 0.00549999904 0.0127999997
+ vertex -0.00274999952 0.00476314034 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex -0.00274999952 0.00476314034 0.0127999997
+ vertex -0.00476313895 0.00275000068 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex -0.00476313895 0.00275000068 0.0127999997
+ vertex -0.00536602503 -0.0355000049 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex -0.00536602503 -0.0355000049 0.0127999997
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 0.0137420204 -0.0359396972 0.0127999997
+ vertex 0.0143848071 -0.0268263537 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 0.00476314034 0.0127999997
+ vertex 0.0143848071 -0.0268263537 0.0127999997
+ vertex 0.00476313988 0.00275000068 0.0127999997
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/left_hand_palm_link.STL b/assets/unitree_hand/meshes/left_hand_palm_link.STL
new file mode 100644
index 0000000..4c68928
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_palm_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_palm_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_palm_link.STL.convex.stl
new file mode 100644
index 0000000..bf42a2d
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_palm_link.STL.convex.stl
@@ -0,0 +1,1826 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.0929791778 0.0240329262 0.0221764054
+ vertex 0.0946417376 0.0236909073 -0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.0946417376 0.0236909073 -0.0228220038
+ vertex 0.0822351947 0.0242381375 -0.0316604972
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.0822351947 0.0242381375 -0.0316604972
+ vertex 0.040512275 0.0241192076 -0.0296534151
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.040512275 0.0241192076 -0.0296534151
+ vertex 0.0198960323 0.0236970317 -0.0199881103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.0198960323 0.0236970317 -0.0199881103
+ vertex 0.00780997705 0.0237585288 -0.0051452904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.00780997705 0.0237585288 -0.0051452904
+ vertex 0.0119591318 0.0240044985 0.0111451717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.0119591318 0.0240044985 0.0111451717
+ vertex 0.0499858037 0.0242248494 0.0313238502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0179378465 0.0427427813
+ vertex 0.108945198 -0.011792901 0.0375782177
+ vertex 0.100349553 0.012113275 0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00130202749 -0.00396212796 0.0239653178
+ vertex 0.000813621096 -0.0147488276 0.0207792539
+ vertex 0.0367529877 -0.0196497161 0.0367338806
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0205855183 -0.021230232 -0.0284087285
+ vertex 0.0105307335 -0.0241115689 -0.0180585217
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000827543903 -0.0200854614 0.0154875098
+ vertex -4.33680869e-19 -0.0204886571 0.0058807116
+ vertex 0.000466723082 -0.0220151171 -0.00335950544
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000827543903 -0.0200854614 0.0154875098
+ vertex 0.000466723082 -0.0220151171 -0.00335950544
+ vertex 0.00325558288 -0.0242521018 0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.059854243 -0.0200609211 -0.0413660444
+ vertex 0.087197192 -0.0204425566 -0.0412426963
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.059854243 -0.0200609211 -0.0413660444
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ vertex 0.0450868383 -0.0220738277 -0.036408931
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.106526084 -0.0142641403 -0.0376710109
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.108969845 -0.00179999915 -0.0376710109
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ vertex 0.110197194 0.00729999831 -0.0289999992
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.110197194 0.00729999831 -0.0289999992
+ vertex 0.110085137 0.0117910709 0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.110085137 0.0117910709 0.029902745
+ vertex 0.108945198 -0.011792901 0.0375782177
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.108945198 -0.011792901 0.0375782177
+ vertex 0.106539778 -0.0142910061 0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.106539778 -0.0142910061 0.0375000015
+ vertex 0.106526084 -0.0142641403 -0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ vertex 0.108969845 -0.00179999915 -0.0376710109
+ vertex 0.106593035 0.0114635993 -0.0383162908
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ vertex 0.110085137 0.0117910709 0.029902745
+ vertex 0.110197194 0.00729999831 -0.0289999992
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0386839993 0.0196409728 0.0348441415
+ vertex 0.057112921 0.0175744239 0.0402963273
+ vertex 0.05054418 0.0230156612 0.0343847312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0386839993 0.0196409728 0.0348441415
+ vertex 0.05054418 0.0230156612 0.0343847312
+ vertex 0.0301822927 0.0239052977 0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0010439317 0.0179824214 -0.0128565431
+ vertex 0.0198960323 0.0236970317 -0.0199881103
+ vertex 0.0253822114 0.0197990108 -0.0283071157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0010439317 0.0179824214 -0.0128565431
+ vertex 0.0253822114 0.0197990108 -0.0283071157
+ vertex 0.000815250794 0.0111495871 -0.0192433316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0010439317 0.0179824214 -0.0128565431
+ vertex 0.000815250794 0.0111495871 -0.0192433316
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00100057351 0.0217247847 0.00168395217
+ vertex 0.000972606533 0.0196658205 0.00986019056
+ vertex 0.0119591318 0.0240044985 0.0111451717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00100057351 0.0217247847 0.00168395217
+ vertex 0.0119591318 0.0240044985 0.0111451717
+ vertex 0.00780997705 0.0237585288 -0.0051452904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00109609449 -0.0130085731 -0.021813415
+ vertex 0.0205855183 -0.021230232 -0.0284087285
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00109609449 -0.0130085731 -0.021813415
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ vertex 0.000540190493 -0.00509330677 -0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 0.011894213 0.0428665318
+ vertex 0.100349553 0.012113275 0.0422544107
+ vertex 0.0918507203 0.017598493 0.0412663892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 0.011894213 0.0428665318
+ vertex 0.0918507203 0.017598493 0.0412663892
+ vertex 0.057112921 0.0175744239 0.0402963273
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 0.011894213 0.0428665318
+ vertex 0.0629487932 -0.0172377508 0.0428446829
+ vertex 0.087197192 -0.0179378465 0.0427427813
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 0.011894213 0.0428665318
+ vertex 0.087197192 -0.0179378465 0.0427427813
+ vertex 0.100349553 0.012113275 0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.107092947 0.0170837287 0.0276683085
+ vertex 0.108737834 0.0146880094 0.0309894644
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.107092947 0.0170837287 0.0276683085
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ vertex 0.106343694 0.0170951393 -0.0316420346
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0470071323 -0.0164586306 0.0407023169
+ vertex 0.0629487932 -0.0172377508 0.0428446829
+ vertex 0.0630400777 0.011894213 0.0428665318
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0470071323 -0.0164586306 0.0407023169
+ vertex 0.0630400777 0.011894213 0.0428665318
+ vertex 0.0493300669 0.0108000021 0.0412307456
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108609546 0.00320781744 -0.0230950378
+ vertex 0.0410275012 0.0118555408 -0.0389420204
+ vertex 0.000540190493 -0.00509330677 -0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000813621096 -0.0147488276 0.0207792539
+ vertex 0.000827543903 -0.0200854614 0.0154875098
+ vertex 0.0113188038 -0.023762105 0.0193939283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000813621096 -0.0147488276 0.0207792539
+ vertex 0.0113188038 -0.023762105 0.0193939283
+ vertex 0.0187891237 -0.0216411445 0.0271195248
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0187891237 -0.0216411445 0.0271195248
+ vertex 0.0367529877 -0.0196497161 0.0367338806
+ vertex 0.000813621096 -0.0147488276 0.0207792539
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0929791778 0.0240329262 0.0221764054
+ vertex 0.101307355 0.0211336818 0.0262018219
+ vertex 0.0946417376 0.0236909073 -0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.053119909 -0.0242999997 2.50523644e-05
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ vertex 0.087197192 -0.022126114 0.0379388034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.056487333 -0.0162701067 -0.042417977
+ vertex 0.0616687201 0.0108000021 -0.0428737625
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.056487333 -0.0162701067 -0.042417977
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ vertex 0.059854243 -0.0200609211 -0.0413660444
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.056487333 -0.0162701067 -0.042417977
+ vertex 0.059854243 -0.0200609211 -0.0413660444
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ vertex 0.0410275012 0.0118555408 -0.0389420204
+ vertex 0.0511443056 0.0141101684 -0.041027382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ vertex 0.0511443056 0.0141101684 -0.041027382
+ vertex 0.0616687201 0.0108000021 -0.0428737625
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ vertex 0.0616687201 0.0108000021 -0.0428737625
+ vertex 0.056487333 -0.0162701067 -0.042417977
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0902594849 0.0186875556 -0.0406222567
+ vertex 0.0559303612 0.0197001118 -0.0386815257
+ vertex 0.0859468654 0.0226191785 -0.0365190059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0902594849 0.0186875556 -0.0406222567
+ vertex 0.0859468654 0.0226191785 -0.0365190059
+ vertex 0.0973515064 0.0192573983 -0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0902594849 0.0186875556 -0.0406222567
+ vertex 0.0973515064 0.0192573983 -0.0381290019
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 0.021898469 0.0377079397
+ vertex 0.05054418 0.0230156612 0.0343847312
+ vertex 0.057112921 0.0175744239 0.0402963273
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 0.021898469 0.0377079397
+ vertex 0.057112921 0.0175744239 0.0402963273
+ vertex 0.0918507203 0.017598493 0.0412663892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 0.021898469 0.0377079397
+ vertex 0.0918507203 0.017598493 0.0412663892
+ vertex 0.0973515064 0.0192573983 0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 0.021898469 0.0377079397
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.0499858037 0.0242248494 0.0313238502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 0.021898469 0.0377079397
+ vertex 0.0499858037 0.0242248494 0.0313238502
+ vertex 0.05054418 0.0230156612 0.0343847312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.106539778 -0.0142910061 0.0375000015
+ vertex 0.108945198 -0.011792901 0.0375782177
+ vertex 0.087197192 -0.0179378465 0.0427427813
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.022126114 0.0379388034
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ vertex 0.106526084 -0.0142641403 -0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.022126114 0.0379388034
+ vertex 0.106526084 -0.0142641403 -0.0376710109
+ vertex 0.106539778 -0.0142910061 0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.104415461 0.0159155261 -0.03732666
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ vertex 0.0973515064 0.0192573983 -0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.104415461 0.0159155261 -0.03732666
+ vertex 0.106343694 0.0170951393 -0.0316420346
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.104415461 0.0159155261 -0.03732666
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ vertex 0.106593035 0.0114635993 -0.0383162908
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0204425566 -0.0412426963
+ vertex 0.059854243 -0.0200609211 -0.0413660444
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0204425566 -0.0412426963
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ vertex 0.106526084 -0.0142641403 -0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0204425566 -0.0412426963
+ vertex 0.106526084 -0.0142641403 -0.0376710109
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449927524 -0.0241424944 -0.00870923791
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ vertex 0.0105307335 -0.0241115689 -0.0180585217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 0.0211347025 0.0277207121
+ vertex 0.000985993189 0.0146409618 0.0166332144
+ vertex 0.000382332481 0.00733469939 0.0209617745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 0.0211347025 0.0277207121
+ vertex 0.000382332481 0.00733469939 0.0209617745
+ vertex 0.0319184139 0.0136874076 0.0349926092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 0.0211347025 0.0277207121
+ vertex 0.0319184139 0.0136874076 0.0349926092
+ vertex 0.0386839993 0.0196409728 0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 0.0211347025 0.0277207121
+ vertex 0.0386839993 0.0196409728 0.0348441415
+ vertex 0.0301822927 0.0239052977 0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.022126114 0.0379388034
+ vertex 0.0569128245 -0.0214257389 0.0395162031
+ vertex 0.0378879793 -0.0222807229 0.0342065804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.022126114 0.0379388034
+ vertex 0.0378879793 -0.0222807229 0.0342065804
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.053119909 -0.0242999997 2.50523644e-05
+ vertex 0.087197192 -0.022126114 0.0379388034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108797297 -0.000248799392 0.0377499983
+ vertex 0.105289027 0.0114629809 0.0395951495
+ vertex 0.100349553 0.012113275 0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108797297 -0.000248799392 0.0377499983
+ vertex 0.100349553 0.012113275 0.0422544107
+ vertex 0.108945198 -0.011792901 0.0375782177
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108797297 -0.000248799392 0.0377499983
+ vertex 0.108945198 -0.011792901 0.0375782177
+ vertex 0.110085137 0.0117910709 0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0998914167 0.00729999831 -0.042503804
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ vertex 0.0616687201 0.0108000021 -0.0428737625
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0171384849 -0.042926129
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ vertex 0.0998914167 0.00729999831 -0.042503804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0999649987 0.0211366285 -0.0302842781
+ vertex 0.106343694 0.0170951393 -0.0316420346
+ vertex 0.104415461 0.0159155261 -0.03732666
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0999649987 0.0211366285 -0.0302842781
+ vertex 0.104415461 0.0159155261 -0.03732666
+ vertex 0.0973515064 0.0192573983 -0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 0.0226331968 0.0320164189
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ vertex 0.0844106227 0.021898469 0.0377079397
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 0.0226331968 0.0320164189
+ vertex 0.0844106227 0.021898469 0.0377079397
+ vertex 0.0973515064 0.0192573983 0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 0.0226331968 0.0320164189
+ vertex 0.101307355 0.0211336818 0.0262018219
+ vertex 0.0929791778 0.0240329262 0.0221764054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 0.0226331968 0.0320164189
+ vertex 0.0929791778 0.0240329262 0.0221764054
+ vertex 0.0830827579 0.0240309183 0.0329208523
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0511443056 0.0141101684 -0.041027382
+ vertex 0.0410275012 0.0118555408 -0.0389420204
+ vertex 0.0325543284 0.0152562167 -0.0347678363
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0511443056 0.0141101684 -0.041027382
+ vertex 0.0325543284 0.0152562167 -0.0347678363
+ vertex 0.0386839993 0.0196409728 -0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0511443056 0.0141101684 -0.041027382
+ vertex 0.0386839993 0.0196409728 -0.0348441415
+ vertex 0.0559303612 0.0197001118 -0.0386815257
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000466723082 -0.0220151171 -0.00335950544
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ vertex 0.00449927524 -0.0241424944 -0.00870923791
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000466723082 -0.0220151171 -0.00335950544
+ vertex 0.00449927524 -0.0241424944 -0.00870923791
+ vertex 0.00325558288 -0.0242521018 0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000466723082 -0.0220151171 -0.00335950544
+ vertex -4.33680869e-19 -0.0204886571 0.0058807116
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0371800698 -0.0204614326 -0.0363381244
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ vertex 0.059854243 -0.0200609211 -0.0413660444
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0371800698 -0.0204614326 -0.0363381244
+ vertex 0.059854243 -0.0200609211 -0.0413660444
+ vertex 0.0450868383 -0.0220738277 -0.036408931
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 0.0230234805 -0.0347991399
+ vertex 0.0559303612 0.0197001118 -0.0386815257
+ vertex 0.0386839993 0.0196409728 -0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 0.0230234805 -0.0347991399
+ vertex 0.0386839993 0.0196409728 -0.0348441415
+ vertex 0.0313282795 0.0230003837 -0.0283750538
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 0.0230234805 -0.0347991399
+ vertex 0.0313282795 0.0230003837 -0.0283750538
+ vertex 0.040512275 0.0241192076 -0.0296534151
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 0.0230234805 -0.0347991399
+ vertex 0.040512275 0.0241192076 -0.0296534151
+ vertex 0.0822351947 0.0242381375 -0.0316604972
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 0.0230234805 -0.0347991399
+ vertex 0.0822351947 0.0242381375 -0.0316604972
+ vertex 0.0859468654 0.0226191785 -0.0365190059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 0.0230234805 -0.0347991399
+ vertex 0.0859468654 0.0226191785 -0.0365190059
+ vertex 0.0559303612 0.0197001118 -0.0386815257
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 0.0152562167 -0.0347678363
+ vertex 0.0410275012 0.0118555408 -0.0389420204
+ vertex 0.00108609546 0.00320781744 -0.0230950378
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 0.0152562167 -0.0347678363
+ vertex 0.00108609546 0.00320781744 -0.0230950378
+ vertex 0.000815250794 0.0111495871 -0.0192433316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 0.0152562167 -0.0347678363
+ vertex 0.000815250794 0.0111495871 -0.0192433316
+ vertex 0.0253822114 0.0197990108 -0.0283071157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 0.0152562167 -0.0347678363
+ vertex 0.0253822114 0.0197990108 -0.0283071157
+ vertex 0.0386839993 0.0196409728 -0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 0.0153009761 0.0400322676
+ vertex 0.100349553 0.012113275 0.0422544107
+ vertex 0.105289027 0.0114629809 0.0395951495
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 0.0153009761 0.0400322676
+ vertex 0.105289027 0.0114629809 0.0395951495
+ vertex 0.106516667 0.014690673 0.0362586193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 0.0153009761 0.0400322676
+ vertex 0.0973515064 0.0192573983 0.0381290019
+ vertex 0.0918507203 0.017598493 0.0412663892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 0.0153009761 0.0400322676
+ vertex 0.0918507203 0.017598493 0.0412663892
+ vertex 0.100349553 0.012113275 0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 0.023337489 0.0187711585
+ vertex 0.000972606533 0.0196658205 0.00986019056
+ vertex 0.000985993189 0.0146409618 0.0166332144
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 0.023337489 0.0187711585
+ vertex 0.000985993189 0.0146409618 0.0166332144
+ vertex 0.0262105837 0.0211347025 0.0277207121
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 0.023337489 0.0187711585
+ vertex 0.0262105837 0.0211347025 0.0277207121
+ vertex 0.0301822927 0.0239052977 0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 0.023337489 0.0187711585
+ vertex 0.0301822927 0.0239052977 0.0260417778
+ vertex 0.0119591318 0.0240044985 0.0111451717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 0.023337489 0.0187711585
+ vertex 0.0119591318 0.0240044985 0.0111451717
+ vertex 0.000972606533 0.0196658205 0.00986019056
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00550768012 -0.0242134128 0.0107838986
+ vertex 0.0113188038 -0.023762105 0.0193939283
+ vertex 0.000827543903 -0.0200854614 0.0154875098
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00550768012 -0.0242134128 0.0107838986
+ vertex 0.000827543903 -0.0200854614 0.0154875098
+ vertex 0.00325558288 -0.0242521018 0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00550768012 -0.0242134128 0.0107838986
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.0113188038 -0.023762105 0.0193939283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0378879793 -0.0222807229 0.0342065804
+ vertex 0.0367529877 -0.0196497161 0.0367338806
+ vertex 0.0187891237 -0.0216411445 0.0271195248
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0378879793 -0.0222807229 0.0342065804
+ vertex 0.0187891237 -0.0216411445 0.0271195248
+ vertex 0.0113188038 -0.023762105 0.0193939283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0378879793 -0.0222807229 0.0342065804
+ vertex 0.0113188038 -0.023762105 0.0193939283
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108607769 0.0117945615 0.0352748968
+ vertex 0.106516667 0.014690673 0.0362586193
+ vertex 0.105289027 0.0114629809 0.0395951495
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108607769 0.0117945615 0.0352748968
+ vertex 0.105289027 0.0114629809 0.0395951495
+ vertex 0.108797297 -0.000248799392 0.0377499983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108607769 0.0117945615 0.0352748968
+ vertex 0.108797297 -0.000248799392 0.0377499983
+ vertex 0.110085137 0.0117910709 0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0313282795 0.0230003837 -0.0283750538
+ vertex 0.0253822114 0.0197990108 -0.0283071157
+ vertex 0.0198960323 0.0236970317 -0.0199881103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0313282795 0.0230003837 -0.0283750538
+ vertex 0.0198960323 0.0236970317 -0.0199881103
+ vertex 0.040512275 0.0241192076 -0.0296534151
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0313282795 0.0230003837 -0.0283750538
+ vertex 0.0386839993 0.0196409728 -0.0348441415
+ vertex 0.0253822114 0.0197990108 -0.0283071157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 0.019266421 0.0338273309
+ vertex 0.0973515064 0.0192573983 0.0381290019
+ vertex 0.1019651 0.0153009761 0.0400322676
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 0.019266421 0.0338273309
+ vertex 0.1019651 0.0153009761 0.0400322676
+ vertex 0.106516667 0.014690673 0.0362586193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 0.019266421 0.0338273309
+ vertex 0.107092947 0.0170837287 0.0276683085
+ vertex 0.101307355 0.0211336818 0.0262018219
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 0.019266421 0.0338273309
+ vertex 0.101307355 0.0211336818 0.0262018219
+ vertex 0.094236359 0.0226331968 0.0320164189
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 0.019266421 0.0338273309
+ vertex 0.094236359 0.0226331968 0.0320164189
+ vertex 0.0973515064 0.0192573983 0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 -0.0193150528 0.0406607464
+ vertex 0.0629487932 -0.0172377508 0.0428446829
+ vertex 0.0470071323 -0.0164586306 0.0407023169
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 -0.0193150528 0.0406607464
+ vertex 0.0470071323 -0.0164586306 0.0407023169
+ vertex 0.0367529877 -0.0196497161 0.0367338806
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 -0.0193150528 0.0406607464
+ vertex 0.0367529877 -0.0196497161 0.0367338806
+ vertex 0.0378879793 -0.0222807229 0.0342065804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 -0.0193150528 0.0406607464
+ vertex 0.0378879793 -0.0222807229 0.0342065804
+ vertex 0.0569128245 -0.0214257389 0.0395162031
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262515005 -0.0242873672 -0.0249164384
+ vertex 0.0450868383 -0.0220738277 -0.036408931
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.00550768012 -0.0242134128 0.0107838986
+ vertex 0.00325558288 -0.0242521018 0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.00325558288 -0.0242521018 0.001551767
+ vertex 0.00449927524 -0.0241424944 -0.00870923791
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.00449927524 -0.0241424944 -0.00870923791
+ vertex 0.0105307335 -0.0241115689 -0.0180585217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.0105307335 -0.0241115689 -0.0180585217
+ vertex 0.0262515005 -0.0242873672 -0.0249164384
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.0262515005 -0.0242873672 -0.0249164384
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 -0.0242866464 0.024875341
+ vertex 0.087197192 -0.0221349504 -0.0378812216
+ vertex 0.053119909 -0.0242999997 2.50523644e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0205955189 0.0410840139
+ vertex 0.087197192 -0.0179378465 0.0427427813
+ vertex 0.0629487932 -0.0172377508 0.0428446829
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0205955189 0.0410840139
+ vertex 0.0629487932 -0.0172377508 0.0428446829
+ vertex 0.050357122 -0.0193150528 0.0406607464
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0205955189 0.0410840139
+ vertex 0.050357122 -0.0193150528 0.0406607464
+ vertex 0.0569128245 -0.0214257389 0.0395162031
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0205955189 0.0410840139
+ vertex 0.0569128245 -0.0214257389 0.0395162031
+ vertex 0.087197192 -0.022126114 0.0379388034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0205955189 0.0410840139
+ vertex 0.087197192 -0.022126114 0.0379388034
+ vertex 0.106539778 -0.0142910061 0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 -0.0205955189 0.0410840139
+ vertex 0.106539778 -0.0142910061 0.0375000015
+ vertex 0.087197192 -0.0179378465 0.0427427813
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.26137872e-05 -0.00500459271 0.0223245509
+ vertex 0.000813621096 -0.0147488276 0.0207792539
+ vertex 0.00130202749 -0.00396212796 0.0239653178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 0.0152454879 0.0397942774
+ vertex 0.057112921 0.0175744239 0.0402963273
+ vertex 0.0386839993 0.0196409728 0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 0.0152454879 0.0397942774
+ vertex 0.0386839993 0.0196409728 0.0348441415
+ vertex 0.0319184139 0.0136874076 0.0349926092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 0.0152454879 0.0397942774
+ vertex 0.0493300669 0.0108000021 0.0412307456
+ vertex 0.0630400777 0.011894213 0.0428665318
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 0.0152454879 0.0397942774
+ vertex 0.0630400777 0.011894213 0.0428665318
+ vertex 0.057112921 0.0175744239 0.0402963273
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 0.0114607271 -0.0416026823
+ vertex 0.106593035 0.0114635993 -0.0383162908
+ vertex 0.108969845 -0.00179999915 -0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 0.0114607271 -0.0416026823
+ vertex 0.108969845 -0.00179999915 -0.0376710109
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 0.0114607271 -0.0416026823
+ vertex 0.108987689 -0.0116422204 -0.0375000015
+ vertex 0.0998914167 0.00729999831 -0.042503804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 0.0114607271 -0.0416026823
+ vertex 0.0998914167 0.00729999831 -0.042503804
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 0.0114607271 -0.0416026823
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ vertex 0.104415461 0.0159155261 -0.03732666
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 0.0114607271 -0.0416026823
+ vertex 0.104415461 0.0159155261 -0.03732666
+ vertex 0.106593035 0.0114635993 -0.0383162908
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 0.0202339236 -0.0249931291
+ vertex 0.106343694 0.0170951393 -0.0316420346
+ vertex 0.0999649987 0.0211366285 -0.0302842781
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 0.0202339236 -0.0249931291
+ vertex 0.0999649987 0.0211366285 -0.0302842781
+ vertex 0.0946417376 0.0236909073 -0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 0.0202339236 -0.0249931291
+ vertex 0.0946417376 0.0236909073 -0.0228220038
+ vertex 0.101307355 0.0211336818 0.0262018219
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 0.0202339236 -0.0249931291
+ vertex 0.101307355 0.0211336818 0.0262018219
+ vertex 0.107092947 0.0170837287 0.0276683085
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 0.0202339236 -0.0249931291
+ vertex 0.107092947 0.0170837287 0.0276683085
+ vertex 0.106343694 0.0170951393 -0.0316420346
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 0.0153330769 -0.0418230109
+ vertex 0.0616687201 0.0108000021 -0.0428737625
+ vertex 0.0511443056 0.0141101684 -0.041027382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 0.0153330769 -0.0418230109
+ vertex 0.0511443056 0.0141101684 -0.041027382
+ vertex 0.0559303612 0.0197001118 -0.0386815257
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 0.0153330769 -0.0418230109
+ vertex 0.0559303612 0.0197001118 -0.0386815257
+ vertex 0.0902594849 0.0186875556 -0.0406222567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 0.0153330769 -0.0418230109
+ vertex 0.0902594849 0.0186875556 -0.0406222567
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 0.0153330769 -0.0418230109
+ vertex 0.098503001 0.0140360352 -0.0422261059
+ vertex 0.0616687201 0.0108000021 -0.0428737625
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100970119 0.0232202392 -0.0119567169
+ vertex 0.0198960323 0.0236970317 -0.0199881103
+ vertex 0.0010439317 0.0179824214 -0.0128565431
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100970119 0.0232202392 -0.0119567169
+ vertex 0.00780997705 0.0237585288 -0.0051452904
+ vertex 0.0198960323 0.0236970317 -0.0199881103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 0.0176422466 0.0106721586
+ vertex 0.000382332481 0.00733469939 0.0209617745
+ vertex 0.000985993189 0.0146409618 0.0166332144
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 0.0176422466 0.0106721586
+ vertex 0.000985993189 0.0146409618 0.0166332144
+ vertex 0.000972606533 0.0196658205 0.00986019056
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 0.0176422466 0.0106721586
+ vertex 0.000972606533 0.0196658205 0.00986019056
+ vertex 0.00100057351 0.0217247847 0.00168395217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 0.0176422466 0.0106721586
+ vertex 0.00100057351 0.0217247847 0.00168395217
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 0.0176422466 0.0106721586
+ vertex 2.26137872e-05 -0.00500459271 0.0223245509
+ vertex 0.000382332481 0.00733469939 0.0209617745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 0.0232216027 -0.031036051
+ vertex 0.0946417376 0.0236909073 -0.0228220038
+ vertex 0.0999649987 0.0211366285 -0.0302842781
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 0.0232216027 -0.031036051
+ vertex 0.0999649987 0.0211366285 -0.0302842781
+ vertex 0.0973515064 0.0192573983 -0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 0.0232216027 -0.031036051
+ vertex 0.0973515064 0.0192573983 -0.0381290019
+ vertex 0.0859468654 0.0226191785 -0.0365190059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 0.0232216027 -0.031036051
+ vertex 0.0859468654 0.0226191785 -0.0365190059
+ vertex 0.0822351947 0.0242381375 -0.0316604972
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 0.0232216027 -0.031036051
+ vertex 0.0822351947 0.0242381375 -0.0316604972
+ vertex 0.0946417376 0.0236909073 -0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108572433 0.00311817578 0.0231178533
+ vertex 0.000382332481 0.00733469939 0.0209617745
+ vertex 2.26137872e-05 -0.00500459271 0.0223245509
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108572433 0.00311817578 0.0231178533
+ vertex 2.26137872e-05 -0.00500459271 0.0223245509
+ vertex 0.00130202749 -0.00396212796 0.0239653178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108572433 0.00311817578 0.0231178533
+ vertex 0.0319184139 0.0136874076 0.0349926092
+ vertex 0.000382332481 0.00733469939 0.0209617745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 -0.0179210324 -0.0359583385
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ vertex 0.0371800698 -0.0204614326 -0.0363381244
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 -0.0179210324 -0.0359583385
+ vertex 0.0371800698 -0.0204614326 -0.0363381244
+ vertex 0.0205855183 -0.021230232 -0.0284087285
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 -0.0179210324 -0.0359583385
+ vertex 0.0205855183 -0.021230232 -0.0284087285
+ vertex 0.00109609449 -0.0130085731 -0.021813415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 -0.0179210324 -0.0359583385
+ vertex 0.00109609449 -0.0130085731 -0.021813415
+ vertex 0.000540190493 -0.00509330677 -0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000540190493 -0.00509330677 -0.0233880505
+ vertex 0.0410275012 0.0118555408 -0.0389420204
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000540190493 -0.00509330677 -0.0233880505
+ vertex 0.0439595468 -0.0175483078 -0.0398119316
+ vertex 0.0332721323 -0.0179210324 -0.0359583385
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 -0.0241615251 -0.0233735386
+ vertex 0.0205855183 -0.021230232 -0.0284087285
+ vertex 0.0371800698 -0.0204614326 -0.0363381244
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 -0.0241615251 -0.0233735386
+ vertex 0.0371800698 -0.0204614326 -0.0363381244
+ vertex 0.0450868383 -0.0220738277 -0.036408931
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 -0.0241615251 -0.0233735386
+ vertex 0.0450868383 -0.0220738277 -0.036408931
+ vertex 0.0262515005 -0.0242873672 -0.0249164384
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 -0.0241615251 -0.0233735386
+ vertex 0.0262515005 -0.0242873672 -0.0249164384
+ vertex 0.0105307335 -0.0241115689 -0.0180585217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 -0.0241615251 -0.0233735386
+ vertex 0.0105307335 -0.0241115689 -0.0180585217
+ vertex 0.0205855183 -0.021230232 -0.0284087285
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 0.0146880094 0.0309894644
+ vertex 0.110085137 0.0117910709 0.029902745
+ vertex 0.109601542 0.0127749545 -0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 0.0146880094 0.0309894644
+ vertex 0.107092947 0.0170837287 0.0276683085
+ vertex 0.101918705 0.019266421 0.0338273309
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 0.0146880094 0.0309894644
+ vertex 0.101918705 0.019266421 0.0338273309
+ vertex 0.106516667 0.014690673 0.0362586193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 0.0146880094 0.0309894644
+ vertex 0.106516667 0.014690673 0.0362586193
+ vertex 0.108607769 0.0117945615 0.0352748968
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 0.0146880094 0.0309894644
+ vertex 0.108607769 0.0117945615 0.0352748968
+ vertex 0.110085137 0.0117910709 0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 0.0108000021 0.0378460772
+ vertex 0.0319184139 0.0136874076 0.0349926092
+ vertex 0.00108572433 0.00311817578 0.0231178533
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 0.0108000021 0.0378460772
+ vertex 0.00108572433 0.00311817578 0.0231178533
+ vertex 0.00130202749 -0.00396212796 0.0239653178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 0.0108000021 0.0378460772
+ vertex 0.00130202749 -0.00396212796 0.0239653178
+ vertex 0.0367529877 -0.0196497161 0.0367338806
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 0.0108000021 0.0378460772
+ vertex 0.0367529877 -0.0196497161 0.0367338806
+ vertex 0.0470071323 -0.0164586306 0.0407023169
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 0.0108000021 0.0378460772
+ vertex 0.0470071323 -0.0164586306 0.0407023169
+ vertex 0.0493300669 0.0108000021 0.0412307456
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 0.0108000021 0.0378460772
+ vertex 0.0493300669 0.0108000021 0.0412307456
+ vertex 0.0472228453 0.0152454879 0.0397942774
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 0.0108000021 0.0378460772
+ vertex 0.0472228453 0.0152454879 0.0397942774
+ vertex 0.0319184139 0.0136874076 0.0349926092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 0.00436450867 -0.0215465762
+ vertex 0.000815250794 0.0111495871 -0.0192433316
+ vertex 0.00108609546 0.00320781744 -0.0230950378
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 0.00436450867 -0.0215465762
+ vertex 0.00108609546 0.00320781744 -0.0230950378
+ vertex 0.000540190493 -0.00509330677 -0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 0.00436450867 -0.0215465762
+ vertex 0.000540190493 -0.00509330677 -0.0233880505
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ vertex 9.77833115e-05 0.00436450867 -0.0215465762
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ vertex 0.000391842274 -0.0191479456 -0.0163868312
+ vertex -4.33680869e-19 -0.0204886571 0.0058807116
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ vertex -4.33680869e-19 -0.0204886571 0.0058807116
+ vertex 2.65021208e-05 -0.0172973722 0.0173943657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ vertex 2.65021208e-05 -0.0172973722 0.0173943657
+ vertex 2.26137872e-05 -0.00500459271 0.0223245509
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ vertex 2.26137872e-05 -0.00500459271 0.0223245509
+ vertex 2.23411407e-05 0.0176422466 0.0106721586
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 0.00436450867 -0.0215465762
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ vertex 0.000815250794 0.0111495871 -0.0192433316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0499858037 0.0242248494 0.0313238502
+ vertex 0.0301822927 0.0239052977 0.0260417778
+ vertex 0.05054418 0.0230156612 0.0343847312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0499858037 0.0242248494 0.0313238502
+ vertex 0.0119591318 0.0240044985 0.0111451717
+ vertex 0.0301822927 0.0239052977 0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 0.0215513017 -0.00422760192
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ vertex 0.00100057351 0.0217247847 0.00168395217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 0.0215513017 -0.00422760192
+ vertex 0.00100057351 0.0217247847 0.00168395217
+ vertex 0.00780997705 0.0237585288 -0.0051452904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 0.0215513017 -0.00422760192
+ vertex 0.00780997705 0.0237585288 -0.0051452904
+ vertex 0.0100970119 0.0232202392 -0.0119567169
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 0.0215513017 -0.00422760192
+ vertex 0.0100970119 0.0232202392 -0.0119567169
+ vertex 0.0010439317 0.0179824214 -0.0128565431
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 0.0215513017 -0.00422760192
+ vertex 0.0010439317 0.0179824214 -0.0128565431
+ vertex 8.5700085e-05 0.0198695455 -0.00598262344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.65021208e-05 -0.0172973722 0.0173943657
+ vertex 0.000813621096 -0.0147488276 0.0207792539
+ vertex 2.26137872e-05 -0.00500459271 0.0223245509
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.65021208e-05 -0.0172973722 0.0173943657
+ vertex -4.33680869e-19 -0.0204886571 0.0058807116
+ vertex 0.000827543903 -0.0200854614 0.0154875098
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.65021208e-05 -0.0172973722 0.0173943657
+ vertex 0.000827543903 -0.0200854614 0.0154875098
+ vertex 0.000813621096 -0.0147488276 0.0207792539
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/left_hand_six_link.STL b/assets/unitree_hand/meshes/left_hand_six_link.STL
new file mode 100644
index 0000000..31990c1
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_six_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_six_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_six_link.STL.convex.stl
new file mode 100644
index 0000000..3fc0a48
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_six_link.STL.convex.stl
@@ -0,0 +1,690 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0378707163 0.00771122705 -0.00497220876
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 0.0300000012 0.00700000022 -0.0128999986
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex 6.70552225e-10 0.00700000022 -0.0128999986
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 0.00849467609 -1.17838379e-08
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 -0.00752525544 -0.00558171095
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex 0.0561827868 0.00311235571 -0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.067726776 0.002401951 0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 0.00615968416 0.0105616581
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.049899593 0.00582374632 -0.0103603406
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex 0.0255697463 -0.00990009308 0.00399018405
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex -0.00121553731 -0.00689365435 -0.0128999986
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 -0.00971204787 -0.00558968494
+ vertex 0.0300000012 -0.00700000022 -0.0128999986
+ vertex 0.0411676802 -0.00952773262 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.0486769713 -0.00900336448 0.00344834942
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.0575625114 -0.00782644935 -0.000586750568
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 -0.00584984384 0.00439739088
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ vertex 0.0575334616 -0.00589359924 0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.0620835871 -0.00281458907 0.00817895588
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ vertex 0.067726776 0.002401951 0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 0.000459232426 0.00766683137
+ vertex 0.067726776 0.002401951 0.00608098926
+ vertex 0.0648363978 0.00285470835 0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.066054292 -0.00275459839 0.00593568338
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.064408727 -0.0049878736 -0.000419684395
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 -3.54065014e-05 0.00187589996
+ vertex 0.0686098039 0.00199394976 -6.07967399e-10
+ vertex 0.0680127069 0.000901179796 0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00536231138 -0.00449951319 -0.0128999986
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00536231138 -0.00449951319 -0.00980000105
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00274999929 -0.00476314034 0.0127999997
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex 0.0293420218 -0.00693969289 0.0127999997
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex 0.0251587834 0.00700000022 0.0127999997
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00188111258 0.0051683099 0.0127999997
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 -0.00275000022 0.0127999997
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0666762441 0.00243695313 -0.00758745195
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0680978522 0.000984676648 -0.0057562408
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.067230165 -0.00171520142 -0.00518755475
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 0.000365349086 -0.00737955468
+ vertex 0.0633781254 -0.00415326515 -0.00660281349
+ vertex 0.0606325418 -0.00187931687 -0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00550000137 5.58793602e-11 0.0127999997
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00421324559 0.00353533193 0.0127999997
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00449951505 0.00536231184 -0.0128999986
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 0.00350000034 -0.00980000105
+ vertex -0.00700000115 5.58793602e-11 -0.0128999986
+ vertex -0.00700000115 5.58793602e-11 -0.00980000105
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/left_hand_three_link.STL b/assets/unitree_hand/meshes/left_hand_three_link.STL
new file mode 100644
index 0000000..d574489
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_three_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_three_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_three_link.STL.convex.stl
new file mode 100644
index 0000000..dbc476c
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_three_link.STL.convex.stl
@@ -0,0 +1,514 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0493873209 -0.0195229407 0.00874405634
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0462736487 -0.0142848082 0.0128999986
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0616396926 0.000857979583 0.0128999986
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ vertex 0.0615910105 0.00453977613 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0279263519 -0.0142848082 0.0128999986
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ vertex 0.0292240847 -0.0195752457 0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ vertex -0.00239414047 -0.00657784799 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex 0.0589422211 0.00698768906 0.0128999986
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 0.00689365482 0.0128999986
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ vertex 0.0588857867 0.00703301234 -0.00925000012
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 0.00710000051 -0.00899999961
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0485116169 -0.0198519398 -0.00720310537
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0292285774 -0.0198698081 -0.00704996567
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0617876872 0.00434222026 -0.00899999961
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0492131189 -0.0182656925 -0.00899499655
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0617924035 -0.00550000044 -0.00908682402
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0617999993 -0.00550000044 0.00900000054
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 -0.00999999978 -0.00899999961
+ vertex 0.0596943982 -0.0112850871 0.00900000054
+ vertex 0.0582380779 -0.0125870351 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00549999904 -4.17232499e-10 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00536231231 0.00449951272 0.0128999986
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00536231231 0.00449951272 0.00990000088
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00536231231 -0.00449951272 0.00990000088
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00536231231 -0.00449951272 0.0128999986
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.0128999986
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00700000208 -4.17232499e-10 0.00990000088
+ vertex -0.00549999904 -4.17232499e-10 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00549999904 -4.17232499e-10 -0.0127999997
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00476314034 0.00274999952 -0.0127999997
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex -0.00275000068 0.00476313895 -0.0127999997
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex 0.0355000049 0.00536602503 -0.0127999997
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex 0.0359396972 -0.0137420204 -0.0127999997
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00275000045 -0.0127999997
+ vertex 0.0268263537 -0.0143848071 -0.0127999997
+ vertex -0.00275000068 -0.00476313988 -0.0127999997
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/left_hand_two_link.STL b/assets/unitree_hand/meshes/left_hand_two_link.STL
new file mode 100644
index 0000000..66d01a6
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_two_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_two_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_two_link.STL.convex.stl
new file mode 100644
index 0000000..230a771
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_two_link.STL.convex.stl
@@ -0,0 +1,690 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ vertex -5.58793602e-11 0.00700000115 0.0128999986
+ vertex -0.00536231184 0.00449951505 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ vertex -0.00536231184 0.00449951505 0.0128999986
+ vertex -0.00700000022 -6.70552225e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ vertex -0.00700000022 -6.70552225e-10 0.0128999986
+ vertex -0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ vertex -0.00700000022 -0.0300000012 0.0128999986
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ vertex 0.00689365435 0.00121553731 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00700000022 -0.0300000012 0.0128999986
+ vertex -0.00311235571 -0.0561827868 0.0100471107
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00990009308 -0.0255697463 -0.00399018405
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ vertex 0.00476314034 0.00274999929 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00990009308 -0.0255697463 -0.00399018405
+ vertex 0.00476314034 0.00274999929 -0.0127999997
+ vertex 0.00689365435 0.00121553731 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231184 0.00449951505 0.0128999986
+ vertex -0.0051683099 0.00188111258 -0.0127999997
+ vertex -0.00700000022 -6.70552225e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 0.00536231138 0.00980000105
+ vertex 0.00689365435 0.00121553731 0.0128999986
+ vertex 0.00476314034 0.00274999929 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00700000022 -0.0251587834 -0.0127999997
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ vertex -0.00285470835 -0.0648363978 -0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00700000022 -0.0251587834 -0.0127999997
+ vertex -0.00285470835 -0.0648363978 -0.0083658481
+ vertex -0.00615968416 -0.0472379029 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ vertex 0.00689365435 0.00121553731 0.0128999986
+ vertex 0.00449951319 0.00536231138 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 -0.049899593 0.0103603406
+ vertex -0.00243695313 -0.0666762441 0.00758745195
+ vertex -0.00311235571 -0.0561827868 0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 -0.049899593 0.0103603406
+ vertex -0.00311235571 -0.0561827868 0.0100471107
+ vertex -0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 -0.049899593 0.0103603406
+ vertex -0.00700000022 -0.0300000012 0.0128999986
+ vertex -0.00771122705 -0.0378707163 0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 -0.049899593 0.0103603406
+ vertex -0.00771122705 -0.0378707163 0.00497220876
+ vertex -0.00615968416 -0.0472379029 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 -0.0218338352 1.17838379e-08
+ vertex -0.00700000022 -0.0251587834 -0.0127999997
+ vertex -0.00615968416 -0.0472379029 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 -0.0218338352 1.17838379e-08
+ vertex -0.00615968416 -0.0472379029 -0.0105616581
+ vertex -0.00771122705 -0.0378707163 0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 -0.0218338352 1.17838379e-08
+ vertex -0.00771122705 -0.0378707163 0.00497220876
+ vertex -0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 -0.0218338352 1.17838379e-08
+ vertex -0.00700000022 -0.0300000012 0.0128999986
+ vertex -0.00700000022 -6.70552225e-10 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 -0.0218338352 1.17838379e-08
+ vertex -0.00700000022 -6.70552225e-10 0.0128999986
+ vertex -0.0051683099 0.00188111258 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 -0.0218338352 1.17838379e-08
+ vertex -0.0051683099 0.00188111258 -0.0127999997
+ vertex -0.00700000022 -0.0251587834 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 -0.0486769713 -0.00344834942
+ vertex 0.00990009308 -0.0255697463 -0.00399018405
+ vertex 0.00952773262 -0.0411676802 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 -0.0486769713 -0.00344834942
+ vertex 0.00952773262 -0.0411676802 0.00370552461
+ vertex 0.00782644935 -0.0575625114 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 -0.0486769713 -0.00344834942
+ vertex 0.00589359924 -0.0575334616 -0.00724274013
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 -0.0486769713 -0.00344834942
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ vertex 0.00990009308 -0.0255697463 -0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 -0.0545902252 0.00558171095
+ vertex 0.00415326515 -0.0633781254 0.00660281349
+ vertex 0.00782644935 -0.0575625114 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 -0.0545902252 0.00558171095
+ vertex 0.00782644935 -0.0575625114 0.000586750568
+ vertex 0.00952773262 -0.0411676802 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 -0.0545902252 0.00558171095
+ vertex 0.00952773262 -0.0411676802 0.00370552461
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 -0.0545902252 0.00558171095
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ vertex 0.00415326515 -0.0633781254 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0049878736 -0.064408727 0.000419684395
+ vertex 0.00782644935 -0.0575625114 0.000586750568
+ vertex 0.00415326515 -0.0633781254 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0049878736 -0.064408727 0.000419684395
+ vertex 0.00415326515 -0.0633781254 0.00660281349
+ vertex 0.00171520142 -0.067230165 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00281458907 -0.0620835871 -0.00817895588
+ vertex 0.00589359924 -0.0575334616 -0.00724274013
+ vertex 0.00275459839 -0.066054292 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00281458907 -0.0620835871 -0.00817895588
+ vertex -0.00285470835 -0.0648363978 -0.0083658481
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00281458907 -0.0620835871 -0.00817895588
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ vertex 0.00589359924 -0.0575334616 -0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00311235571 -0.0561827868 0.0100471107
+ vertex -0.00243695313 -0.0666762441 0.00758745195
+ vertex -0.000365349086 -0.0668851808 0.00737955468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00311235571 -0.0561827868 0.0100471107
+ vertex -0.000365349086 -0.0668851808 0.00737955468
+ vertex 0.00187931687 -0.0606325418 0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00187931687 -0.0606325418 0.00884774793
+ vertex 0.00415326515 -0.0633781254 0.00660281349
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00187931687 -0.0606325418 0.00884774793
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ vertex -0.00311235571 -0.0561827868 0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.002401951 -0.067726776 -0.00608098926
+ vertex -0.000901179796 -0.0680127069 -0.00600992516
+ vertex -0.00199394976 -0.0686098039 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.002401951 -0.067726776 -0.00608098926
+ vertex -0.00199394976 -0.0686098039 6.07967399e-10
+ vertex -0.00243695313 -0.0666762441 0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615968416 -0.0472379029 -0.0105616581
+ vertex -0.00285470835 -0.0648363978 -0.0083658481
+ vertex -0.002401951 -0.067726776 -0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615968416 -0.0472379029 -0.0105616581
+ vertex -0.002401951 -0.067726776 -0.00608098926
+ vertex -0.00243695313 -0.0666762441 0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615968416 -0.0472379029 -0.0105616581
+ vertex -0.00243695313 -0.0666762441 0.00758745195
+ vertex -0.00582374632 -0.049899593 0.0103603406
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00353533193 0.00421324559 -0.0127999997
+ vertex -0.0051683099 0.00188111258 -0.0127999997
+ vertex -0.00536231184 0.00449951505 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 -0.0255622845 0.00558968494
+ vertex 0.00952773262 -0.0411676802 0.00370552461
+ vertex 0.00990009308 -0.0255697463 -0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 -0.0255622845 0.00558968494
+ vertex 0.00990009308 -0.0255697463 -0.00399018405
+ vertex 0.00689365435 0.00121553731 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 -0.0255622845 0.00558968494
+ vertex 0.00689365435 0.00121553731 0.0128999986
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 -0.0255622845 0.00558968494
+ vertex 0.00700000022 -0.0300000012 0.0128999986
+ vertex 0.00952773262 -0.0411676802 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 -0.0619539768 -0.00439739088
+ vertex 0.00589359924 -0.0575334616 -0.00724274013
+ vertex 0.00900336448 -0.0486769713 -0.00344834942
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 -0.0619539768 -0.00439739088
+ vertex 0.00900336448 -0.0486769713 -0.00344834942
+ vertex 0.00782644935 -0.0575625114 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 -0.0619539768 -0.00439739088
+ vertex 0.00782644935 -0.0575625114 0.000586750568
+ vertex 0.0049878736 -0.064408727 0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 -0.0619539768 -0.00439739088
+ vertex 0.0049878736 -0.064408727 0.000419684395
+ vertex 0.00275459839 -0.066054292 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 -0.0619539768 -0.00439739088
+ vertex 0.00275459839 -0.066054292 -0.00593568338
+ vertex 0.00589359924 -0.0575334616 -0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000984676648 -0.0680978522 0.0057562408
+ vertex -0.00243695313 -0.0666762441 0.00758745195
+ vertex -0.00199394976 -0.0686098039 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 -0.0664913431 -0.00766683137
+ vertex -0.00285470835 -0.0648363978 -0.0083658481
+ vertex 0.00281458907 -0.0620835871 -0.00817895588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 -0.0664913431 -0.00766683137
+ vertex 0.00281458907 -0.0620835871 -0.00817895588
+ vertex 0.00275459839 -0.066054292 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 -0.0664913431 -0.00766683137
+ vertex 0.00275459839 -0.066054292 -0.00593568338
+ vertex -0.000901179796 -0.0680127069 -0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 -0.0664913431 -0.00766683137
+ vertex -0.000901179796 -0.0680127069 -0.00600992516
+ vertex -0.002401951 -0.067726776 -0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 -0.0664913431 -0.00766683137
+ vertex -0.002401951 -0.067726776 -0.00608098926
+ vertex -0.00285470835 -0.0648363978 -0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 -0.0685341135 -0.00187589996
+ vertex -0.000901179796 -0.0680127069 -0.00600992516
+ vertex 0.00275459839 -0.066054292 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 -0.0685341135 -0.00187589996
+ vertex 0.00275459839 -0.066054292 -0.00593568338
+ vertex 0.0049878736 -0.064408727 0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 -0.0685341135 -0.00187589996
+ vertex 0.0049878736 -0.064408727 0.000419684395
+ vertex 0.00171520142 -0.067230165 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 -0.0685341135 -0.00187589996
+ vertex 0.00171520142 -0.067230165 0.00518755475
+ vertex -0.000984676648 -0.0680978522 0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 -0.0685341135 -0.00187589996
+ vertex -0.000984676648 -0.0680978522 0.0057562408
+ vertex -0.00199394976 -0.0686098039 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 -0.0685341135 -0.00187589996
+ vertex -0.00199394976 -0.0686098039 6.07967399e-10
+ vertex -0.000901179796 -0.0680127069 -0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex -5.58793602e-11 0.00550000137 -0.0127999997
+ vertex -5.58793602e-11 0.00700000115 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex -5.58793602e-11 0.00700000115 0.00980000105
+ vertex -5.58793602e-11 0.00700000115 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex -5.58793602e-11 0.00700000115 0.0128999986
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex 0.00449951319 0.00536231138 0.0128999986
+ vertex 0.00449951319 0.00536231138 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex 0.00449951319 0.00536231138 0.00980000105
+ vertex 0.00476314034 0.00274999929 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex 0.00476314034 0.00274999929 -0.0127999997
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex 0.00693969289 -0.0293420218 -0.0127999997
+ vertex -0.00700000022 -0.0251587834 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex -0.00700000022 -0.0251587834 -0.0127999997
+ vertex -0.0051683099 0.00188111258 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex -0.0051683099 0.00188111258 -0.0127999997
+ vertex -0.00353533193 0.00421324559 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 0.00476313895 -0.0127999997
+ vertex -0.00353533193 0.00421324559 -0.0127999997
+ vertex -5.58793602e-11 0.00550000137 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 -0.0668851808 0.00737955468
+ vertex -0.00243695313 -0.0666762441 0.00758745195
+ vertex -0.000984676648 -0.0680978522 0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 -0.0668851808 0.00737955468
+ vertex -0.000984676648 -0.0680978522 0.0057562408
+ vertex 0.00171520142 -0.067230165 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 -0.0668851808 0.00737955468
+ vertex 0.00171520142 -0.067230165 0.00518755475
+ vertex 0.00415326515 -0.0633781254 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 -0.0668851808 0.00737955468
+ vertex 0.00415326515 -0.0633781254 0.00660281349
+ vertex 0.00187931687 -0.0606325418 0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 0.00606217748 0.00980000105
+ vertex -5.58793602e-11 0.00700000115 0.00980000105
+ vertex -5.58793602e-11 0.00550000137 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 0.00606217748 0.00980000105
+ vertex -5.58793602e-11 0.00550000137 -0.0127999997
+ vertex -0.00353533193 0.00421324559 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 0.00606217748 0.00980000105
+ vertex -0.00353533193 0.00421324559 -0.0127999997
+ vertex -0.00536231184 0.00449951505 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 0.00606217748 0.00980000105
+ vertex -0.00536231184 0.00449951505 0.0128999986
+ vertex -5.58793602e-11 0.00700000115 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 0.00606217748 0.00980000105
+ vertex -5.58793602e-11 0.00700000115 0.0128999986
+ vertex -5.58793602e-11 0.00700000115 0.00980000105
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/left_hand_zero_link.STL b/assets/unitree_hand/meshes/left_hand_zero_link.STL
new file mode 100644
index 0000000..4e03353
Binary files /dev/null and b/assets/unitree_hand/meshes/left_hand_zero_link.STL differ
diff --git a/assets/unitree_hand/meshes/left_hand_zero_link.STL.convex.stl b/assets/unitree_hand/meshes/left_hand_zero_link.STL.convex.stl
new file mode 100644
index 0000000..5b18758
--- /dev/null
+++ b/assets/unitree_hand/meshes/left_hand_zero_link.STL.convex.stl
@@ -0,0 +1,594 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.00180805009 0.00119999959 -0.0148906345
+ vertex -0.0035897349 0.00119999959 -0.0145641286
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -0.0035897349 0.00119999959 -0.0145641286
+ vertex -0.00852097105 0.00119999959 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -0.00852097105 0.00119999959 -0.012344759
+ vertex -0.0132818408 0.00119999959 -0.00697084796
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -0.0132818408 0.00119999959 -0.00697084796
+ vertex -0.0148906335 0.00119999959 -0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -0.0148906335 0.00119999959 -0.0018080502
+ vertex -0.0145641277 0.00119999959 0.00358973537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -0.0145641277 0.00119999959 0.00358973537
+ vertex -0.0112276617 0.00119999959 0.00994683988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -0.0112276617 0.00119999959 0.00994683988
+ vertex -0.00531907333 0.00119999959 0.0140252449
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -0.00531907333 0.00119999959 0.0140252449
+ vertex -5.58793567e-11 0.00119999959 0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex -5.58793567e-11 0.00119999959 0.0149999997
+ vertex 0.00531907333 0.00119999959 0.0140252449
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.00531907333 0.00119999959 0.0140252449
+ vertex 0.00994683988 0.00119999959 0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.00994683988 0.00119999959 0.0112276617
+ vertex 0.0132818399 0.00119999959 0.00697084842
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.0132818399 0.00119999959 0.00697084842
+ vertex 0.0149999997 0.00119999959 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.0149999997 0.00119999959 5.21540693e-11
+ vertex 0.0140252439 0.00119999959 -0.0053190738
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.0140252439 0.00119999959 -0.0053190738
+ vertex 0.0112276608 0.00119999959 -0.00994684082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00775584811 -0.0333846211 -0.00917101093
+ vertex 0.00775584811 -0.0333846211 0.00917101093
+ vertex -0.00249999994 -0.0336000025 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00775584811 -0.0333846211 -0.00917101093
+ vertex -0.00249999994 -0.0336000025 0.00900000054
+ vertex -0.0043192273 -0.033158794 -0.00943301339
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ vertex 0.00775584811 -0.0333846211 -0.00917101093
+ vertex -0.0043192273 -0.033158794 -0.00943301339
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00852097105 -0.0242999997 0.012344759
+ vertex -0.00916589517 -0.0306019988 0.00917101093
+ vertex -0.00616062991 -0.0328219086 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00852097105 -0.0242999997 0.012344759
+ vertex -0.00616062991 -0.0328219086 0.00900000054
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ vertex -0.00249999994 -0.0336000025 0.00900000054
+ vertex 0.00775584811 -0.0333846211 0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ vertex 0.00775584811 -0.0333846211 0.00917101093
+ vertex 0.00993980374 -0.0309586544 0.00932139438
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ vertex 0.00993980374 -0.0309586544 0.00932139438
+ vertex 0.00852097105 -0.0242999997 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00975675788 -0.0298723429 -0.00917101093
+ vertex -0.00994683988 -0.0242999997 -0.0112276617
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00975675788 -0.0298723429 -0.00917101093
+ vertex -0.00916589517 -0.0306019988 0.00917101093
+ vertex -0.0148906335 -0.0242999997 0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 -0.0242999997 0.00697084842
+ vertex 0.00994683988 0.00119999959 0.0112276617
+ vertex 0.00852097105 -0.0242999997 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140252439 -0.0242999997 -0.0053190738
+ vertex -0.00994683988 -0.0242999997 -0.0112276617
+ vertex -0.00975675788 -0.0298723429 -0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140252439 -0.0242999997 -0.0053190738
+ vertex -0.00975675788 -0.0298723429 -0.00917101093
+ vertex -0.0148906335 -0.0242999997 0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140252439 -0.0242999997 -0.0053190738
+ vertex -0.0148906335 -0.0242999997 0.0018080502
+ vertex -0.0148906335 0.00119999959 -0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 -0.0242999997 -0.00697084796
+ vertex 0.00852097105 -0.0242999997 -0.012344759
+ vertex 0.0112276608 0.00119999959 -0.00994684082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0145641277 0.00119999959 0.00358973537
+ vertex -0.0148906335 0.00119999959 -0.0018080502
+ vertex -0.0148906335 -0.0242999997 0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.0242999997 0.00697084842
+ vertex -0.00852097105 -0.0242999997 0.012344759
+ vertex -0.0112276617 0.00119999959 0.00994683988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.0242999997 0.00697084842
+ vertex -0.0112276617 0.00119999959 0.00994683988
+ vertex -0.0145641277 0.00119999959 0.00358973537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.0242999997 0.00697084842
+ vertex -0.0145641277 0.00119999959 0.00358973537
+ vertex -0.0148906335 -0.0242999997 0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.0242999997 0.00697084842
+ vertex -0.0148906335 -0.0242999997 0.0018080502
+ vertex -0.00916589517 -0.0306019988 0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.0242999997 0.00697084842
+ vertex -0.00916589517 -0.0306019988 0.00917101093
+ vertex -0.00852097105 -0.0242999997 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00531907333 0.00119999959 0.0140252449
+ vertex -0.0112276617 0.00119999959 0.00994683988
+ vertex -0.00852097105 -0.0242999997 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00531907333 0.00119999959 0.0140252449
+ vertex -0.00852097105 -0.0242999997 0.012344759
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00531907333 0.00119999959 0.0140252449
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ vertex -5.58793567e-11 0.00119999959 0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.00119999959 -0.00697084796
+ vertex -0.00852097105 0.00119999959 -0.012344759
+ vertex -0.00994683988 -0.0242999997 -0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.00119999959 -0.00697084796
+ vertex -0.00994683988 -0.0242999997 -0.0112276617
+ vertex -0.0140252439 -0.0242999997 -0.0053190738
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.00119999959 -0.00697084796
+ vertex -0.0140252439 -0.0242999997 -0.0053190738
+ vertex -0.0148906335 0.00119999959 -0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 0.00119999959 0.00697084842
+ vertex 0.00994683988 0.00119999959 0.0112276617
+ vertex 0.0132818399 -0.0242999997 0.00697084842
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 0.00119999959 0.00697084842
+ vertex 0.0132818399 -0.0242999997 0.00697084842
+ vertex 0.0149999997 -0.0242999997 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 0.00119999959 0.00697084842
+ vertex 0.0149999997 -0.0242999997 5.21540693e-11
+ vertex 0.0149999997 0.00119999959 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 -0.0309586544 -0.00932139438
+ vertex 0.00852097105 -0.0242999997 -0.012344759
+ vertex 0.0132818399 -0.0242999997 -0.00697084796
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 -0.0309586544 -0.00932139438
+ vertex 0.0132818399 -0.0242999997 -0.00697084796
+ vertex 0.0149999997 -0.0242999997 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 -0.0309586544 0.00932139438
+ vertex 0.00775584811 -0.0333846211 0.00917101093
+ vertex 0.00775584811 -0.0333846211 -0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 -0.0309586544 0.00932139438
+ vertex 0.00775584811 -0.0333846211 -0.00917101093
+ vertex 0.00993980374 -0.0309586544 -0.00932139438
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 -0.0309586544 0.00932139438
+ vertex 0.00993980374 -0.0309586544 -0.00932139438
+ vertex 0.0149999997 -0.0242999997 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 -0.0309586544 0.00932139438
+ vertex 0.0149999997 -0.0242999997 5.21540693e-11
+ vertex 0.0132818399 -0.0242999997 0.00697084842
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 -0.0309586544 0.00932139438
+ vertex 0.0132818399 -0.0242999997 0.00697084842
+ vertex 0.00852097105 -0.0242999997 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00531907333 0.00119999959 0.0140252449
+ vertex 0.00852097105 -0.0242999997 0.012344759
+ vertex 0.00994683988 0.00119999959 0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00531907333 0.00119999959 0.0140252449
+ vertex -5.58793567e-11 0.00119999959 0.0149999997
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00531907333 0.00119999959 0.0140252449
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ vertex 0.00852097105 -0.0242999997 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0035897349 0.00119999959 -0.0145641286
+ vertex 0.00180805009 0.00119999959 -0.0148906345
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0035897349 0.00119999959 -0.0145641286
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ vertex -0.00994683988 -0.0242999997 -0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0035897349 0.00119999959 -0.0145641286
+ vertex -0.00994683988 -0.0242999997 -0.0112276617
+ vertex -0.00852097105 0.00119999959 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 -0.0242999997 -0.0145641286
+ vertex 0.00852097105 -0.0242999997 -0.012344759
+ vertex 0.00993980374 -0.0309586544 -0.00932139438
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 -0.0242999997 -0.0145641286
+ vertex 0.00993980374 -0.0309586544 -0.00932139438
+ vertex 0.00775584811 -0.0333846211 -0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 -0.0242999997 -0.0145641286
+ vertex 0.00775584811 -0.0333846211 -0.00917101093
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 -0.0242999997 -0.0145641286
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ vertex 0.00180805009 0.00119999959 -0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0140252439 0.00119999959 -0.0053190738
+ vertex 0.0149999997 0.00119999959 5.21540693e-11
+ vertex 0.0149999997 -0.0242999997 5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0140252439 0.00119999959 -0.0053190738
+ vertex 0.0149999997 -0.0242999997 5.21540693e-11
+ vertex 0.0132818399 -0.0242999997 -0.00697084796
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0140252439 0.00119999959 -0.0053190738
+ vertex 0.0132818399 -0.0242999997 -0.00697084796
+ vertex 0.0112276608 0.00119999959 -0.00994684082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.0112276608 0.00119999959 -0.00994684082
+ vertex 0.00852097105 -0.0242999997 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.00852097105 -0.0242999997 -0.012344759
+ vertex 0.0035897349 -0.0242999997 -0.0145641286
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 0.00119999959 -0.0132818408
+ vertex 0.0035897349 -0.0242999997 -0.0145641286
+ vertex 0.00180805009 0.00119999959 -0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00616062991 -0.0328219086 0.00900000054
+ vertex -0.00249999994 -0.0336000025 0.00900000054
+ vertex -5.58793567e-11 -0.0242999997 0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00616062991 -0.0328219086 0.00900000054
+ vertex -0.0043192273 -0.033158794 -0.00943301339
+ vertex -0.00249999994 -0.0336000025 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 -0.0323942304 -0.00900000054
+ vertex -0.0043192273 -0.033158794 -0.00943301339
+ vertex -0.00616062991 -0.0328219086 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 -0.0323942304 -0.00900000054
+ vertex -0.00616062991 -0.0328219086 0.00900000054
+ vertex -0.00916589517 -0.0306019988 0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 -0.0323942304 -0.00900000054
+ vertex -0.00916589517 -0.0306019988 0.00917101093
+ vertex -0.00975675788 -0.0298723429 -0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 -0.0323942304 -0.00900000054
+ vertex -0.00975675788 -0.0298723429 -0.00917101093
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 -0.0323942304 -0.00900000054
+ vertex -0.0018080502 -0.0242999997 -0.0148906345
+ vertex -0.0043192273 -0.033158794 -0.00943301339
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_five_link.STL b/assets/unitree_hand/meshes/right_hand_five_link.STL
new file mode 100644
index 0000000..0e055a9
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_five_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_five_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_five_link.STL.convex.stl
new file mode 100644
index 0000000..2b64d5c
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_five_link.STL.convex.stl
@@ -0,0 +1,514 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00549999904 4.17232499e-10 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ vertex -0.00549999904 4.17232499e-10 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00549999904 4.17232499e-10 0.0127999997
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_four_link.STL b/assets/unitree_hand/meshes/right_hand_four_link.STL
new file mode 100644
index 0000000..dc376d8
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_four_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_four_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_four_link.STL.convex.stl
new file mode 100644
index 0000000..ccd6a8e
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_four_link.STL.convex.stl
@@ -0,0 +1,690 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.067230165 0.00171520142 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ vertex 0.064408727 0.0049878736 0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ vertex 0.064408727 0.0049878736 0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.067230165 0.00171520142 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.067230165 0.00171520142 0.00518755475
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ vertex 0.067230165 0.00171520142 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.067230165 0.00171520142 0.00518755475
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_one_link.STL b/assets/unitree_hand/meshes/right_hand_one_link.STL
new file mode 100644
index 0000000..3efb21e
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_one_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_one_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_one_link.STL.convex.stl
new file mode 100644
index 0000000..fb046bc
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_one_link.STL.convex.stl
@@ -0,0 +1,514 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex 0.00657784799 -0.00239414047 0.0128999986
+ vertex 0.0142848082 0.0279263519 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex 0.0142848082 0.0279263519 0.0128999986
+ vertex 0.0142848082 0.0462736487 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex 0.0142848082 0.0462736487 0.0128999986
+ vertex -0.000857979583 0.0616396926 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex -0.000857979583 0.0616396926 0.0128999986
+ vertex -0.00453977613 0.0615910105 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex -0.00453977613 0.0615910105 0.0128999986
+ vertex -0.00698768906 0.0589422211 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex -0.00698768906 0.0589422211 0.0128999986
+ vertex -0.00689365482 -0.00121553685 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex -0.00689365482 -0.00121553685 0.0128999986
+ vertex -0.00449951272 -0.00536231231 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex -0.00449951272 -0.00536231231 0.0128999986
+ vertex 4.17232499e-10 -0.00700000208 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0195229407 0.0493873209 0.00874405634
+ vertex 0.0195752457 0.0292240847 0.00902805198
+ vertex 0.0198698081 0.0292285774 -0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0195229407 0.0493873209 0.00874405634
+ vertex 0.0198698081 0.0292285774 -0.00704996567
+ vertex 0.0198519398 0.0485116169 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0198698081 0.0292285774 -0.00704996567
+ vertex 0.0195752457 0.0292240847 0.00902805198
+ vertex 0.00657784799 -0.00239414047 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0198698081 0.0292285774 -0.00704996567
+ vertex 0.00657784799 -0.00239414047 0.0128999986
+ vertex 0.00476313988 -0.00275000068 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0198698081 0.0292285774 -0.00704996567
+ vertex 0.00476313988 -0.00275000068 -0.0127999997
+ vertex 0.0143848071 0.0268263537 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0142848082 0.0462736487 0.0128999986
+ vertex 0.0142848082 0.0279263519 0.0128999986
+ vertex 0.0195752457 0.0292240847 0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0142848082 0.0462736487 0.0128999986
+ vertex 0.0195752457 0.0292240847 0.00902805198
+ vertex 0.0195229407 0.0493873209 0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0112850871 0.0596943982 0.00900000054
+ vertex 0.0142848082 0.0462736487 0.0128999986
+ vertex 0.0195229407 0.0493873209 0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0112850871 0.0596943982 0.00900000054
+ vertex 0.0195229407 0.0493873209 0.00874405634
+ vertex 0.0198519398 0.0485116169 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0112850871 0.0596943982 0.00900000054
+ vertex 0.0198519398 0.0485116169 -0.00720310537
+ vertex 0.0125870351 0.0582380779 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000857979583 0.0616396926 0.0128999986
+ vertex 0.0142848082 0.0462736487 0.0128999986
+ vertex 0.0112850871 0.0596943982 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000857979583 0.0616396926 0.0128999986
+ vertex 0.0112850871 0.0596943982 0.00900000054
+ vertex 0.00550000044 0.0617999993 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536602503 0.0355000049 -0.0127999997
+ vertex -0.00703301234 0.0588857867 -0.00925000012
+ vertex -0.00434222026 0.0617876872 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951272 -0.00536231231 0.00990000088
+ vertex -0.00689365482 -0.00121553685 0.0128999986
+ vertex -0.00476313895 -0.00275000068 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951272 -0.00536231231 0.0128999986
+ vertex -0.00689365482 -0.00121553685 0.0128999986
+ vertex -0.00449951272 -0.00536231231 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00453977613 0.0615910105 0.0128999986
+ vertex -0.000857979583 0.0616396926 0.0128999986
+ vertex 0.00550000044 0.0617999993 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00453977613 0.0615910105 0.0128999986
+ vertex 0.00550000044 0.0617999993 0.00900000054
+ vertex 0.00550000044 0.0617924035 -0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00453977613 0.0615910105 0.0128999986
+ vertex 0.00550000044 0.0617924035 -0.00908682402
+ vertex -0.00434222026 0.0617876872 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00434222026 0.0617876872 -0.00899999961
+ vertex -0.00703301234 0.0588857867 -0.00925000012
+ vertex -0.00698768906 0.0589422211 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00434222026 0.0617876872 -0.00899999961
+ vertex -0.00698768906 0.0589422211 0.0128999986
+ vertex -0.00453977613 0.0615910105 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.00990000088
+ vertex 0.00476313988 -0.00275000068 -0.0127999997
+ vertex 0.00657784799 -0.00239414047 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0142848082 0.0279263519 0.0128999986
+ vertex 0.00657784799 -0.00239414047 0.0128999986
+ vertex 0.0195752457 0.0292240847 0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex 0.00449951272 -0.00536231231 0.00990000088
+ vertex 0.00657784799 -0.00239414047 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00710000051 0.0280000027 -0.00899999961
+ vertex -0.00476313895 -0.00275000068 -0.0127999997
+ vertex -0.00689365482 -0.00121553685 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00689365482 -0.00121553685 0.0128999986
+ vertex -0.00698768906 0.0589422211 0.0128999986
+ vertex -0.00703301234 0.0588857867 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00689365482 -0.00121553685 0.0128999986
+ vertex -0.00703301234 0.0588857867 -0.00925000012
+ vertex -0.00710000051 0.0280000027 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00710000051 0.0280000027 -0.00899999961
+ vertex -0.00703301234 0.0588857867 -0.00925000012
+ vertex -0.00536602503 0.0355000049 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00710000051 0.0280000027 -0.00899999961
+ vertex -0.00536602503 0.0355000049 -0.0127999997
+ vertex -0.00476313895 -0.00275000068 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0182656925 0.0492131189 -0.00899499655
+ vertex 0.0125870351 0.0582380779 -0.00925000012
+ vertex 0.0198519398 0.0485116169 -0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0182656925 0.0492131189 -0.00899499655
+ vertex 0.0198519398 0.0485116169 -0.00720310537
+ vertex 0.0198698081 0.0292285774 -0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0182656925 0.0492131189 -0.00899499655
+ vertex 0.0198698081 0.0292285774 -0.00704996567
+ vertex 0.0143848071 0.0268263537 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ vertex -0.00536602503 0.0355000049 -0.0127999997
+ vertex -0.00434222026 0.0617876872 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ vertex -0.00434222026 0.0617876872 -0.00899999961
+ vertex 0.00550000044 0.0617924035 -0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ vertex 0.00550000044 0.0617924035 -0.00908682402
+ vertex 0.00999999978 0.0605942272 -0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ vertex 0.00999999978 0.0605942272 -0.00899999961
+ vertex 0.0125870351 0.0582380779 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ vertex 0.0125870351 0.0582380779 -0.00925000012
+ vertex 0.0182656925 0.0492131189 -0.00899499655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ vertex 0.0182656925 0.0492131189 -0.00899499655
+ vertex 0.0143848071 0.0268263537 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999999978 0.0605942272 -0.00899999961
+ vertex 0.00550000044 0.0617924035 -0.00908682402
+ vertex 0.00550000044 0.0617999993 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999999978 0.0605942272 -0.00899999961
+ vertex 0.00550000044 0.0617999993 0.00900000054
+ vertex 0.0112850871 0.0596943982 0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00999999978 0.0605942272 -0.00899999961
+ vertex 0.0112850871 0.0596943982 0.00900000054
+ vertex 0.0125870351 0.0582380779 -0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 -0.00476314034 -0.0127999997
+ vertex 4.17232499e-10 -0.00549999904 -0.0127999997
+ vertex 4.17232499e-10 -0.00700000208 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 -0.00476314034 -0.0127999997
+ vertex 4.17232499e-10 -0.00700000208 0.00990000088
+ vertex 4.17232499e-10 -0.00700000208 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 -0.00476314034 -0.0127999997
+ vertex 4.17232499e-10 -0.00700000208 0.0128999986
+ vertex -0.00449951272 -0.00536231231 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 -0.00476314034 -0.0127999997
+ vertex -0.00449951272 -0.00536231231 0.0128999986
+ vertex -0.00449951272 -0.00536231231 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00274999952 -0.00476314034 -0.0127999997
+ vertex -0.00449951272 -0.00536231231 0.00990000088
+ vertex -0.00476313895 -0.00275000068 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 0.00476313988 -0.00275000068 -0.0127999997
+ vertex 0.00449951272 -0.00536231231 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 0.00449951272 -0.00536231231 0.00990000088
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 0.00449951272 -0.00536231231 0.0128999986
+ vertex 4.17232499e-10 -0.00700000208 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 4.17232499e-10 -0.00700000208 0.0128999986
+ vertex 4.17232499e-10 -0.00700000208 0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 4.17232499e-10 -0.00700000208 0.00990000088
+ vertex 4.17232499e-10 -0.00549999904 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 4.17232499e-10 -0.00549999904 -0.0127999997
+ vertex -0.00274999952 -0.00476314034 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex -0.00274999952 -0.00476314034 -0.0127999997
+ vertex -0.00476313895 -0.00275000068 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex -0.00476313895 -0.00275000068 -0.0127999997
+ vertex -0.00536602503 0.0355000049 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex -0.00536602503 0.0355000049 -0.0127999997
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 0.0137420204 0.0359396972 -0.0127999997
+ vertex 0.0143848071 0.0268263537 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000045 -0.00476314034 -0.0127999997
+ vertex 0.0143848071 0.0268263537 -0.0127999997
+ vertex 0.00476313988 -0.00275000068 -0.0127999997
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_palm_link.STL b/assets/unitree_hand/meshes/right_hand_palm_link.STL
new file mode 100644
index 0000000..43e1c98
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_palm_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_palm_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_palm_link.STL.convex.stl
new file mode 100644
index 0000000..594cd29
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_palm_link.STL.convex.stl
@@ -0,0 +1,1826 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.0929791778 -0.0240329262 -0.0221764054
+ vertex 0.0946417376 -0.0236909073 0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.0946417376 -0.0236909073 0.0228220038
+ vertex 0.0822351947 -0.0242381375 0.0316604972
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.0822351947 -0.0242381375 0.0316604972
+ vertex 0.040512275 -0.0241192076 0.0296534151
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.040512275 -0.0241192076 0.0296534151
+ vertex 0.0198960323 -0.0236970317 0.0199881103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.0198960323 -0.0236970317 0.0199881103
+ vertex 0.00780997705 -0.0237585288 0.0051452904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.00780997705 -0.0237585288 0.0051452904
+ vertex 0.0119591318 -0.0240044985 -0.0111451717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.0119591318 -0.0240044985 -0.0111451717
+ vertex 0.0499858037 -0.0242248494 -0.0313238502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0179378465 -0.0427427813
+ vertex 0.108945198 0.011792901 -0.0375782177
+ vertex 0.100349553 -0.012113275 -0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00130202749 0.00396212796 -0.0239653178
+ vertex 0.000813621096 0.0147488276 -0.0207792539
+ vertex 0.0367529877 0.0196497161 -0.0367338806
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0205855183 0.021230232 0.0284087285
+ vertex 0.0105307335 0.0241115689 0.0180585217
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000827543903 0.0200854614 -0.0154875098
+ vertex -4.33680869e-19 0.0204886571 -0.0058807116
+ vertex 0.000466723082 0.0220151171 0.00335950544
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000827543903 0.0200854614 -0.0154875098
+ vertex 0.000466723082 0.0220151171 0.00335950544
+ vertex 0.00325558288 0.0242521018 -0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.059854243 0.0200609211 0.0413660444
+ vertex 0.087197192 0.0204425566 0.0412426963
+ vertex 0.087197192 0.0221349504 0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.059854243 0.0200609211 0.0413660444
+ vertex 0.087197192 0.0221349504 0.0378812216
+ vertex 0.0450868383 0.0220738277 0.036408931
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.106526084 0.0142641403 0.0376710109
+ vertex 0.087197192 0.0171384849 0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.108969845 0.00179999915 0.0376710109
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ vertex 0.110197194 -0.00729999831 0.0289999992
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.110197194 -0.00729999831 0.0289999992
+ vertex 0.110085137 -0.0117910709 -0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.110085137 -0.0117910709 -0.029902745
+ vertex 0.108945198 0.011792901 -0.0375782177
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.108945198 0.011792901 -0.0375782177
+ vertex 0.106539778 0.0142910061 -0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.106539778 0.0142910061 -0.0375000015
+ vertex 0.106526084 0.0142641403 0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ vertex 0.108969845 0.00179999915 0.0376710109
+ vertex 0.106593035 -0.0114635993 0.0383162908
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ vertex 0.110085137 -0.0117910709 -0.029902745
+ vertex 0.110197194 -0.00729999831 0.0289999992
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0386839993 -0.0196409728 -0.0348441415
+ vertex 0.057112921 -0.0175744239 -0.0402963273
+ vertex 0.05054418 -0.0230156612 -0.0343847312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0386839993 -0.0196409728 -0.0348441415
+ vertex 0.05054418 -0.0230156612 -0.0343847312
+ vertex 0.0301822927 -0.0239052977 -0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0010439317 -0.0179824214 0.0128565431
+ vertex 0.0198960323 -0.0236970317 0.0199881103
+ vertex 0.0253822114 -0.0197990108 0.0283071157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0010439317 -0.0179824214 0.0128565431
+ vertex 0.0253822114 -0.0197990108 0.0283071157
+ vertex 0.000815250794 -0.0111495871 0.0192433316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0010439317 -0.0179824214 0.0128565431
+ vertex 0.000815250794 -0.0111495871 0.0192433316
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00100057351 -0.0217247847 -0.00168395217
+ vertex 0.000972606533 -0.0196658205 -0.00986019056
+ vertex 0.0119591318 -0.0240044985 -0.0111451717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00100057351 -0.0217247847 -0.00168395217
+ vertex 0.0119591318 -0.0240044985 -0.0111451717
+ vertex 0.00780997705 -0.0237585288 0.0051452904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00109609449 0.0130085731 0.021813415
+ vertex 0.0205855183 0.021230232 0.0284087285
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00109609449 0.0130085731 0.021813415
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ vertex 0.000540190493 0.00509330677 0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ vertex 0.100349553 -0.012113275 -0.0422544107
+ vertex 0.0918507203 -0.017598493 -0.0412663892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ vertex 0.0918507203 -0.017598493 -0.0412663892
+ vertex 0.057112921 -0.0175744239 -0.0402963273
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ vertex 0.0629487932 0.0172377508 -0.0428446829
+ vertex 0.087197192 0.0179378465 -0.0427427813
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ vertex 0.087197192 0.0179378465 -0.0427427813
+ vertex 0.100349553 -0.012113275 -0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.107092947 -0.0170837287 -0.0276683085
+ vertex 0.108737834 -0.0146880094 -0.0309894644
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.107092947 -0.0170837287 -0.0276683085
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ vertex 0.106343694 -0.0170951393 0.0316420346
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0470071323 0.0164586306 -0.0407023169
+ vertex 0.0629487932 0.0172377508 -0.0428446829
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0470071323 0.0164586306 -0.0407023169
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ vertex 0.0493300669 -0.0108000021 -0.0412307456
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108609546 -0.00320781744 0.0230950378
+ vertex 0.0410275012 -0.0118555408 0.0389420204
+ vertex 0.000540190493 0.00509330677 0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000813621096 0.0147488276 -0.0207792539
+ vertex 0.000827543903 0.0200854614 -0.0154875098
+ vertex 0.0113188038 0.023762105 -0.0193939283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000813621096 0.0147488276 -0.0207792539
+ vertex 0.0113188038 0.023762105 -0.0193939283
+ vertex 0.0187891237 0.0216411445 -0.0271195248
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0187891237 0.0216411445 -0.0271195248
+ vertex 0.0367529877 0.0196497161 -0.0367338806
+ vertex 0.000813621096 0.0147488276 -0.0207792539
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0929791778 -0.0240329262 -0.0221764054
+ vertex 0.101307355 -0.0211336818 -0.0262018219
+ vertex 0.0946417376 -0.0236909073 0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.053119909 0.0242999997 -2.50523644e-05
+ vertex 0.087197192 0.0221349504 0.0378812216
+ vertex 0.087197192 0.022126114 -0.0379388034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.056487333 0.0162701067 0.042417977
+ vertex 0.0616687201 -0.0108000021 0.0428737625
+ vertex 0.087197192 0.0171384849 0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.056487333 0.0162701067 0.042417977
+ vertex 0.087197192 0.0171384849 0.042926129
+ vertex 0.059854243 0.0200609211 0.0413660444
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.056487333 0.0162701067 0.042417977
+ vertex 0.059854243 0.0200609211 0.0413660444
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ vertex 0.0410275012 -0.0118555408 0.0389420204
+ vertex 0.0511443056 -0.0141101684 0.041027382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ vertex 0.0511443056 -0.0141101684 0.041027382
+ vertex 0.0616687201 -0.0108000021 0.0428737625
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ vertex 0.0616687201 -0.0108000021 0.0428737625
+ vertex 0.056487333 0.0162701067 0.042417977
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0902594849 -0.0186875556 0.0406222567
+ vertex 0.0559303612 -0.0197001118 0.0386815257
+ vertex 0.0859468654 -0.0226191785 0.0365190059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0902594849 -0.0186875556 0.0406222567
+ vertex 0.0859468654 -0.0226191785 0.0365190059
+ vertex 0.0973515064 -0.0192573983 0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0902594849 -0.0186875556 0.0406222567
+ vertex 0.0973515064 -0.0192573983 0.0381290019
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 -0.021898469 -0.0377079397
+ vertex 0.05054418 -0.0230156612 -0.0343847312
+ vertex 0.057112921 -0.0175744239 -0.0402963273
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 -0.021898469 -0.0377079397
+ vertex 0.057112921 -0.0175744239 -0.0402963273
+ vertex 0.0918507203 -0.017598493 -0.0412663892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 -0.021898469 -0.0377079397
+ vertex 0.0918507203 -0.017598493 -0.0412663892
+ vertex 0.0973515064 -0.0192573983 -0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 -0.021898469 -0.0377079397
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.0499858037 -0.0242248494 -0.0313238502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0844106227 -0.021898469 -0.0377079397
+ vertex 0.0499858037 -0.0242248494 -0.0313238502
+ vertex 0.05054418 -0.0230156612 -0.0343847312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.106539778 0.0142910061 -0.0375000015
+ vertex 0.108945198 0.011792901 -0.0375782177
+ vertex 0.087197192 0.0179378465 -0.0427427813
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.022126114 -0.0379388034
+ vertex 0.087197192 0.0221349504 0.0378812216
+ vertex 0.106526084 0.0142641403 0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.022126114 -0.0379388034
+ vertex 0.106526084 0.0142641403 0.0376710109
+ vertex 0.106539778 0.0142910061 -0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.104415461 -0.0159155261 0.03732666
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ vertex 0.0973515064 -0.0192573983 0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.104415461 -0.0159155261 0.03732666
+ vertex 0.106343694 -0.0170951393 0.0316420346
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.104415461 -0.0159155261 0.03732666
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ vertex 0.106593035 -0.0114635993 0.0383162908
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0204425566 0.0412426963
+ vertex 0.059854243 0.0200609211 0.0413660444
+ vertex 0.087197192 0.0171384849 0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0204425566 0.0412426963
+ vertex 0.087197192 0.0171384849 0.042926129
+ vertex 0.106526084 0.0142641403 0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0204425566 0.0412426963
+ vertex 0.106526084 0.0142641403 0.0376710109
+ vertex 0.087197192 0.0221349504 0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449927524 0.0241424944 0.00870923791
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ vertex 0.0105307335 0.0241115689 0.0180585217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 -0.0211347025 -0.0277207121
+ vertex 0.000985993189 -0.0146409618 -0.0166332144
+ vertex 0.000382332481 -0.00733469939 -0.0209617745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 -0.0211347025 -0.0277207121
+ vertex 0.000382332481 -0.00733469939 -0.0209617745
+ vertex 0.0319184139 -0.0136874076 -0.0349926092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 -0.0211347025 -0.0277207121
+ vertex 0.0319184139 -0.0136874076 -0.0349926092
+ vertex 0.0386839993 -0.0196409728 -0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262105837 -0.0211347025 -0.0277207121
+ vertex 0.0386839993 -0.0196409728 -0.0348441415
+ vertex 0.0301822927 -0.0239052977 -0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.022126114 -0.0379388034
+ vertex 0.0569128245 0.0214257389 -0.0395162031
+ vertex 0.0378879793 0.0222807229 -0.0342065804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.022126114 -0.0379388034
+ vertex 0.0378879793 0.0222807229 -0.0342065804
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.053119909 0.0242999997 -2.50523644e-05
+ vertex 0.087197192 0.022126114 -0.0379388034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108797297 0.000248799392 -0.0377499983
+ vertex 0.105289027 -0.0114629809 -0.0395951495
+ vertex 0.100349553 -0.012113275 -0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108797297 0.000248799392 -0.0377499983
+ vertex 0.100349553 -0.012113275 -0.0422544107
+ vertex 0.108945198 0.011792901 -0.0375782177
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108797297 0.000248799392 -0.0377499983
+ vertex 0.108945198 0.011792901 -0.0375782177
+ vertex 0.110085137 -0.0117910709 -0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0998914167 -0.00729999831 0.042503804
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.087197192 0.0171384849 0.042926129
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0171384849 0.042926129
+ vertex 0.0616687201 -0.0108000021 0.0428737625
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0171384849 0.042926129
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ vertex 0.0998914167 -0.00729999831 0.042503804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0999649987 -0.0211366285 0.0302842781
+ vertex 0.106343694 -0.0170951393 0.0316420346
+ vertex 0.104415461 -0.0159155261 0.03732666
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0999649987 -0.0211366285 0.0302842781
+ vertex 0.104415461 -0.0159155261 0.03732666
+ vertex 0.0973515064 -0.0192573983 0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 -0.0226331968 -0.0320164189
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ vertex 0.0844106227 -0.021898469 -0.0377079397
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 -0.0226331968 -0.0320164189
+ vertex 0.0844106227 -0.021898469 -0.0377079397
+ vertex 0.0973515064 -0.0192573983 -0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 -0.0226331968 -0.0320164189
+ vertex 0.101307355 -0.0211336818 -0.0262018219
+ vertex 0.0929791778 -0.0240329262 -0.0221764054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.094236359 -0.0226331968 -0.0320164189
+ vertex 0.0929791778 -0.0240329262 -0.0221764054
+ vertex 0.0830827579 -0.0240309183 -0.0329208523
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0511443056 -0.0141101684 0.041027382
+ vertex 0.0410275012 -0.0118555408 0.0389420204
+ vertex 0.0325543284 -0.0152562167 0.0347678363
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0511443056 -0.0141101684 0.041027382
+ vertex 0.0325543284 -0.0152562167 0.0347678363
+ vertex 0.0386839993 -0.0196409728 0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0511443056 -0.0141101684 0.041027382
+ vertex 0.0386839993 -0.0196409728 0.0348441415
+ vertex 0.0559303612 -0.0197001118 0.0386815257
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000466723082 0.0220151171 0.00335950544
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ vertex 0.00449927524 0.0241424944 0.00870923791
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000466723082 0.0220151171 0.00335950544
+ vertex 0.00449927524 0.0241424944 0.00870923791
+ vertex 0.00325558288 0.0242521018 -0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000466723082 0.0220151171 0.00335950544
+ vertex -4.33680869e-19 0.0204886571 -0.0058807116
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0371800698 0.0204614326 0.0363381244
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ vertex 0.059854243 0.0200609211 0.0413660444
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0371800698 0.0204614326 0.0363381244
+ vertex 0.059854243 0.0200609211 0.0413660444
+ vertex 0.0450868383 0.0220738277 0.036408931
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 -0.0230234805 0.0347991399
+ vertex 0.0559303612 -0.0197001118 0.0386815257
+ vertex 0.0386839993 -0.0196409728 0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 -0.0230234805 0.0347991399
+ vertex 0.0386839993 -0.0196409728 0.0348441415
+ vertex 0.0313282795 -0.0230003837 0.0283750538
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 -0.0230234805 0.0347991399
+ vertex 0.0313282795 -0.0230003837 0.0283750538
+ vertex 0.040512275 -0.0241192076 0.0296534151
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 -0.0230234805 0.0347991399
+ vertex 0.040512275 -0.0241192076 0.0296534151
+ vertex 0.0822351947 -0.0242381375 0.0316604972
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 -0.0230234805 0.0347991399
+ vertex 0.0822351947 -0.0242381375 0.0316604972
+ vertex 0.0859468654 -0.0226191785 0.0365190059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0538015515 -0.0230234805 0.0347991399
+ vertex 0.0859468654 -0.0226191785 0.0365190059
+ vertex 0.0559303612 -0.0197001118 0.0386815257
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 -0.0152562167 0.0347678363
+ vertex 0.0410275012 -0.0118555408 0.0389420204
+ vertex 0.00108609546 -0.00320781744 0.0230950378
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 -0.0152562167 0.0347678363
+ vertex 0.00108609546 -0.00320781744 0.0230950378
+ vertex 0.000815250794 -0.0111495871 0.0192433316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 -0.0152562167 0.0347678363
+ vertex 0.000815250794 -0.0111495871 0.0192433316
+ vertex 0.0253822114 -0.0197990108 0.0283071157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0325543284 -0.0152562167 0.0347678363
+ vertex 0.0253822114 -0.0197990108 0.0283071157
+ vertex 0.0386839993 -0.0196409728 0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 -0.0153009761 -0.0400322676
+ vertex 0.100349553 -0.012113275 -0.0422544107
+ vertex 0.105289027 -0.0114629809 -0.0395951495
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 -0.0153009761 -0.0400322676
+ vertex 0.105289027 -0.0114629809 -0.0395951495
+ vertex 0.106516667 -0.014690673 -0.0362586193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 -0.0153009761 -0.0400322676
+ vertex 0.0973515064 -0.0192573983 -0.0381290019
+ vertex 0.0918507203 -0.017598493 -0.0412663892
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1019651 -0.0153009761 -0.0400322676
+ vertex 0.0918507203 -0.017598493 -0.0412663892
+ vertex 0.100349553 -0.012113275 -0.0422544107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 -0.023337489 -0.0187711585
+ vertex 0.000972606533 -0.0196658205 -0.00986019056
+ vertex 0.000985993189 -0.0146409618 -0.0166332144
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 -0.023337489 -0.0187711585
+ vertex 0.000985993189 -0.0146409618 -0.0166332144
+ vertex 0.0262105837 -0.0211347025 -0.0277207121
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 -0.023337489 -0.0187711585
+ vertex 0.0262105837 -0.0211347025 -0.0277207121
+ vertex 0.0301822927 -0.0239052977 -0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 -0.023337489 -0.0187711585
+ vertex 0.0301822927 -0.0239052977 -0.0260417778
+ vertex 0.0119591318 -0.0240044985 -0.0111451717
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.017371837 -0.023337489 -0.0187711585
+ vertex 0.0119591318 -0.0240044985 -0.0111451717
+ vertex 0.000972606533 -0.0196658205 -0.00986019056
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00550768012 0.0242134128 -0.0107838986
+ vertex 0.0113188038 0.023762105 -0.0193939283
+ vertex 0.000827543903 0.0200854614 -0.0154875098
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00550768012 0.0242134128 -0.0107838986
+ vertex 0.000827543903 0.0200854614 -0.0154875098
+ vertex 0.00325558288 0.0242521018 -0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00550768012 0.0242134128 -0.0107838986
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.0113188038 0.023762105 -0.0193939283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0378879793 0.0222807229 -0.0342065804
+ vertex 0.0367529877 0.0196497161 -0.0367338806
+ vertex 0.0187891237 0.0216411445 -0.0271195248
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0378879793 0.0222807229 -0.0342065804
+ vertex 0.0187891237 0.0216411445 -0.0271195248
+ vertex 0.0113188038 0.023762105 -0.0193939283
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0378879793 0.0222807229 -0.0342065804
+ vertex 0.0113188038 0.023762105 -0.0193939283
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108607769 -0.0117945615 -0.0352748968
+ vertex 0.106516667 -0.014690673 -0.0362586193
+ vertex 0.105289027 -0.0114629809 -0.0395951495
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108607769 -0.0117945615 -0.0352748968
+ vertex 0.105289027 -0.0114629809 -0.0395951495
+ vertex 0.108797297 0.000248799392 -0.0377499983
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108607769 -0.0117945615 -0.0352748968
+ vertex 0.108797297 0.000248799392 -0.0377499983
+ vertex 0.110085137 -0.0117910709 -0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0313282795 -0.0230003837 0.0283750538
+ vertex 0.0253822114 -0.0197990108 0.0283071157
+ vertex 0.0198960323 -0.0236970317 0.0199881103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0313282795 -0.0230003837 0.0283750538
+ vertex 0.0198960323 -0.0236970317 0.0199881103
+ vertex 0.040512275 -0.0241192076 0.0296534151
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0313282795 -0.0230003837 0.0283750538
+ vertex 0.0386839993 -0.0196409728 0.0348441415
+ vertex 0.0253822114 -0.0197990108 0.0283071157
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 -0.019266421 -0.0338273309
+ vertex 0.0973515064 -0.0192573983 -0.0381290019
+ vertex 0.1019651 -0.0153009761 -0.0400322676
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 -0.019266421 -0.0338273309
+ vertex 0.1019651 -0.0153009761 -0.0400322676
+ vertex 0.106516667 -0.014690673 -0.0362586193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 -0.019266421 -0.0338273309
+ vertex 0.107092947 -0.0170837287 -0.0276683085
+ vertex 0.101307355 -0.0211336818 -0.0262018219
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 -0.019266421 -0.0338273309
+ vertex 0.101307355 -0.0211336818 -0.0262018219
+ vertex 0.094236359 -0.0226331968 -0.0320164189
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.101918705 -0.019266421 -0.0338273309
+ vertex 0.094236359 -0.0226331968 -0.0320164189
+ vertex 0.0973515064 -0.0192573983 -0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 0.0193150528 -0.0406607464
+ vertex 0.0629487932 0.0172377508 -0.0428446829
+ vertex 0.0470071323 0.0164586306 -0.0407023169
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 0.0193150528 -0.0406607464
+ vertex 0.0470071323 0.0164586306 -0.0407023169
+ vertex 0.0367529877 0.0196497161 -0.0367338806
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 0.0193150528 -0.0406607464
+ vertex 0.0367529877 0.0196497161 -0.0367338806
+ vertex 0.0378879793 0.0222807229 -0.0342065804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.050357122 0.0193150528 -0.0406607464
+ vertex 0.0378879793 0.0222807229 -0.0342065804
+ vertex 0.0569128245 0.0214257389 -0.0395162031
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0262515005 0.0242873672 0.0249164384
+ vertex 0.0450868383 0.0220738277 0.036408931
+ vertex 0.087197192 0.0221349504 0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.00550768012 0.0242134128 -0.0107838986
+ vertex 0.00325558288 0.0242521018 -0.001551767
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.00325558288 0.0242521018 -0.001551767
+ vertex 0.00449927524 0.0241424944 0.00870923791
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.00449927524 0.0241424944 0.00870923791
+ vertex 0.0105307335 0.0241115689 0.0180585217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.0105307335 0.0241115689 0.0180585217
+ vertex 0.0262515005 0.0242873672 0.0249164384
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.0262515005 0.0242873672 0.0249164384
+ vertex 0.087197192 0.0221349504 0.0378812216
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0257808995 0.0242866464 -0.024875341
+ vertex 0.087197192 0.0221349504 0.0378812216
+ vertex 0.053119909 0.0242999997 -2.50523644e-05
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0205955189 -0.0410840139
+ vertex 0.087197192 0.0179378465 -0.0427427813
+ vertex 0.0629487932 0.0172377508 -0.0428446829
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0205955189 -0.0410840139
+ vertex 0.0629487932 0.0172377508 -0.0428446829
+ vertex 0.050357122 0.0193150528 -0.0406607464
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0205955189 -0.0410840139
+ vertex 0.050357122 0.0193150528 -0.0406607464
+ vertex 0.0569128245 0.0214257389 -0.0395162031
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0205955189 -0.0410840139
+ vertex 0.0569128245 0.0214257389 -0.0395162031
+ vertex 0.087197192 0.022126114 -0.0379388034
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0205955189 -0.0410840139
+ vertex 0.087197192 0.022126114 -0.0379388034
+ vertex 0.106539778 0.0142910061 -0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.087197192 0.0205955189 -0.0410840139
+ vertex 0.106539778 0.0142910061 -0.0375000015
+ vertex 0.087197192 0.0179378465 -0.0427427813
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.26137872e-05 0.00500459271 -0.0223245509
+ vertex 0.000813621096 0.0147488276 -0.0207792539
+ vertex 0.00130202749 0.00396212796 -0.0239653178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 -0.0152454879 -0.0397942774
+ vertex 0.057112921 -0.0175744239 -0.0402963273
+ vertex 0.0386839993 -0.0196409728 -0.0348441415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 -0.0152454879 -0.0397942774
+ vertex 0.0386839993 -0.0196409728 -0.0348441415
+ vertex 0.0319184139 -0.0136874076 -0.0349926092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 -0.0152454879 -0.0397942774
+ vertex 0.0493300669 -0.0108000021 -0.0412307456
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472228453 -0.0152454879 -0.0397942774
+ vertex 0.0630400777 -0.011894213 -0.0428665318
+ vertex 0.057112921 -0.0175744239 -0.0402963273
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 -0.0114607271 0.0416026823
+ vertex 0.106593035 -0.0114635993 0.0383162908
+ vertex 0.108969845 0.00179999915 0.0376710109
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 -0.0114607271 0.0416026823
+ vertex 0.108969845 0.00179999915 0.0376710109
+ vertex 0.108987689 0.0116422204 0.0375000015
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 -0.0114607271 0.0416026823
+ vertex 0.108987689 0.0116422204 0.0375000015
+ vertex 0.0998914167 -0.00729999831 0.042503804
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 -0.0114607271 0.0416026823
+ vertex 0.0998914167 -0.00729999831 0.042503804
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 -0.0114607271 0.0416026823
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ vertex 0.104415461 -0.0159155261 0.03732666
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.102219269 -0.0114607271 0.0416026823
+ vertex 0.104415461 -0.0159155261 0.03732666
+ vertex 0.106593035 -0.0114635993 0.0383162908
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 -0.0202339236 0.0249931291
+ vertex 0.106343694 -0.0170951393 0.0316420346
+ vertex 0.0999649987 -0.0211366285 0.0302842781
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 -0.0202339236 0.0249931291
+ vertex 0.0999649987 -0.0211366285 0.0302842781
+ vertex 0.0946417376 -0.0236909073 0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 -0.0202339236 0.0249931291
+ vertex 0.0946417376 -0.0236909073 0.0228220038
+ vertex 0.101307355 -0.0211336818 -0.0262018219
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 -0.0202339236 0.0249931291
+ vertex 0.101307355 -0.0211336818 -0.0262018219
+ vertex 0.107092947 -0.0170837287 -0.0276683085
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.1030735 -0.0202339236 0.0249931291
+ vertex 0.107092947 -0.0170837287 -0.0276683085
+ vertex 0.106343694 -0.0170951393 0.0316420346
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 -0.0153330769 0.0418230109
+ vertex 0.0616687201 -0.0108000021 0.0428737625
+ vertex 0.0511443056 -0.0141101684 0.041027382
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 -0.0153330769 0.0418230109
+ vertex 0.0511443056 -0.0141101684 0.041027382
+ vertex 0.0559303612 -0.0197001118 0.0386815257
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 -0.0153330769 0.0418230109
+ vertex 0.0559303612 -0.0197001118 0.0386815257
+ vertex 0.0902594849 -0.0186875556 0.0406222567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 -0.0153330769 0.0418230109
+ vertex 0.0902594849 -0.0186875556 0.0406222567
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619780906 -0.0153330769 0.0418230109
+ vertex 0.098503001 -0.0140360352 0.0422261059
+ vertex 0.0616687201 -0.0108000021 0.0428737625
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100970119 -0.0232202392 0.0119567169
+ vertex 0.0198960323 -0.0236970317 0.0199881103
+ vertex 0.0010439317 -0.0179824214 0.0128565431
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0100970119 -0.0232202392 0.0119567169
+ vertex 0.00780997705 -0.0237585288 0.0051452904
+ vertex 0.0198960323 -0.0236970317 0.0199881103
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 -0.0176422466 -0.0106721586
+ vertex 0.000382332481 -0.00733469939 -0.0209617745
+ vertex 0.000985993189 -0.0146409618 -0.0166332144
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 -0.0176422466 -0.0106721586
+ vertex 0.000985993189 -0.0146409618 -0.0166332144
+ vertex 0.000972606533 -0.0196658205 -0.00986019056
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 -0.0176422466 -0.0106721586
+ vertex 0.000972606533 -0.0196658205 -0.00986019056
+ vertex 0.00100057351 -0.0217247847 -0.00168395217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 -0.0176422466 -0.0106721586
+ vertex 0.00100057351 -0.0217247847 -0.00168395217
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.23411407e-05 -0.0176422466 -0.0106721586
+ vertex 2.26137872e-05 0.00500459271 -0.0223245509
+ vertex 0.000382332481 -0.00733469939 -0.0209617745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 -0.0232216027 0.031036051
+ vertex 0.0946417376 -0.0236909073 0.0228220038
+ vertex 0.0999649987 -0.0211366285 0.0302842781
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 -0.0232216027 0.031036051
+ vertex 0.0999649987 -0.0211366285 0.0302842781
+ vertex 0.0973515064 -0.0192573983 0.0381290019
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 -0.0232216027 0.031036051
+ vertex 0.0973515064 -0.0192573983 0.0381290019
+ vertex 0.0859468654 -0.0226191785 0.0365190059
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 -0.0232216027 0.031036051
+ vertex 0.0859468654 -0.0226191785 0.0365190059
+ vertex 0.0822351947 -0.0242381375 0.0316604972
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0926227644 -0.0232216027 0.031036051
+ vertex 0.0822351947 -0.0242381375 0.0316604972
+ vertex 0.0946417376 -0.0236909073 0.0228220038
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108572433 -0.00311817578 -0.0231178533
+ vertex 0.000382332481 -0.00733469939 -0.0209617745
+ vertex 2.26137872e-05 0.00500459271 -0.0223245509
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108572433 -0.00311817578 -0.0231178533
+ vertex 2.26137872e-05 0.00500459271 -0.0223245509
+ vertex 0.00130202749 0.00396212796 -0.0239653178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00108572433 -0.00311817578 -0.0231178533
+ vertex 0.0319184139 -0.0136874076 -0.0349926092
+ vertex 0.000382332481 -0.00733469939 -0.0209617745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 0.0179210324 0.0359583385
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ vertex 0.0371800698 0.0204614326 0.0363381244
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 0.0179210324 0.0359583385
+ vertex 0.0371800698 0.0204614326 0.0363381244
+ vertex 0.0205855183 0.021230232 0.0284087285
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 0.0179210324 0.0359583385
+ vertex 0.0205855183 0.021230232 0.0284087285
+ vertex 0.00109609449 0.0130085731 0.021813415
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0332721323 0.0179210324 0.0359583385
+ vertex 0.00109609449 0.0130085731 0.021813415
+ vertex 0.000540190493 0.00509330677 0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000540190493 0.00509330677 0.0233880505
+ vertex 0.0410275012 -0.0118555408 0.0389420204
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.000540190493 0.00509330677 0.0233880505
+ vertex 0.0439595468 0.0175483078 0.0398119316
+ vertex 0.0332721323 0.0179210324 0.0359583385
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 0.0241615251 0.0233735386
+ vertex 0.0205855183 0.021230232 0.0284087285
+ vertex 0.0371800698 0.0204614326 0.0363381244
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 0.0241615251 0.0233735386
+ vertex 0.0371800698 0.0204614326 0.0363381244
+ vertex 0.0450868383 0.0220738277 0.036408931
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 0.0241615251 0.0233735386
+ vertex 0.0450868383 0.0220738277 0.036408931
+ vertex 0.0262515005 0.0242873672 0.0249164384
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 0.0241615251 0.0233735386
+ vertex 0.0262515005 0.0242873672 0.0249164384
+ vertex 0.0105307335 0.0241115689 0.0180585217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0186832212 0.0241615251 0.0233735386
+ vertex 0.0105307335 0.0241115689 0.0180585217
+ vertex 0.0205855183 0.021230232 0.0284087285
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 -0.0146880094 -0.0309894644
+ vertex 0.110085137 -0.0117910709 -0.029902745
+ vertex 0.109601542 -0.0127749545 0.0316092521
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 -0.0146880094 -0.0309894644
+ vertex 0.107092947 -0.0170837287 -0.0276683085
+ vertex 0.101918705 -0.019266421 -0.0338273309
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 -0.0146880094 -0.0309894644
+ vertex 0.101918705 -0.019266421 -0.0338273309
+ vertex 0.106516667 -0.014690673 -0.0362586193
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 -0.0146880094 -0.0309894644
+ vertex 0.106516667 -0.014690673 -0.0362586193
+ vertex 0.108607769 -0.0117945615 -0.0352748968
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.108737834 -0.0146880094 -0.0309894644
+ vertex 0.108607769 -0.0117945615 -0.0352748968
+ vertex 0.110085137 -0.0117910709 -0.029902745
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 -0.0108000021 -0.0378460772
+ vertex 0.0319184139 -0.0136874076 -0.0349926092
+ vertex 0.00108572433 -0.00311817578 -0.0231178533
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 -0.0108000021 -0.0378460772
+ vertex 0.00108572433 -0.00311817578 -0.0231178533
+ vertex 0.00130202749 0.00396212796 -0.0239653178
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 -0.0108000021 -0.0378460772
+ vertex 0.00130202749 0.00396212796 -0.0239653178
+ vertex 0.0367529877 0.0196497161 -0.0367338806
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 -0.0108000021 -0.0378460772
+ vertex 0.0367529877 0.0196497161 -0.0367338806
+ vertex 0.0470071323 0.0164586306 -0.0407023169
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 -0.0108000021 -0.0378460772
+ vertex 0.0470071323 0.0164586306 -0.0407023169
+ vertex 0.0493300669 -0.0108000021 -0.0412307456
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 -0.0108000021 -0.0378460772
+ vertex 0.0493300669 -0.0108000021 -0.0412307456
+ vertex 0.0472228453 -0.0152454879 -0.0397942774
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0377135612 -0.0108000021 -0.0378460772
+ vertex 0.0472228453 -0.0152454879 -0.0397942774
+ vertex 0.0319184139 -0.0136874076 -0.0349926092
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 -0.00436450867 0.0215465762
+ vertex 0.000815250794 -0.0111495871 0.0192433316
+ vertex 0.00108609546 -0.00320781744 0.0230950378
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 -0.00436450867 0.0215465762
+ vertex 0.00108609546 -0.00320781744 0.0230950378
+ vertex 0.000540190493 0.00509330677 0.0233880505
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 -0.00436450867 0.0215465762
+ vertex 0.000540190493 0.00509330677 0.0233880505
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ vertex 9.77833115e-05 -0.00436450867 0.0215465762
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ vertex 0.000391842274 0.0191479456 0.0163868312
+ vertex -4.33680869e-19 0.0204886571 -0.0058807116
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ vertex -4.33680869e-19 0.0204886571 -0.0058807116
+ vertex 2.65021208e-05 0.0172973722 -0.0173943657
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ vertex 2.65021208e-05 0.0172973722 -0.0173943657
+ vertex 2.26137872e-05 0.00500459271 -0.0223245509
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ vertex 2.26137872e-05 0.00500459271 -0.0223245509
+ vertex 2.23411407e-05 -0.0176422466 -0.0106721586
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 9.77833115e-05 -0.00436450867 0.0215465762
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ vertex 0.000815250794 -0.0111495871 0.0192433316
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0499858037 -0.0242248494 -0.0313238502
+ vertex 0.0301822927 -0.0239052977 -0.0260417778
+ vertex 0.05054418 -0.0230156612 -0.0343847312
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0499858037 -0.0242248494 -0.0313238502
+ vertex 0.0119591318 -0.0240044985 -0.0111451717
+ vertex 0.0301822927 -0.0239052977 -0.0260417778
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 -0.0215513017 0.00422760192
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ vertex 0.00100057351 -0.0217247847 -0.00168395217
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 -0.0215513017 0.00422760192
+ vertex 0.00100057351 -0.0217247847 -0.00168395217
+ vertex 0.00780997705 -0.0237585288 0.0051452904
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 -0.0215513017 0.00422760192
+ vertex 0.00780997705 -0.0237585288 0.0051452904
+ vertex 0.0100970119 -0.0232202392 0.0119567169
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 -0.0215513017 0.00422760192
+ vertex 0.0100970119 -0.0232202392 0.0119567169
+ vertex 0.0010439317 -0.0179824214 0.0128565431
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00124881195 -0.0215513017 0.00422760192
+ vertex 0.0010439317 -0.0179824214 0.0128565431
+ vertex 8.5700085e-05 -0.0198695455 0.00598262344
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.65021208e-05 0.0172973722 -0.0173943657
+ vertex 0.000813621096 0.0147488276 -0.0207792539
+ vertex 2.26137872e-05 0.00500459271 -0.0223245509
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.65021208e-05 0.0172973722 -0.0173943657
+ vertex -4.33680869e-19 0.0204886571 -0.0058807116
+ vertex 0.000827543903 0.0200854614 -0.0154875098
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 2.65021208e-05 0.0172973722 -0.0173943657
+ vertex 0.000827543903 0.0200854614 -0.0154875098
+ vertex 0.000813621096 0.0147488276 -0.0207792539
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_six_link.STL b/assets/unitree_hand/meshes/right_hand_six_link.STL
new file mode 100644
index 0000000..262b9fb
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_six_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_six_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_six_link.STL.convex.stl
new file mode 100644
index 0000000..ccd6a8e
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_six_link.STL.convex.stl
@@ -0,0 +1,690 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0378707163 -0.00771122705 0.00497220876
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 0.0300000012 -0.00700000022 0.0128999986
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex 6.70552225e-10 -0.00700000022 0.0128999986
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0218338352 -0.00849467609 1.17838379e-08
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0545902252 0.00752525544 0.00558171095
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.067230165 0.00171520142 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex 0.0561827868 -0.00311235571 0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0472379029 -0.00615968416 -0.0105616581
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.049899593 -0.00582374632 0.0103603406
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex 0.0255697463 0.00990009308 -0.00399018405
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex -0.00121553731 0.00689365435 0.0128999986
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0255622845 0.00971204787 0.00558968494
+ vertex 0.0300000012 0.00700000022 0.0128999986
+ vertex 0.0411676802 0.00952773262 0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.0486769713 0.00900336448 -0.00344834942
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.0575625114 0.00782644935 0.000586750568
+ vertex 0.064408727 0.0049878736 0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0619539768 0.00584984384 -0.00439739088
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ vertex 0.0575334616 0.00589359924 -0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.0620835871 0.00281458907 -0.00817895588
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0664913431 -0.000459232426 -0.00766683137
+ vertex 0.067726776 -0.002401951 -0.00608098926
+ vertex 0.0648363978 -0.00285470835 -0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.066054292 0.00275459839 -0.00593568338
+ vertex 0.064408727 0.0049878736 0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.064408727 0.0049878736 0.000419684395
+ vertex 0.067230165 0.00171520142 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.067230165 0.00171520142 0.00518755475
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0685341135 3.54065014e-05 -0.00187589996
+ vertex 0.0686098039 -0.00199394976 6.07967399e-10
+ vertex 0.0680127069 -0.000901179796 -0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00536231138 0.00449951319 0.0128999986
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00536231138 0.00449951319 0.00980000105
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00274999929 0.00476314034 -0.0127999997
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex 0.0293420218 0.00693969289 -0.0127999997
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex 0.0251587834 -0.00700000022 -0.0127999997
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00188111258 -0.0051683099 -0.0127999997
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476313895 0.00275000022 -0.0127999997
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0666762441 -0.00243695313 0.00758745195
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0680978522 -0.000984676648 0.0057562408
+ vertex 0.067230165 0.00171520142 0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.067230165 0.00171520142 0.00518755475
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0668851808 -0.000365349086 0.00737955468
+ vertex 0.0633781254 0.00415326515 0.00660281349
+ vertex 0.0606325418 0.00187931687 0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00550000137 -5.58793602e-11 -0.0127999997
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00421324559 -0.00353533193 -0.0127999997
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00449951505 -0.00536231184 0.0128999986
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00606217748 -0.00350000034 0.00980000105
+ vertex -0.00700000115 -5.58793602e-11 0.0128999986
+ vertex -0.00700000115 -5.58793602e-11 0.00980000105
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_three_link.STL b/assets/unitree_hand/meshes/right_hand_three_link.STL
new file mode 100644
index 0000000..5fa3f69
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_three_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_three_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_three_link.STL.convex.stl
new file mode 100644
index 0000000..2b64d5c
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_three_link.STL.convex.stl
@@ -0,0 +1,514 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0493873209 0.0195229407 -0.00874405634
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0462736487 0.0142848082 -0.0128999986
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0616396926 -0.000857979583 -0.0128999986
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ vertex 0.0615910105 -0.00453977613 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0279263519 0.0142848082 -0.0128999986
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ vertex 0.0292240847 0.0195752457 -0.00902805198
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ vertex -0.00239414047 0.00657784799 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex 0.0589422211 -0.00698768906 -0.0128999986
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00121553685 -0.00689365482 -0.0128999986
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ vertex 0.0588857867 -0.00703301234 0.00925000012
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0280000027 -0.00710000051 0.00899999961
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0485116169 0.0198519398 0.00720310537
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0292285774 0.0198698081 0.00704996567
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0617876872 -0.00434222026 0.00899999961
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0492131189 0.0182656925 0.00899499655
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0617924035 0.00550000044 0.00908682402
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0617999993 0.00550000044 -0.00900000054
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0605942272 0.00999999978 0.00899999961
+ vertex 0.0596943982 0.0112850871 -0.00900000054
+ vertex 0.0582380779 0.0125870351 0.00925000012
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00549999904 4.17232499e-10 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00536231231 -0.00449951272 -0.0128999986
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00536231231 -0.00449951272 -0.00990000088
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00536231231 0.00449951272 -0.00990000088
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00536231231 0.00449951272 -0.0128999986
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.0128999986
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00700000208 4.17232499e-10 -0.00990000088
+ vertex -0.00549999904 4.17232499e-10 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00549999904 4.17232499e-10 0.0127999997
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00476314034 -0.00274999952 0.0127999997
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex -0.00275000068 -0.00476313895 0.0127999997
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex 0.0355000049 -0.00536602503 0.0127999997
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex 0.0359396972 0.0137420204 0.0127999997
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00476314034 0.00275000045 0.0127999997
+ vertex 0.0268263537 0.0143848071 0.0127999997
+ vertex -0.00275000068 0.00476313988 0.0127999997
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_two_link.STL b/assets/unitree_hand/meshes/right_hand_two_link.STL
new file mode 100644
index 0000000..a4b3447
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_two_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_two_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_two_link.STL.convex.stl
new file mode 100644
index 0000000..2c051ce
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_two_link.STL.convex.stl
@@ -0,0 +1,690 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ vertex -5.58793602e-11 -0.00700000115 -0.0128999986
+ vertex -0.00536231184 -0.00449951505 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ vertex -0.00536231184 -0.00449951505 -0.0128999986
+ vertex -0.00700000022 6.70552225e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ vertex -0.00700000022 6.70552225e-10 -0.0128999986
+ vertex -0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ vertex -0.00700000022 0.0300000012 -0.0128999986
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ vertex 0.00689365435 -0.00121553731 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00700000022 0.0300000012 -0.0128999986
+ vertex -0.00311235571 0.0561827868 -0.0100471107
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00990009308 0.0255697463 0.00399018405
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ vertex 0.00476314034 -0.00274999929 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00990009308 0.0255697463 0.00399018405
+ vertex 0.00476314034 -0.00274999929 0.0127999997
+ vertex 0.00689365435 -0.00121553731 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00536231184 -0.00449951505 -0.0128999986
+ vertex -0.0051683099 -0.00188111258 0.0127999997
+ vertex -0.00700000022 6.70552225e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 -0.00536231138 -0.00980000105
+ vertex 0.00689365435 -0.00121553731 -0.0128999986
+ vertex 0.00476314034 -0.00274999929 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00700000022 0.0251587834 0.0127999997
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ vertex -0.00285470835 0.0648363978 0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00700000022 0.0251587834 0.0127999997
+ vertex -0.00285470835 0.0648363978 0.0083658481
+ vertex -0.00615968416 0.0472379029 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ vertex 0.00689365435 -0.00121553731 -0.0128999986
+ vertex 0.00449951319 -0.00536231138 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 0.049899593 -0.0103603406
+ vertex -0.00243695313 0.0666762441 -0.00758745195
+ vertex -0.00311235571 0.0561827868 -0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 0.049899593 -0.0103603406
+ vertex -0.00311235571 0.0561827868 -0.0100471107
+ vertex -0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 0.049899593 -0.0103603406
+ vertex -0.00700000022 0.0300000012 -0.0128999986
+ vertex -0.00771122705 0.0378707163 -0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00582374632 0.049899593 -0.0103603406
+ vertex -0.00771122705 0.0378707163 -0.00497220876
+ vertex -0.00615968416 0.0472379029 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 0.0218338352 -1.17838379e-08
+ vertex -0.00700000022 0.0251587834 0.0127999997
+ vertex -0.00615968416 0.0472379029 0.0105616581
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 0.0218338352 -1.17838379e-08
+ vertex -0.00615968416 0.0472379029 0.0105616581
+ vertex -0.00771122705 0.0378707163 -0.00497220876
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 0.0218338352 -1.17838379e-08
+ vertex -0.00771122705 0.0378707163 -0.00497220876
+ vertex -0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 0.0218338352 -1.17838379e-08
+ vertex -0.00700000022 0.0300000012 -0.0128999986
+ vertex -0.00700000022 6.70552225e-10 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 0.0218338352 -1.17838379e-08
+ vertex -0.00700000022 6.70552225e-10 -0.0128999986
+ vertex -0.0051683099 -0.00188111258 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00849467609 0.0218338352 -1.17838379e-08
+ vertex -0.0051683099 -0.00188111258 0.0127999997
+ vertex -0.00700000022 0.0251587834 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 0.0486769713 0.00344834942
+ vertex 0.00990009308 0.0255697463 0.00399018405
+ vertex 0.00952773262 0.0411676802 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 0.0486769713 0.00344834942
+ vertex 0.00952773262 0.0411676802 -0.00370552461
+ vertex 0.00782644935 0.0575625114 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 0.0486769713 0.00344834942
+ vertex 0.00589359924 0.0575334616 0.00724274013
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00900336448 0.0486769713 0.00344834942
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ vertex 0.00990009308 0.0255697463 0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 0.0545902252 -0.00558171095
+ vertex 0.00415326515 0.0633781254 -0.00660281349
+ vertex 0.00782644935 0.0575625114 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 0.0545902252 -0.00558171095
+ vertex 0.00782644935 0.0575625114 -0.000586750568
+ vertex 0.00952773262 0.0411676802 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 0.0545902252 -0.00558171095
+ vertex 0.00952773262 0.0411676802 -0.00370552461
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00752525544 0.0545902252 -0.00558171095
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ vertex 0.00415326515 0.0633781254 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0049878736 0.064408727 -0.000419684395
+ vertex 0.00782644935 0.0575625114 -0.000586750568
+ vertex 0.00415326515 0.0633781254 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0049878736 0.064408727 -0.000419684395
+ vertex 0.00415326515 0.0633781254 -0.00660281349
+ vertex 0.00171520142 0.067230165 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00281458907 0.0620835871 0.00817895588
+ vertex 0.00589359924 0.0575334616 0.00724274013
+ vertex 0.00275459839 0.066054292 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00281458907 0.0620835871 0.00817895588
+ vertex -0.00285470835 0.0648363978 0.0083658481
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00281458907 0.0620835871 0.00817895588
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ vertex 0.00589359924 0.0575334616 0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00311235571 0.0561827868 -0.0100471107
+ vertex -0.00243695313 0.0666762441 -0.00758745195
+ vertex -0.000365349086 0.0668851808 -0.00737955468
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00311235571 0.0561827868 -0.0100471107
+ vertex -0.000365349086 0.0668851808 -0.00737955468
+ vertex 0.00187931687 0.0606325418 -0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00187931687 0.0606325418 -0.00884774793
+ vertex 0.00415326515 0.0633781254 -0.00660281349
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00187931687 0.0606325418 -0.00884774793
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ vertex -0.00311235571 0.0561827868 -0.0100471107
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.002401951 0.067726776 0.00608098926
+ vertex -0.000901179796 0.0680127069 0.00600992516
+ vertex -0.00199394976 0.0686098039 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.002401951 0.067726776 0.00608098926
+ vertex -0.00199394976 0.0686098039 -6.07967399e-10
+ vertex -0.00243695313 0.0666762441 -0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615968416 0.0472379029 0.0105616581
+ vertex -0.00285470835 0.0648363978 0.0083658481
+ vertex -0.002401951 0.067726776 0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615968416 0.0472379029 0.0105616581
+ vertex -0.002401951 0.067726776 0.00608098926
+ vertex -0.00243695313 0.0666762441 -0.00758745195
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00615968416 0.0472379029 0.0105616581
+ vertex -0.00243695313 0.0666762441 -0.00758745195
+ vertex -0.00582374632 0.049899593 -0.0103603406
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00353533193 -0.00421324559 0.0127999997
+ vertex -0.0051683099 -0.00188111258 0.0127999997
+ vertex -0.00536231184 -0.00449951505 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 0.0255622845 -0.00558968494
+ vertex 0.00952773262 0.0411676802 -0.00370552461
+ vertex 0.00990009308 0.0255697463 0.00399018405
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 0.0255622845 -0.00558968494
+ vertex 0.00990009308 0.0255697463 0.00399018405
+ vertex 0.00689365435 -0.00121553731 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 0.0255622845 -0.00558968494
+ vertex 0.00689365435 -0.00121553731 -0.0128999986
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00971204787 0.0255622845 -0.00558968494
+ vertex 0.00700000022 0.0300000012 -0.0128999986
+ vertex 0.00952773262 0.0411676802 -0.00370552461
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 0.0619539768 0.00439739088
+ vertex 0.00589359924 0.0575334616 0.00724274013
+ vertex 0.00900336448 0.0486769713 0.00344834942
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 0.0619539768 0.00439739088
+ vertex 0.00900336448 0.0486769713 0.00344834942
+ vertex 0.00782644935 0.0575625114 -0.000586750568
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 0.0619539768 0.00439739088
+ vertex 0.00782644935 0.0575625114 -0.000586750568
+ vertex 0.0049878736 0.064408727 -0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 0.0619539768 0.00439739088
+ vertex 0.0049878736 0.064408727 -0.000419684395
+ vertex 0.00275459839 0.066054292 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00584984384 0.0619539768 0.00439739088
+ vertex 0.00275459839 0.066054292 0.00593568338
+ vertex 0.00589359924 0.0575334616 0.00724274013
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000984676648 0.0680978522 -0.0057562408
+ vertex -0.00243695313 0.0666762441 -0.00758745195
+ vertex -0.00199394976 0.0686098039 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 0.0664913431 0.00766683137
+ vertex -0.00285470835 0.0648363978 0.0083658481
+ vertex 0.00281458907 0.0620835871 0.00817895588
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 0.0664913431 0.00766683137
+ vertex 0.00281458907 0.0620835871 0.00817895588
+ vertex 0.00275459839 0.066054292 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 0.0664913431 0.00766683137
+ vertex 0.00275459839 0.066054292 0.00593568338
+ vertex -0.000901179796 0.0680127069 0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 0.0664913431 0.00766683137
+ vertex -0.000901179796 0.0680127069 0.00600992516
+ vertex -0.002401951 0.067726776 0.00608098926
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000459232426 0.0664913431 0.00766683137
+ vertex -0.002401951 0.067726776 0.00608098926
+ vertex -0.00285470835 0.0648363978 0.0083658481
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 0.0685341135 0.00187589996
+ vertex -0.000901179796 0.0680127069 0.00600992516
+ vertex 0.00275459839 0.066054292 0.00593568338
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 0.0685341135 0.00187589996
+ vertex 0.00275459839 0.066054292 0.00593568338
+ vertex 0.0049878736 0.064408727 -0.000419684395
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 0.0685341135 0.00187589996
+ vertex 0.0049878736 0.064408727 -0.000419684395
+ vertex 0.00171520142 0.067230165 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 0.0685341135 0.00187589996
+ vertex 0.00171520142 0.067230165 -0.00518755475
+ vertex -0.000984676648 0.0680978522 -0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 0.0685341135 0.00187589996
+ vertex -0.000984676648 0.0680978522 -0.0057562408
+ vertex -0.00199394976 0.0686098039 -6.07967399e-10
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 3.54065014e-05 0.0685341135 0.00187589996
+ vertex -0.00199394976 0.0686098039 -6.07967399e-10
+ vertex -0.000901179796 0.0680127069 0.00600992516
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex -5.58793602e-11 -0.00550000137 0.0127999997
+ vertex -5.58793602e-11 -0.00700000115 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex -5.58793602e-11 -0.00700000115 -0.00980000105
+ vertex -5.58793602e-11 -0.00700000115 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex -5.58793602e-11 -0.00700000115 -0.0128999986
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex 0.00449951319 -0.00536231138 -0.0128999986
+ vertex 0.00449951319 -0.00536231138 -0.00980000105
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex 0.00449951319 -0.00536231138 -0.00980000105
+ vertex 0.00476314034 -0.00274999929 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex 0.00476314034 -0.00274999929 0.0127999997
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex 0.00693969289 0.0293420218 0.0127999997
+ vertex -0.00700000022 0.0251587834 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex -0.00700000022 0.0251587834 0.0127999997
+ vertex -0.0051683099 -0.00188111258 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex -0.0051683099 -0.00188111258 0.0127999997
+ vertex -0.00353533193 -0.00421324559 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00275000022 -0.00476313895 0.0127999997
+ vertex -0.00353533193 -0.00421324559 0.0127999997
+ vertex -5.58793602e-11 -0.00550000137 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 0.0668851808 -0.00737955468
+ vertex -0.00243695313 0.0666762441 -0.00758745195
+ vertex -0.000984676648 0.0680978522 -0.0057562408
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 0.0668851808 -0.00737955468
+ vertex -0.000984676648 0.0680978522 -0.0057562408
+ vertex 0.00171520142 0.067230165 -0.00518755475
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 0.0668851808 -0.00737955468
+ vertex 0.00171520142 0.067230165 -0.00518755475
+ vertex 0.00415326515 0.0633781254 -0.00660281349
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.000365349086 0.0668851808 -0.00737955468
+ vertex 0.00415326515 0.0633781254 -0.00660281349
+ vertex 0.00187931687 0.0606325418 -0.00884774793
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 -0.00606217748 -0.00980000105
+ vertex -5.58793602e-11 -0.00700000115 -0.00980000105
+ vertex -5.58793602e-11 -0.00550000137 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 -0.00606217748 -0.00980000105
+ vertex -5.58793602e-11 -0.00550000137 0.0127999997
+ vertex -0.00353533193 -0.00421324559 0.0127999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 -0.00606217748 -0.00980000105
+ vertex -0.00353533193 -0.00421324559 0.0127999997
+ vertex -0.00536231184 -0.00449951505 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 -0.00606217748 -0.00980000105
+ vertex -0.00536231184 -0.00449951505 -0.0128999986
+ vertex -5.58793602e-11 -0.00700000115 -0.0128999986
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00350000034 -0.00606217748 -0.00980000105
+ vertex -5.58793602e-11 -0.00700000115 -0.0128999986
+ vertex -5.58793602e-11 -0.00700000115 -0.00980000105
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/meshes/right_hand_zero_link.STL b/assets/unitree_hand/meshes/right_hand_zero_link.STL
new file mode 100644
index 0000000..07c3be0
Binary files /dev/null and b/assets/unitree_hand/meshes/right_hand_zero_link.STL differ
diff --git a/assets/unitree_hand/meshes/right_hand_zero_link.STL.convex.stl b/assets/unitree_hand/meshes/right_hand_zero_link.STL.convex.stl
new file mode 100644
index 0000000..8322d8b
--- /dev/null
+++ b/assets/unitree_hand/meshes/right_hand_zero_link.STL.convex.stl
@@ -0,0 +1,594 @@
+solid AssimpScene
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.00180805009 -0.00119999959 0.0148906345
+ vertex -0.0035897349 -0.00119999959 0.0145641286
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -0.0035897349 -0.00119999959 0.0145641286
+ vertex -0.00852097105 -0.00119999959 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -0.00852097105 -0.00119999959 0.012344759
+ vertex -0.0132818408 -0.00119999959 0.00697084796
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -0.0132818408 -0.00119999959 0.00697084796
+ vertex -0.0148906335 -0.00119999959 0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -0.0148906335 -0.00119999959 0.0018080502
+ vertex -0.0145641277 -0.00119999959 -0.00358973537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -0.0145641277 -0.00119999959 -0.00358973537
+ vertex -0.0112276617 -0.00119999959 -0.00994683988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -0.0112276617 -0.00119999959 -0.00994683988
+ vertex -0.00531907333 -0.00119999959 -0.0140252449
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -0.00531907333 -0.00119999959 -0.0140252449
+ vertex -5.58793567e-11 -0.00119999959 -0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex -5.58793567e-11 -0.00119999959 -0.0149999997
+ vertex 0.00531907333 -0.00119999959 -0.0140252449
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.00531907333 -0.00119999959 -0.0140252449
+ vertex 0.00994683988 -0.00119999959 -0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.00994683988 -0.00119999959 -0.0112276617
+ vertex 0.0132818399 -0.00119999959 -0.00697084842
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.0132818399 -0.00119999959 -0.00697084842
+ vertex 0.0149999997 -0.00119999959 -5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.0149999997 -0.00119999959 -5.21540693e-11
+ vertex 0.0140252439 -0.00119999959 0.0053190738
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.0140252439 -0.00119999959 0.0053190738
+ vertex 0.0112276608 -0.00119999959 0.00994684082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00775584811 0.0333846211 0.00917101093
+ vertex 0.00775584811 0.0333846211 -0.00917101093
+ vertex -0.00249999994 0.0336000025 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00775584811 0.0333846211 0.00917101093
+ vertex -0.00249999994 0.0336000025 -0.00900000054
+ vertex -0.0043192273 0.033158794 0.00943301339
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ vertex 0.00775584811 0.0333846211 0.00917101093
+ vertex -0.0043192273 0.033158794 0.00943301339
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00852097105 0.0242999997 -0.012344759
+ vertex -0.00916589517 0.0306019988 -0.00917101093
+ vertex -0.00616062991 0.0328219086 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00852097105 0.0242999997 -0.012344759
+ vertex -0.00616062991 0.0328219086 -0.00900000054
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ vertex -0.00249999994 0.0336000025 -0.00900000054
+ vertex 0.00775584811 0.0333846211 -0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ vertex 0.00775584811 0.0333846211 -0.00917101093
+ vertex 0.00993980374 0.0309586544 -0.00932139438
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ vertex 0.00993980374 0.0309586544 -0.00932139438
+ vertex 0.00852097105 0.0242999997 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00975675788 0.0298723429 0.00917101093
+ vertex -0.00994683988 0.0242999997 0.0112276617
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00975675788 0.0298723429 0.00917101093
+ vertex -0.00916589517 0.0306019988 -0.00917101093
+ vertex -0.0148906335 0.0242999997 -0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 0.0242999997 -0.00697084842
+ vertex 0.00994683988 -0.00119999959 -0.0112276617
+ vertex 0.00852097105 0.0242999997 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140252439 0.0242999997 0.0053190738
+ vertex -0.00994683988 0.0242999997 0.0112276617
+ vertex -0.00975675788 0.0298723429 0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140252439 0.0242999997 0.0053190738
+ vertex -0.00975675788 0.0298723429 0.00917101093
+ vertex -0.0148906335 0.0242999997 -0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0140252439 0.0242999997 0.0053190738
+ vertex -0.0148906335 0.0242999997 -0.0018080502
+ vertex -0.0148906335 -0.00119999959 0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 0.0242999997 0.00697084796
+ vertex 0.00852097105 0.0242999997 0.012344759
+ vertex 0.0112276608 -0.00119999959 0.00994684082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0145641277 -0.00119999959 -0.00358973537
+ vertex -0.0148906335 -0.00119999959 0.0018080502
+ vertex -0.0148906335 0.0242999997 -0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.0242999997 -0.00697084842
+ vertex -0.00852097105 0.0242999997 -0.012344759
+ vertex -0.0112276617 -0.00119999959 -0.00994683988
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.0242999997 -0.00697084842
+ vertex -0.0112276617 -0.00119999959 -0.00994683988
+ vertex -0.0145641277 -0.00119999959 -0.00358973537
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.0242999997 -0.00697084842
+ vertex -0.0145641277 -0.00119999959 -0.00358973537
+ vertex -0.0148906335 0.0242999997 -0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.0242999997 -0.00697084842
+ vertex -0.0148906335 0.0242999997 -0.0018080502
+ vertex -0.00916589517 0.0306019988 -0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 0.0242999997 -0.00697084842
+ vertex -0.00916589517 0.0306019988 -0.00917101093
+ vertex -0.00852097105 0.0242999997 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00531907333 -0.00119999959 -0.0140252449
+ vertex -0.0112276617 -0.00119999959 -0.00994683988
+ vertex -0.00852097105 0.0242999997 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00531907333 -0.00119999959 -0.0140252449
+ vertex -0.00852097105 0.0242999997 -0.012344759
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00531907333 -0.00119999959 -0.0140252449
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ vertex -5.58793567e-11 -0.00119999959 -0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.00119999959 0.00697084796
+ vertex -0.00852097105 -0.00119999959 0.012344759
+ vertex -0.00994683988 0.0242999997 0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.00119999959 0.00697084796
+ vertex -0.00994683988 0.0242999997 0.0112276617
+ vertex -0.0140252439 0.0242999997 0.0053190738
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0132818408 -0.00119999959 0.00697084796
+ vertex -0.0140252439 0.0242999997 0.0053190738
+ vertex -0.0148906335 -0.00119999959 0.0018080502
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 -0.00119999959 -0.00697084842
+ vertex 0.00994683988 -0.00119999959 -0.0112276617
+ vertex 0.0132818399 0.0242999997 -0.00697084842
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 -0.00119999959 -0.00697084842
+ vertex 0.0132818399 0.0242999997 -0.00697084842
+ vertex 0.0149999997 0.0242999997 -5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0132818399 -0.00119999959 -0.00697084842
+ vertex 0.0149999997 0.0242999997 -5.21540693e-11
+ vertex 0.0149999997 -0.00119999959 -5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 0.0309586544 0.00932139438
+ vertex 0.00852097105 0.0242999997 0.012344759
+ vertex 0.0132818399 0.0242999997 0.00697084796
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 0.0309586544 0.00932139438
+ vertex 0.0132818399 0.0242999997 0.00697084796
+ vertex 0.0149999997 0.0242999997 -5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 0.0309586544 -0.00932139438
+ vertex 0.00775584811 0.0333846211 -0.00917101093
+ vertex 0.00775584811 0.0333846211 0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 0.0309586544 -0.00932139438
+ vertex 0.00775584811 0.0333846211 0.00917101093
+ vertex 0.00993980374 0.0309586544 0.00932139438
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 0.0309586544 -0.00932139438
+ vertex 0.00993980374 0.0309586544 0.00932139438
+ vertex 0.0149999997 0.0242999997 -5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 0.0309586544 -0.00932139438
+ vertex 0.0149999997 0.0242999997 -5.21540693e-11
+ vertex 0.0132818399 0.0242999997 -0.00697084842
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00993980374 0.0309586544 -0.00932139438
+ vertex 0.0132818399 0.0242999997 -0.00697084842
+ vertex 0.00852097105 0.0242999997 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00531907333 -0.00119999959 -0.0140252449
+ vertex 0.00852097105 0.0242999997 -0.012344759
+ vertex 0.00994683988 -0.00119999959 -0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00531907333 -0.00119999959 -0.0140252449
+ vertex -5.58793567e-11 -0.00119999959 -0.0149999997
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00531907333 -0.00119999959 -0.0140252449
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ vertex 0.00852097105 0.0242999997 -0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0035897349 -0.00119999959 0.0145641286
+ vertex 0.00180805009 -0.00119999959 0.0148906345
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0035897349 -0.00119999959 0.0145641286
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ vertex -0.00994683988 0.0242999997 0.0112276617
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.0035897349 -0.00119999959 0.0145641286
+ vertex -0.00994683988 0.0242999997 0.0112276617
+ vertex -0.00852097105 -0.00119999959 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 0.0242999997 0.0145641286
+ vertex 0.00852097105 0.0242999997 0.012344759
+ vertex 0.00993980374 0.0309586544 0.00932139438
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 0.0242999997 0.0145641286
+ vertex 0.00993980374 0.0309586544 0.00932139438
+ vertex 0.00775584811 0.0333846211 0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 0.0242999997 0.0145641286
+ vertex 0.00775584811 0.0333846211 0.00917101093
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0035897349 0.0242999997 0.0145641286
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ vertex 0.00180805009 -0.00119999959 0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0140252439 -0.00119999959 0.0053190738
+ vertex 0.0149999997 -0.00119999959 -5.21540693e-11
+ vertex 0.0149999997 0.0242999997 -5.21540693e-11
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0140252439 -0.00119999959 0.0053190738
+ vertex 0.0149999997 0.0242999997 -5.21540693e-11
+ vertex 0.0132818399 0.0242999997 0.00697084796
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.0140252439 -0.00119999959 0.0053190738
+ vertex 0.0132818399 0.0242999997 0.00697084796
+ vertex 0.0112276608 -0.00119999959 0.00994684082
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.0112276608 -0.00119999959 0.00994684082
+ vertex 0.00852097105 0.0242999997 0.012344759
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.00852097105 0.0242999997 0.012344759
+ vertex 0.0035897349 0.0242999997 0.0145641286
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex 0.00697084749 -0.00119999959 0.0132818408
+ vertex 0.0035897349 0.0242999997 0.0145641286
+ vertex 0.00180805009 -0.00119999959 0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00616062991 0.0328219086 -0.00900000054
+ vertex -0.00249999994 0.0336000025 -0.00900000054
+ vertex -5.58793567e-11 0.0242999997 -0.0149999997
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00616062991 0.0328219086 -0.00900000054
+ vertex -0.0043192273 0.033158794 0.00943301339
+ vertex -0.00249999994 0.0336000025 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 0.0323942304 0.00900000054
+ vertex -0.0043192273 0.033158794 0.00943301339
+ vertex -0.00616062991 0.0328219086 -0.00900000054
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 0.0323942304 0.00900000054
+ vertex -0.00616062991 0.0328219086 -0.00900000054
+ vertex -0.00916589517 0.0306019988 -0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 0.0323942304 0.00900000054
+ vertex -0.00916589517 0.0306019988 -0.00917101093
+ vertex -0.00975675788 0.0298723429 0.00917101093
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 0.0323942304 0.00900000054
+ vertex -0.00975675788 0.0298723429 0.00917101093
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ endloop
+ endfacet
+
+ facet normal 0 0 0
+ outer loop
+ vertex -0.00699999975 0.0323942304 0.00900000054
+ vertex -0.0018080502 0.0242999997 0.0148906345
+ vertex -0.0043192273 0.033158794 0.00943301339
+ endloop
+ endfacet
+
+endsolid AssimpScene
diff --git a/assets/unitree_hand/unitree_dex3.yml b/assets/unitree_hand/unitree_dex3.yml
new file mode 100644
index 0000000..4e2ea51
--- /dev/null
+++ b/assets/unitree_hand/unitree_dex3.yml
@@ -0,0 +1,48 @@
+left:
+ type: vector
+ urdf_path: unitree_hand/unitree_dex3_left.urdf
+
+ # Target refers to the retargeting target, which is the robot hand
+ # target_joint_names:
+ target_joint_names:
+ [
+ "left_hand_zero_joint",
+ "left_hand_one_joint",
+ "left_hand_two_joint",
+ "left_hand_three_joint",
+ "left_hand_four_joint",
+ "left_hand_five_joint",
+ "left_hand_six_joint",
+ ]
+ wrist_link_name: None
+ target_origin_link_names: ["base_link_thumb","base_link","base_link"]
+ target_task_link_names: ["thumb_tip","index_tip","middle_tip"]
+ target_link_human_indices: [[0, 0, 0], [4, 9, 14]]
+
+ scaling_factor: 1.4
+
+ # A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
+ low_pass_alpha: 0.2
+
+right:
+ type: vector
+ urdf_path: unitree_hand/unitree_dex3_right.urdf
+
+ # Target refers to the retargeting target, which is the robot hand
+ target_joint_names:
+ [
+ "right_hand_zero_joint",
+ "right_hand_one_joint",
+ "right_hand_two_joint",
+ "right_hand_three_joint",
+ "right_hand_four_joint",
+ "right_hand_five_joint",
+ "right_hand_six_joint",
+ ]
+ wrist_link_name: None
+ target_origin_link_names: ["base_link_thumb","base_link","base_link"]
+ target_task_link_names: ["thumb_tip", "index_tip", "middle_tip"]
+ target_link_human_indices: [[0, 0, 0], [4, 9, 14]]
+ scaling_factor: 1.4
+ # A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
+ low_pass_alpha: 0.2
diff --git a/assets/unitree_hand/unitree_dex3_left.urdf b/assets/unitree_hand/unitree_dex3_left.urdf
new file mode 100644
index 0000000..f4609b3
--- /dev/null
+++ b/assets/unitree_hand/unitree_dex3_left.urdf
@@ -0,0 +1,400 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/assets/unitree_hand/unitree_dex3_right.urdf b/assets/unitree_hand/unitree_dex3_right.urdf
new file mode 100644
index 0000000..2f0554e
--- /dev/null
+++ b/assets/unitree_hand/unitree_dex3_right.urdf
@@ -0,0 +1,400 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/scripts/deploy_sim.py b/scripts/deploy_sim.py
deleted file mode 100644
index 294661a..0000000
--- a/scripts/deploy_sim.py
+++ /dev/null
@@ -1,150 +0,0 @@
-from isaacgym import gymapi
-from isaacgym import gymutil
-
-import math
-import numpy as np
-import matplotlib.pyplot as plt
-
-from replay_demo import Player
-
-from pathlib import Path
-import h5py
-from tqdm import tqdm
-import time
-import yaml
-import pickle
-import torch
-import cv2
-from collections import deque
-import argparse
-import sys
-sys.path.append("../")
-from act.utils import parse_id
-# from act.imitate_episodes import RECORD_DIR, DATA_DIR, LOG_DIR
-
-from pathlib import Path
-current_dir = Path(__file__).parent.resolve()
-DATA_DIR = (current_dir.parent / 'data/').resolve()
-RECORD_DIR = (DATA_DIR / 'recordings/').resolve()
-LOG_DIR = (DATA_DIR / 'logs/').resolve()
-# print(f"\nDATA dir: {DATA_DIR}")
-
-def get_norm_stats(data_path):
- # norm_stats = {
- # "action_mean": np.array([]), "action_std": np.array([]),
- # "qpos_mean": np.array([]), "qpos_std": np.array([]),
- # }
- with open(data_path, "rb") as f:
- norm_stats = pickle.load(f)
- return norm_stats
-
-
-def load_policy(policy_path, device):
- policy = torch.jit.load(policy_path, map_location=device)
- return policy
-
-
-def normalize_input(state, left_img, right_img, norm_stats, last_action_data=None):
- # import ipdb; ipdb.set_trace()
- # left_img = cv2.resize(left_img, (308, 224))
- # right_img = cv2.resize(right_img, (308, 224))
- image_data = torch.from_numpy(np.stack([left_img, right_img], axis=0)) / 255.0
- qpos_data = (torch.from_numpy(state) - norm_stats["qpos_mean"]) / norm_stats["qpos_std"]
- image_data = image_data.view((1, 2, 3, 480, 640)).to(device='cuda')
- qpos_data = qpos_data.view((1, 26)).to(device='cuda')
-
- if last_action_data is not None:
- last_action_data = torch.from_numpy(last_action_data).to(device='cuda').view((1, -1)).to(torch.float)
- qpos_data = torch.cat((qpos_data, last_action_data), dim=1)
- return (qpos_data, image_data)
-
-
-def merge_act(actions_for_curr_step, k = 0.01):
- actions_populated = np.all(actions_for_curr_step != 0, axis=1)
- actions_for_curr_step = actions_for_curr_step[actions_populated]
-
- exp_weights = np.exp(-k * np.arange(actions_for_curr_step.shape[0]))
- exp_weights = (exp_weights / exp_weights.sum()).reshape((-1, 1))
- raw_action = (actions_for_curr_step * exp_weights).sum(axis=0)
-
- return raw_action
-
-
-if __name__ == '__main__':
- parser = argparse.ArgumentParser('Set transformer detector', add_help=False)
- parser.add_argument('--taskid', action='store', type=str, help='task id', required=True)
- parser.add_argument('--exptid', action='store', type=str, help='experiment id', required=True)
- parser.add_argument('--resume_ckpt', action='store', type=str, help='resume checkpoint', required=True)
- args = vars(parser.parse_args())
-
- episode_name = "processed_episode_0.hdf5"
- task_dir, task_name = parse_id(RECORD_DIR, args['taskid'])
- episode_path = (Path(task_dir) / 'processed' / episode_name).resolve()
- exp_path, _ = parse_id((Path(LOG_DIR) / task_name).resolve(), args['exptid'])
-
- norm_stat_path = Path(exp_path) / "dataset_stats.pkl"
- policy_path = Path(exp_path) / f"traced_jit_{args['resume_ckpt']}.pt"
-
- temporal_agg = True
- action_dim = 28
-
- chunk_size = 60
- device = "cuda"
-
- data = h5py.File(str(episode_path), 'r')
- actions = np.array(data['qpos_action'])
- left_imgs = np.array(data['observation.image.left'])
- right_imgs = np.array(data['observation.image.right'])
- states = np.array(data['observation.state'])
- init_action = np.array(data.attrs['init_action'])
- data.close()
- timestamps = states.shape[0]
-
- norm_stats = get_norm_stats(norm_stat_path)
- policy = load_policy(policy_path, device)
- policy.cuda()
- policy.eval()
-
- history_stack = 0
- if history_stack > 0:
- last_action_queue = deque(maxlen=history_stack)
- for i in range(history_stack):
- last_action_queue.append(actions[0])
- else:
- last_action_queue = None
- last_action_data = None
- player = Player(dt=1/30)
-
- if temporal_agg:
- all_time_actions = np.zeros([timestamps, timestamps+chunk_size, action_dim])
- else:
- num_actions_exe = chunk_size
-
- try:
- output = None
- act_index = 0
- for t in tqdm(range(timestamps)):
- if history_stack > 0:
- last_action_data = np.array(last_action_queue)
-
- data = normalize_input(states[t], left_imgs[t], right_imgs[t], norm_stats, last_action_data)
-
- if temporal_agg:
- output = policy(*data)[0].detach().cpu().numpy() # (1,chuck_size,action_dim)
- all_time_actions[[t], t:t+chunk_size] = output
- act = merge_act(all_time_actions[:, t])
- else:
- if output is None or act_index == num_actions_exe-1:
- print("Inference...")
- output = policy(*data)[0].detach().cpu().numpy()
- act_index = 0
- act = output[act_index]
- act_index += 1
- # import ipdb; ipdb.set_trace()
- if history_stack > 0:
- last_action_queue.append(act)
- act = act * norm_stats["action_std"] + norm_stats["action_mean"]
- player.step(act, left_imgs[t], right_imgs[t])
- except KeyboardInterrupt:
- player.end()
- exit()
\ No newline at end of file
diff --git a/scripts/plot_action.py b/scripts/plot_action.py
deleted file mode 100644
index 28cecf4..0000000
--- a/scripts/plot_action.py
+++ /dev/null
@@ -1,33 +0,0 @@
-import math
-import numpy as np
-import matplotlib.pyplot as plt
-
-from pathlib import Path
-import h5py
-from tqdm import tqdm
-import time
-import yaml
-import pickle
-
-
-if __name__ == '__main__':
-
- root = "../data/recordings"
- exp_name = "00-can-sorting"
- episode_name = "processed_episode_0.hdf5"
- episode_path = Path(root) / exp_name / "processed" / episode_name
-
- data = h5py.File(str(episode_path), 'r')
- actions = np.array(data['qpos_action'])
- data.close()
- timestamps = actions.shape[0]
- action_dim = actions.shape[1]
-
- plot_num = np.ceil(np.sqrt(action_dim)).astype(int)
- plt.subplot(plot_num, plot_num, 1)
-
- for i in range(action_dim):
- plt.subplot(plot_num, plot_num, i+1)
- plt.plot(np.arange(timestamps), actions[:,i])
-
- plt.show()
diff --git a/scripts/post_process.py b/scripts/post_process.py
deleted file mode 100644
index 35c6f3b..0000000
--- a/scripts/post_process.py
+++ /dev/null
@@ -1,207 +0,0 @@
-import h5py
-import numpy as np
-import pyzed.sl as sl
-import time
-import cv2
-import matplotlib.pyplot as plt
-import tqdm
-import torch
-from torch.utils.data import Dataset
-import os
-import multiprocessing
-from numpy.lib.stride_tricks import as_strided
-
-from pytransform3d import rotations
-import concurrent.futures
-from pathlib import Path
-import argparse
-
-def load_svo(path, crop_size_h=240, crop_size_w=320):
- input_file = path + ".svo"
- # import ipdb; ipdb.set_trace()
- print(input_file)
- crop_size_h = crop_size_h
- crop_size_w = crop_size_w
- init_parameters = sl.InitParameters()
- init_parameters.set_from_svo_file(input_file)
-
- zed = sl.Camera()
- err = zed.open(init_parameters)
- left_image = sl.Mat()
- right_image = sl.Mat()
-
- nb_frames = zed.get_svo_number_of_frames()
- print("Total image frames: ", nb_frames)
-
- cropped_img_shape = (720-crop_size_h, 1280-2*crop_size_w)
- left_imgs = np.zeros((nb_frames, 3, cropped_img_shape[0], cropped_img_shape[1]), dtype=np.uint8)
- right_imgs = np.zeros((nb_frames, 3, cropped_img_shape[0], cropped_img_shape[1]), dtype=np.uint8)
- timestamps = np.zeros((nb_frames, ), dtype=np.int64)
- cnt = 0
- while True:
- if zed.grab() == sl.ERROR_CODE.SUCCESS:
- zed.retrieve_image(left_image, sl.VIEW.LEFT)
- zed.retrieve_image(right_image, sl.VIEW.RIGHT)
-
- timestamps[cnt] = zed.get_timestamp(sl.TIME_REFERENCE.IMAGE).get_milliseconds()
- # import ipdb; ipdb.set_trace()
- left_imgs[cnt] = cv2.cvtColor(left_image.get_data()[crop_size_h:, crop_size_w:-crop_size_w], cv2.COLOR_BGRA2RGB).transpose(2, 0, 1)
- right_imgs[cnt] = cv2.cvtColor(right_image.get_data()[crop_size_h:, crop_size_w:-crop_size_w], cv2.COLOR_BGRA2RGB).transpose(2, 0, 1)
- cnt += 1
- if cnt % 100 == 0:
- print(f"{cnt/nb_frames*100:.2f}%")
- # plt.imsave(f"left_img_{cnt}.png", left_imgs[cnt-1].transpose(1, 2, 0))
- elif zed.grab() == sl.ERROR_CODE.END_OF_SVOFILE_REACHED:
- break
- # print delta mean and std for img_timstamps
- delta = np.diff(timestamps)[:-1]
- print("img timestamps delta mean: ", np.mean(delta))
- print("img timestamps delta std: ", np.std(delta))
- return left_imgs[10:-10], right_imgs[10:-10], timestamps[10:-10]
-
-def load_hdf5(path, offset=10): # offset 10ms
- input_file = path + ".hdf5"
- file = h5py.File(input_file, 'r')
- print(f"Total hdf5_frames: {file['/obs/timestamp'].shape[0]}")
- # print(file["/obs/timestamp"].shape)
- # print(file["/obs/qpos"].shape)
- # print(file["/obs/qvel"].shape)
- # print(file["/action/joint_pos"].shape)
- # print("keys: ", list(file.keys()))
- timestamps = np.array(file["/obs/timestamp"][:] * 1000, dtype=np.int64) - offset
- states = np.array(file["/obs/qpos"][:])
- actions = np.array(file["/action/joint_pos"][:])
- cmds = np.array(file["/action/cmd"][:])
-
- return timestamps, states, actions, cmds
-
-def match_timestamps(candidate, ref):
- closest_indices = []
- # candidate = np.sort(candidate)
- for t in ref:
- idx = np.searchsorted(candidate, t, side="left")
- if idx > 0 and (idx == len(candidate) or np.fabs(t - candidate[idx-1]) < np.fabs(t - candidate[idx])):
- closest_indices.append(idx-1)
- else:
- closest_indices.append(idx)
- # print("closest_indices: ", len(closest_indices))
- return np.array(closest_indices)
-
-def find_all_episodes(path):
- episodes = [os.path.join(path, f) for f in os.listdir(path) if f.startswith('episode') and f.endswith('.svo')]
- episodes = [os.path.basename(ep).split(".")[0] for ep in episodes]
- return episodes
-
-def create_chunks(data, chunk_size):
- N, F = data.shape
- if chunk_size > N:
- raise ValueError("chunk_size cannot be greater than N.")
-
- stride0, stride1 = data.strides
- new_shape = (N - chunk_size + 1, chunk_size, F)
- new_strides = (stride0, stride0, stride1)
-
- return as_strided(data, shape=new_shape, strides=new_strides)
-
-def process_episode(file_name, ep):
- left_imgs, right_imgs, img_timestamps = load_svo(file_name)
- hdf5_timestamps, states, actions, cmds = load_hdf5(file_name)
- closest_indices = match_timestamps(candidate=hdf5_timestamps, ref=img_timestamps)
-
- timesteps = len(closest_indices)
- qpos_actions = actions[closest_indices]
- cmds = cmds[closest_indices]
-
- # save_video(left_imgs, file_name + ".mp4")
- path = os.path.dirname(file_name)
- all_data_path = os.path.join(path, "processed")
- os.makedirs(all_data_path, exist_ok=True)
-
- with h5py.File(all_data_path + f"/processed_{ep}.hdf5", 'w') as hf:
- start = time.time()
- hf.create_dataset('observation.image.left', data=left_imgs)
- hf.create_dataset('observation.image.right', data=right_imgs)
- hf.create_dataset('cmds', data=cmds.astype(np.float32))
- hf.create_dataset('observation.state', data=states[closest_indices].astype(np.float32))
- hf.create_dataset('qpos_action', data=qpos_actions.astype(np.float32))
- hf.attrs['sim'] = False
- hf.attrs['init_action'] = cmds[0].astype(np.float32)
-
- print("Time to save dataset: ", time.time() - start)
-
-def process_all_episodes(all_eps, path):
- results = []
- with concurrent.futures.ProcessPoolExecutor() as executor:
- future_to_ep = {executor.submit(process_episode, os.path.join(path, ep), ep): ep for ep in all_eps}
- for future in concurrent.futures.as_completed(future_to_ep):
- ep = future_to_ep[future]
- try:
- result = future.result()
- results.append(result)
- except Exception as e:
- print(f"Episode {ep} generated an exception: {e}")
- return results
-
-def save_video(left_imgs, path):
- _, height, width= left_imgs[0].shape
- print(f"width: {width}, height: {height}")
- fourcc = cv2.VideoWriter_fourcc(*'mp4v')
- video_writer = cv2.VideoWriter(path, fourcc, 60, (width, height))
-
- for img in left_imgs:
- # print(img.shape)
- img_bgr = cv2.cvtColor(img.transpose(1, 2, 0), cv2.COLOR_RGB2BGR)
- video_writer.write(img_bgr)
-
- video_writer.release()
-
-def find_all_processed_episodes(path):
- episodes = [f for f in os.listdir(path)]
- return episodes
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser()
- parser.add_argument('--save_video', action='store_true', default=False)
- args = parser.parse_args()
-
- root = "../data/recordings"
- folder_name = "00-can-sorting"
-
-
- path = os.path.join(root, folder_name)
-
- all_eps = find_all_episodes(path)
-
- if args.save_video:
- file_name = path + "/" + all_eps[0]
- print("saving video for file: ", file_name)
- left_imgs, right_imgs, img_timestamps = load_svo(file_name)
- os.makedirs(os.path.join(path, "videos"), exist_ok=True)
- save_video(left_imgs, os.path.join(path, "videos", "sample.mp4"))
- else:
- for ep in all_eps:
- file_name = path + "/" + ep
- process_episode(file_name, ep)
- print('processed file', file_name)
-
- # print len
- folder_path = Path(root) / folder_name / "processed"
-
- episodes = find_all_processed_episodes(folder_path)
- num_episodes = len(episodes)
- lens = []
-
- for episode in episodes:
- episode_path = folder_path / episode
-
- data = h5py.File(str(episode_path), 'r')
- lens.append(data['qpos_action'].shape[0])
- data.close()
-
- lens = np.array(lens)
- episodes = np.array(episodes)
- print(lens[np.argsort(lens)])
- print(episodes[np.argsort(lens)])
- # results = process_all_episodes(all_eps, path)
- # print(len(results))
diff --git a/scripts/replay_demo.py b/scripts/replay_demo.py
deleted file mode 100644
index 0275230..0000000
--- a/scripts/replay_demo.py
+++ /dev/null
@@ -1,175 +0,0 @@
-from isaacgym import gymapi
-from isaacgym import gymutil
-
-import math
-import numpy as np
-import matplotlib.pyplot as plt
-
-from pytransform3d import rotations
-
-from pathlib import Path
-import h5py
-from tqdm import tqdm
-import time
-import yaml
-import torch
-from torchvision.transforms import v2
-from sklearn.decomposition import PCA
-
-class Player:
- def __init__(self, dt=1/60):
- self.dt = dt
- self.head_mat = None
- self.left_wrist_mat = None
- self.right_wrist_mat = None
- self.left_hand_pos = None
- self.right_hand_pos = None
-
- # initialize gym
- self.gym = gymapi.acquire_gym()
-
- # configure sim
- sim_params = gymapi.SimParams()
- sim_params.dt = dt
- 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)
-
- robot_asset_root = "../assets"
- robot_asset_file = 'h1_inspire/urdf/h1_inspire.urdf'
- asset_options = gymapi.AssetOptions()
- asset_options.fix_base_link = True
- asset_options.default_dof_drive_mode = gymapi.DOF_MODE_POS
- robot_asset = self.gym.load_asset(self.sim, robot_asset_root, robot_asset_file, asset_options)
- dof = self.gym.get_asset_dof_count(robot_asset)
-
- # 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(17)
- self.env = self.gym.create_env(self.sim, env_lower, env_upper, num_per_row)
-
- # robot
- pose = gymapi.Transform()
- pose.p = gymapi.Vec3(-0.8, 0, 1.1)
- pose.r = gymapi.Quat(0, 0, 0, 1)
- self.robot_handle = self.gym.create_actor(self.env, robot_asset, pose, 'robot', 1, 1)
- self.gym.set_actor_dof_states(self.env, self.robot_handle, np.zeros(dof, gymapi.DofState.dtype),
- gymapi.STATE_ALL)
-
- # 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)
-
- plt.figure(figsize=(12, 6))
- plt.ion()
-
- def step(self, action, left_img, right_img):
- qpos = self.convert_h1_qpos(action)
- states = np.zeros(qpos.shape, dtype=gymapi.DofState.dtype)
- states['pos'] = qpos
- self.gym.set_actor_dof_states(self.env, self.robot_handle, states, gymapi.STATE_POS)
-
- # step the physics
- self.gym.simulate(self.sim)
- self.gym.step_graphics(self.sim)
-
- left_img = left_img.transpose((1, 2, 0))
- right_img = right_img.transpose((1, 2, 0))
- img = np.concatenate((left_img, right_img), axis=1)
-
- plt.cla()
- plt.title('VisionPro View')
- plt.imshow(img, aspect='equal')
- plt.pause(0.001)
-
- self.gym.draw_viewer(self.viewer, self.sim, True)
- self.gym.sync_frame_time(self.sim)
-
- def end(self):
- self.gym.destroy_viewer(self.viewer)
- self.gym.destroy_sim(self.sim)
- plt.close()
-
- def convert_h1_qpos(self, action):
- '''
- left_arm_indices = [13, 14, 15, 16, 17, 18, 19]
- right_arm_indices = [32, 33, 34, 35, 36, 37, 38]
- left_hand_indices = [20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31]
- right_hand_indices = [39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50]
- '''
- qpos = np.zeros(51)
- qpos[13:20] = action[0:7]
-
- # left hand actions
- qpos[20:22] = action[7]
- qpos[22:24] = action[8]
- qpos[24:26] = action[9]
- qpos[26:28] = action[10]
- qpos[28] = action[11]
- qpos[29:32] = action[12] * np.array([1, 1.6, 2.4])
-
- qpos[32:39] = action[13:20]
-
- # right hand actions
- qpos[39:41] = action[20]
- qpos[41:43] = action[21]
- qpos[43:45] = action[22]
- qpos[45:47] = action[23]
- qpos[47] = action[24]
- qpos[48:51] = action[25] * np.array([1, 1.6, 2.4])
-
- return qpos
-
-if __name__ == '__main__':
-
- root = "../data/recordings/"
- # folder_name = "00-coke_can_insert-2024_05_26-23_50_58/processed"
- folder_name = "00-can-sorting/processed"
- episode_name = "processed_episode_0.hdf5"
- episode_path = Path(root) / folder_name / episode_name
-
- data = h5py.File(str(episode_path), 'r')
- actions = np.array(data['qpos_action'])[::2]
- left_imgs = np.array(data['observation.image.left'])[::2] # 30hz
- right_imgs = np.array(data['observation.image.right'])[::2]
- data.close()
-
- timestamps = actions.shape[0]
-
- player = Player(1/30)
-
- try:
- for t in tqdm(range(timestamps)):
- player.step(actions[t], left_imgs[t, :], right_imgs[t, :])
- except KeyboardInterrupt:
- player.end()
- exit()
diff --git a/teleop/Preprocessor.py b/teleop/Preprocessor.py
deleted file mode 100644
index 3376d1d..0000000
--- a/teleop/Preprocessor.py
+++ /dev/null
@@ -1,146 +0,0 @@
-import math
-import numpy as np
-
-from constants_vuer import grd_yup2grd_zup, hand2inspire_l_arm, hand2inspire_r_arm,hand2inspire_l_finger,hand2inspire_r_finger,hand2inspire
-from motion_utils import mat_update, fast_mat_inv
-
-
-class VuerPreprocessor:
- def __init__(self):
- self.vuer_head_mat = np.array([[1, 0, 0, 0],
- [0, 1, 0, 1.5],
- [0, 0, 1, -0.2],
- [0, 0, 0, 1]])
- self.vuer_right_wrist_mat = np.array([[1, 0, 0, 0.5],
- [0, 1, 0, 1],
- [0, 0, 1, -0.5],
- [0, 0, 0, 1]])
- self.vuer_left_wrist_mat = np.array([[1, 0, 0, -0.5],
- [0, 1, 0, 1],
- [0, 0, 1, -0.5],
- [0, 0, 0, 1]])
-
- def process(self, tv):
- self.vuer_head_mat = mat_update(self.vuer_head_mat, tv.head_matrix.copy())
- self.vuer_right_wrist_mat = mat_update(self.vuer_right_wrist_mat, tv.right_hand.copy())
- self.vuer_left_wrist_mat = mat_update(self.vuer_left_wrist_mat, tv.left_hand.copy())
-
- # change of basis
- head_mat = grd_yup2grd_zup @ self.vuer_head_mat @ fast_mat_inv(grd_yup2grd_zup)
- right_wrist_mat = grd_yup2grd_zup @ self.vuer_right_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
- left_wrist_mat = grd_yup2grd_zup @ self.vuer_left_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
-
- rel_left_wrist_mat = left_wrist_mat @ hand2inspire_l_arm
- rel_left_wrist_mat[0:3, 3] = rel_left_wrist_mat[0:3, 3] - head_mat[0:3, 3]
-
- rel_right_wrist_mat = right_wrist_mat @ hand2inspire_r_arm # wTr = wTh @ hTr
- rel_right_wrist_mat[0:3, 3] = rel_right_wrist_mat[0:3, 3] - head_mat[0:3, 3]
-
- # homogeneous
- left_fingers = np.concatenate([tv.left_landmarks.copy().T, np.ones((1, tv.left_landmarks.shape[0]))])
- right_fingers = np.concatenate([tv.right_landmarks.copy().T, np.ones((1, tv.right_landmarks.shape[0]))])
-
- # change of basis
- left_fingers = grd_yup2grd_zup @ left_fingers
- right_fingers = grd_yup2grd_zup @ right_fingers
-
- rel_left_fingers = fast_mat_inv(left_wrist_mat) @ left_fingers
- rel_right_fingers = fast_mat_inv(right_wrist_mat) @ right_fingers
- rel_left_fingers = (hand2inspire_l_finger.T @ rel_left_fingers)[0:3, :].T
- rel_right_fingers = (hand2inspire_r_finger.T @ rel_right_fingers)[0:3, :].T
-
- return head_mat, rel_left_wrist_mat, rel_right_wrist_mat, rel_left_fingers, rel_right_fingers
-
- def get_hand_gesture(self, tv):
- self.vuer_right_wrist_mat = mat_update(self.vuer_right_wrist_mat, tv.right_hand.copy())
- self.vuer_left_wrist_mat = mat_update(self.vuer_left_wrist_mat, tv.left_hand.copy())
-
- # change of basis
- right_wrist_mat = grd_yup2grd_zup @ self.vuer_right_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
- left_wrist_mat = grd_yup2grd_zup @ self.vuer_left_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
-
- left_fingers = np.concatenate([tv.left_landmarks.copy().T, np.ones((1, tv.left_landmarks.shape[0]))])
- right_fingers = np.concatenate([tv.right_landmarks.copy().T, np.ones((1, tv.right_landmarks.shape[0]))])
-
- # change of basis
- left_fingers = grd_yup2grd_zup @ left_fingers
- right_fingers = grd_yup2grd_zup @ right_fingers
-
- rel_left_fingers = fast_mat_inv(left_wrist_mat) @ left_fingers
- rel_right_fingers = fast_mat_inv(right_wrist_mat) @ right_fingers
- rel_left_fingers = (hand2inspire_l_finger.T @ rel_left_fingers)[0:3, :].T
- rel_right_fingers = (hand2inspire_r_finger.T @ rel_right_fingers)[0:3, :].T
- all_fingers = np.concatenate([rel_left_fingers, rel_right_fingers], axis=0)
-
- return all_fingers
-
-
-class VuerPreprocessorLegacy:
- def __init__(self):
- self.vuer_head_mat = np.array([[1, 0, 0, 0],
- [0, 1, 0, 1.5],
- [0, 0, 1, -0.2],
- [0, 0, 0, 1]])
- self.vuer_right_wrist_mat = np.array([[1, 0, 0, 0.5],
- [0, 1, 0, 1],
- [0, 0, 1, -0.5],
- [0, 0, 0, 1]])
- self.vuer_left_wrist_mat = np.array([[1, 0, 0, -0.5],
- [0, 1, 0, 1],
- [0, 0, 1, -0.5],
- [0, 0, 0, 1]])
-
- def process(self, tv):
- self.vuer_head_mat = mat_update(self.vuer_head_mat, tv.head_matrix.copy())
- self.vuer_right_wrist_mat = mat_update(self.vuer_right_wrist_mat, tv.right_hand.copy())
- self.vuer_left_wrist_mat = mat_update(self.vuer_left_wrist_mat, tv.left_hand.copy())
-
- # change of basis
- head_mat = grd_yup2grd_zup @ self.vuer_head_mat @ fast_mat_inv(grd_yup2grd_zup)
- right_wrist_mat = grd_yup2grd_zup @ self.vuer_right_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
- left_wrist_mat = grd_yup2grd_zup @ self.vuer_left_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
-
- rel_left_wrist_mat = left_wrist_mat @ hand2inspire
- rel_left_wrist_mat[0:3, 3] = rel_left_wrist_mat[0:3, 3] - head_mat[0:3, 3]
-
- rel_right_wrist_mat = right_wrist_mat @ hand2inspire # wTr = wTh @ hTr
- rel_right_wrist_mat[0:3, 3] = rel_right_wrist_mat[0:3, 3] - head_mat[0:3, 3]
-
- # homogeneous
- left_fingers = np.concatenate([tv.left_landmarks.copy().T, np.ones((1, tv.left_landmarks.shape[0]))])
- right_fingers = np.concatenate([tv.right_landmarks.copy().T, np.ones((1, tv.right_landmarks.shape[0]))])
-
- # change of basis
- left_fingers = grd_yup2grd_zup @ left_fingers
- right_fingers = grd_yup2grd_zup @ right_fingers
-
- rel_left_fingers = fast_mat_inv(left_wrist_mat) @ left_fingers
- rel_right_fingers = fast_mat_inv(right_wrist_mat) @ right_fingers
- rel_left_fingers = (hand2inspire.T @ rel_left_fingers)[0:3, :].T
- rel_right_fingers = (hand2inspire.T @ rel_right_fingers)[0:3, :].T
-
- return head_mat, rel_left_wrist_mat, rel_right_wrist_mat, rel_left_fingers, rel_right_fingers
-
- def get_hand_gesture(self, tv):
- self.vuer_right_wrist_mat = mat_update(self.vuer_right_wrist_mat, tv.right_hand.copy())
- self.vuer_left_wrist_mat = mat_update(self.vuer_left_wrist_mat, tv.left_hand.copy())
-
- # change of basis
- right_wrist_mat = grd_yup2grd_zup @ self.vuer_right_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
- left_wrist_mat = grd_yup2grd_zup @ self.vuer_left_wrist_mat @ fast_mat_inv(grd_yup2grd_zup)
-
- left_fingers = np.concatenate([tv.left_landmarks.copy().T, np.ones((1, tv.left_landmarks.shape[0]))])
- right_fingers = np.concatenate([tv.right_landmarks.copy().T, np.ones((1, tv.right_landmarks.shape[0]))])
-
- # change of basis
- left_fingers = grd_yup2grd_zup @ left_fingers
- right_fingers = grd_yup2grd_zup @ right_fingers
-
- rel_left_fingers = fast_mat_inv(left_wrist_mat) @ left_fingers
- rel_right_fingers = fast_mat_inv(right_wrist_mat) @ right_fingers
- rel_left_fingers = (hand2inspire.T @ rel_left_fingers)[0:3, :].T
- rel_right_fingers = (hand2inspire.T @ rel_right_fingers)[0:3, :].T
- all_fingers = np.concatenate([rel_left_fingers, rel_right_fingers], axis=0)
-
- return all_fingers
-
diff --git a/teleop/TeleVision.py b/teleop/TeleVision.py
deleted file mode 100644
index 76d90d0..0000000
--- a/teleop/TeleVision.py
+++ /dev/null
@@ -1,247 +0,0 @@
-import time
-from vuer import Vuer
-from vuer.events import ClientEvent
-from vuer.schemas import ImageBackground, group, Hands, WebRTCStereoVideoPlane, DefaultScene
-from multiprocessing import Array, Process, shared_memory, Queue, Manager, Event, Semaphore
-import numpy as np
-import asyncio
-from webrtc.zed_server import *
-
-class OpenTeleVision:
- def __init__(self, img_shape, shm_name, queue, toggle_streaming, stream_mode="image", cert_file="./cert.pem", key_file="./key.pem", ngrok=False):
- # self.app=Vuer()
- self.img_shape = (img_shape[0], 2*img_shape[1], 3)
- self.img_height, self.img_width = img_shape[:2]
-
- if ngrok:
- self.app = Vuer(host='0.0.0.0', queries=dict(grid=False), queue_len=3)
- else:
- self.app = Vuer(host='0.0.0.0', cert=cert_file, key=key_file, queries=dict(grid=False), queue_len=3)
-
- self.app.add_handler("HAND_MOVE")(self.on_hand_move)
- self.app.add_handler("CAMERA_MOVE")(self.on_cam_move)
- if stream_mode == "image":
- existing_shm = shared_memory.SharedMemory(name=shm_name)
- self.img_array = np.ndarray((self.img_shape[0], self.img_shape[1], 3), dtype=np.uint8, buffer=existing_shm.buf)
- self.app.spawn(start=False)(self.main_image)
- elif stream_mode == "webrtc":
- self.app.spawn(start=False)(self.main_webrtc)
- else:
- raise ValueError("stream_mode must be either 'webrtc' or 'image'")
-
- self.left_hand_shared = Array('d', 16, lock=True)
- self.right_hand_shared = Array('d', 16, lock=True)
- self.left_landmarks_shared = Array('d', 75, lock=True)
- self.right_landmarks_shared = Array('d', 75, lock=True)
-
- self.head_matrix_shared = Array('d', 16, lock=True)
- self.aspect_shared = Value('d', 1.0, lock=True)
- if stream_mode == "webrtc":
- # webrtc server
- if Args.verbose:
- logging.basicConfig(level=logging.DEBUG)
- else:
- logging.basicConfig(level=logging.INFO)
- Args.img_shape = img_shape
- # Args.shm_name = shm_name
- Args.fps = 60
-
- ssl_context = ssl.SSLContext()
- ssl_context.load_cert_chain(cert_file, key_file)
-
- app = web.Application()
- cors = aiohttp_cors.setup(app, defaults={
- "*": aiohttp_cors.ResourceOptions(
- allow_credentials=True,
- expose_headers="*",
- allow_headers="*",
- allow_methods="*",
- )
- })
- rtc = RTC(img_shape, queue, toggle_streaming, 60)
- app.on_shutdown.append(on_shutdown)
- cors.add(app.router.add_get("/", index))
- cors.add(app.router.add_get("/client.js", javascript))
- cors.add(app.router.add_post("/offer", rtc.offer))
-
- self.webrtc_process = Process(target=web.run_app, args=(app,), kwargs={"host": "0.0.0.0", "port": 8080, "ssl_context": ssl_context})
- self.webrtc_process.daemon = True
- self.webrtc_process.start()
- # web.run_app(app, host="0.0.0.0", port=8080, ssl_context=ssl_context)
-
- self.process = Process(target=self.run)
- self.process.daemon = True
- self.process.start()
-
-
- def run(self):
- self.app.run()
-
- async def on_cam_move(self, event, session, fps=60):
- # only intercept the ego camera.
- # if event.key != "ego":
- # return
- try:
- # with self.head_matrix_shared.get_lock(): # Use the lock to ensure thread-safe updates
- # self.head_matrix_shared[:] = event.value["camera"]["matrix"]
- # with self.aspect_shared.get_lock():
- # self.aspect_shared.value = event.value['camera']['aspect']
- self.head_matrix_shared[:] = event.value["camera"]["matrix"]
- self.aspect_shared.value = event.value['camera']['aspect']
- except:
- pass
- # self.head_matrix = np.array(event.value["camera"]["matrix"]).reshape(4, 4, order="F")
- # print(np.array(event.value["camera"]["matrix"]).reshape(4, 4, order="F"))
- # print("camera moved", event.value["matrix"].shape, event.value["matrix"])
-
- async def on_hand_move(self, event, session, fps=60):
- try:
- # with self.left_hand_shared.get_lock(): # Use the lock to ensure thread-safe updates
- # self.left_hand_shared[:] = event.value["leftHand"]
- # with self.right_hand_shared.get_lock():
- # self.right_hand_shared[:] = event.value["rightHand"]
- # with self.left_landmarks_shared.get_lock():
- # self.left_landmarks_shared[:] = np.array(event.value["leftLandmarks"]).flatten()
- # with self.right_landmarks_shared.get_lock():
- # self.right_landmarks_shared[:] = np.array(event.value["rightLandmarks"]).flatten()
- self.left_hand_shared[:] = event.value["leftHand"]
- self.right_hand_shared[:] = event.value["rightHand"]
- self.left_landmarks_shared[:] = np.array(event.value["leftLandmarks"]).flatten()
- self.right_landmarks_shared[:] = np.array(event.value["rightLandmarks"]).flatten()
- except:
- pass
-
- async def main_webrtc(self, session, fps=60):
- session.set @ DefaultScene(frameloop="always")
- session.upsert @ Hands(fps=fps, stream=True, key="hands", showLeft=False, showRight=False)
- session.upsert @ WebRTCStereoVideoPlane(
- src="https://192.168.8.102:8080/offer",
- key="zed",
- aspect=1.33334,
- height = 8,
- position=[0, -2, -0.2],
- )
- while True:
- await asyncio.sleep(1)
-
- async def main_image(self, session, fps=60):
- session.upsert @ Hands(fps=fps, stream=True, key="hands", showLeft=False, showRight=False)
- while True:
- # aspect = self.aspect_shared.value
- display_image = self.img_array
-
- # session.upsert(
- # ImageBackground(
- # # Can scale the images down.
- # display_image[:self.img_height],
- # # 'jpg' encoding is significantly faster than 'png'.
- # format="jpeg",
- # quality=80,
- # key="left-image",
- # interpolate=True,
- # # fixed=True,
- # aspect=1.778,
- # distanceToCamera=2,
- # position=[0, -0.5, -2],
- # rotation=[0, 0, 0],
- # ),
- # to="bgChildren",
- # )
-
- session.upsert(
- [ImageBackground(
- # Can scale the images down.
- display_image[::2, :self.img_width],
- # display_image[:self.img_height:2, ::2],
- # 'jpg' encoding is significantly faster than 'png'.
- format="jpeg",
- quality=80,
- key="left-image",
- interpolate=True,
- # fixed=True,
- aspect=1.66667,
- # distanceToCamera=0.5,
- height = 8,
- position=[0, -1, 3],
- # rotation=[0, 0, 0],
- layers=1,
- alphaSrc="./vinette.jpg"
- ),
- ImageBackground(
- # Can scale the images down.
- display_image[::2, self.img_width:],
- # display_image[self.img_height::2, ::2],
- # 'jpg' encoding is significantly faster than 'png'.
- format="jpeg",
- quality=80,
- key="right-image",
- interpolate=True,
- # fixed=True,
- aspect=1.66667,
- # distanceToCamera=0.5,
- height = 8,
- position=[0, -1, 3],
- # rotation=[0, 0, 0],
- layers=2,
- alphaSrc="./vinette.jpg"
- )],
- to="bgChildren",
- )
- await asyncio.sleep(0.03)
-
- @property
- def left_hand(self):
- # with self.left_hand_shared.get_lock():
- # return np.array(self.left_hand_shared[:]).reshape(4, 4, order="F")
- return np.array(self.left_hand_shared[:]).reshape(4, 4, order="F")
-
-
- @property
- def right_hand(self):
- # with self.right_hand_shared.get_lock():
- # return np.array(self.right_hand_shared[:]).reshape(4, 4, order="F")
- return np.array(self.right_hand_shared[:]).reshape(4, 4, order="F")
-
-
- @property
- def left_landmarks(self):
- # with self.left_landmarks_shared.get_lock():
- # return np.array(self.left_landmarks_shared[:]).reshape(25, 3)
- return np.array(self.left_landmarks_shared[:]).reshape(25, 3)
-
- @property
- def right_landmarks(self):
- # with self.right_landmarks_shared.get_lock():
- # return np.array(self.right_landmarks_shared[:]).reshape(25, 3)
- return np.array(self.right_landmarks_shared[:]).reshape(25, 3)
-
- @property
- def head_matrix(self):
- # with self.head_matrix_shared.get_lock():
- # return np.array(self.head_matrix_shared[:]).reshape(4, 4, order="F")
- return np.array(self.head_matrix_shared[:]).reshape(4, 4, order="F")
-
- @property
- def aspect(self):
- # with self.aspect_shared.get_lock():
- # return float(self.aspect_shared.value)
- return float(self.aspect_shared.value)
-
-
-if __name__ == "__main__":
- resolution = (720, 1280)
- crop_size_w = 340 # (resolution[1] - resolution[0]) // 2
- crop_size_h = 270
- resolution_cropped = (resolution[0] - crop_size_h, resolution[1] - 2 * crop_size_w) # 450 * 600
- img_shape = (2 * resolution_cropped[0], resolution_cropped[1], 3) # 900 * 600
- img_height, img_width = resolution_cropped[:2] # 450 * 600
- shm = shared_memory.SharedMemory(create=True, size=np.prod(img_shape) * np.uint8().itemsize)
- shm_name = shm.name
- img_array = np.ndarray((img_shape[0], img_shape[1], 3), dtype=np.uint8, buffer=shm.buf)
-
- tv = OpenTeleVision(resolution_cropped, cert_file="../cert.pem", key_file="../key.pem")
- while True:
- # print(tv.left_landmarks)
- # print(tv.left_hand)
- # tv.modify_shared_image(random=True)
- time.sleep(1)
diff --git a/teleop/constants_vuer.py b/teleop/constants_vuer.py
deleted file mode 100644
index 7f03639..0000000
--- a/teleop/constants_vuer.py
+++ /dev/null
@@ -1,35 +0,0 @@
-import numpy as np
-
-tip_indices = [4, 9, 14, 19, 24]
-
-hand2inspire_l_arm = np.array([[1, 0, 0, 0],
- [0, 0, -1, 0],
- [0, 1, 0, 0],
- [0, 0, 0, 1]])
-
-hand2inspire_r_arm = np.array([[1, 0, 0, 0],
- [0, 0, 1, 0],
- [0, -1, 0, 0],
- [0, 0, 0, 1]])
-
-hand2inspire_l_finger = np.array([[0, -1, 0, 0],
- [0, 0, -1, 0],
- [1, 0, 0, 0],
- [0, 0, 0, 1]])
-
-hand2inspire_r_finger = np.array([[0, -1, 0, 0],
- [0, 0, -1, 0],
- [1, 0, 0, 0],
- [0, 0, 0, 1]])
-
-grd_yup2grd_zup = np.array([[0, 0, -1, 0],
- [-1, 0, 0, 0],
- [0, 1, 0, 0],
- [0, 0, 0, 1]])
-
-# legacy
-hand2inspire = np.array([[0, -1, 0, 0],
- [0, 0, -1, 0],
- [1, 0, 0, 0],
- [0, 0, 0, 1]])
-
diff --git a/teleop/dynamixel/active_cam.py b/teleop/dynamixel/active_cam.py
deleted file mode 100644
index 53c22cf..0000000
--- a/teleop/dynamixel/active_cam.py
+++ /dev/null
@@ -1,105 +0,0 @@
-import os
-import time
-from dataclasses import dataclass
-from typing import Dict, Optional, Sequence, Tuple
-import numpy as np
-from .agent import Agent
-from .dynamixel_robot import DynamixelRobot
-# from agent import Agent
-# from dynamixel_robot import DynamixelRobot
-
-
-@dataclass
-class DynamixelRobotConfig:
- joint_ids: Sequence[int]
- """The joint ids of dynamixel robot. Usually (1, 2, 3 ...)."""
-
- joint_offsets: Sequence[float]
- """The joint offsets of robot. There needs to be a joint offset for each joint_id and should be a multiple of pi/2."""
-
- joint_signs: Sequence[int]
- """The joint signs is -1 for all dynamixel"""
-
- gripper_config: Tuple[int, int, int]
- """reserved for later work"""
-
- # it will run after init and work as init check
- def __post_init__(self):
- assert len(self.joint_ids) == len(self.joint_offsets)
- assert len(self.joint_ids) == len(self.joint_signs)
-
- def make_robot(
- self, port: str = "/dev/ttyUSB0", start_joints: Optional[np.ndarray] = None
- ) -> DynamixelRobot:
- return DynamixelRobot(
- joint_ids=self.joint_ids,
- joint_offsets=list(self.joint_offsets),
- real=True,
- joint_signs=list(self.joint_signs),
- port=port,
- gripper_config=self.gripper_config,
- start_joints=start_joints,
- )
-
-# Can put multi robot into the dic, note that the calibration info shoule be put here
-PORT_CONFIG_MAP: Dict[str, DynamixelRobotConfig] = {
- #! for camera mounta
- "/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT8IT033-if00-port0": DynamixelRobotConfig(
- joint_ids=(1, 2),
- joint_offsets=(
- 2*np.pi/2,
- 2*np.pi/2,
- ),
- joint_signs=(-1, -1),
- gripper_config=None,
- ),
-
-}
-
-# general we only input port into the class, other info is stored in the dic
-class DynamixelAgent(Agent):
- def __init__(
- self,
- port: str,
- dynamixel_config: Optional[DynamixelRobotConfig] = None,
- start_joints: Optional[np.ndarray] = None,
- cap_num: int = 42,
- ):
- #! init dynamixel robot setting
- # use the config to make the robot
- if dynamixel_config is not None:
- self._robot = dynamixel_config.make_robot(
- port=port, start_joints=start_joints
- )
- # find the info auto
- else:
- # check port
- assert os.path.exists(port), port
- assert port in PORT_CONFIG_MAP, f"Port {port} not in config map"
-
- # use port to gain config
- config = PORT_CONFIG_MAP[port]
- self._robot = config.make_robot(port=port, start_joints=start_joints)
-
- def act(self, obs: Dict[str, np.ndarray]) -> np.ndarray:
- return self._robot.get_joint_state()
-
-if __name__ == "__main__":
- agent = DynamixelAgent(port="/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT8IST6E-if00-port0")
-
- agent._robot.set_torque_mode(True)
-
- min_radians = -1.57
- max_radians = 1.57
- interval = 0.1
-
- current_radian = 0
- while current_radian <= max_radians:
- action = agent.act(1)
- print("now action : ", [f"{x:.3f}" for x in action])
- command = [0, 0]
- agent._robot.command_joint_state([0, current_radian])
- time.sleep(0.1)
- true_value = agent._robot._driver.get_joints()
- print("true value : ", [f"{x:.3f}" for x in true_value])
- current_radian += interval
diff --git a/teleop/dynamixel/agent.py b/teleop/dynamixel/agent.py
deleted file mode 100644
index fa8bff7..0000000
--- a/teleop/dynamixel/agent.py
+++ /dev/null
@@ -1,42 +0,0 @@
-from typing import Any, Dict, Protocol
-
-import numpy as np
-
-class Agent(Protocol):
- def act(self, obs: Dict[str, Any]) -> np.ndarray:
- """Returns an action given an observation.
-
- Args:
- obs: observation from the environment.
-
- Returns:
- action: action to take on the environment.
- """
- raise NotImplementedError
-
-
-class DummyAgent(Agent):
- def __init__(self, num_dofs: int):
- self.num_dofs = num_dofs
-
- def act(self, obs: Dict[str, Any]) -> np.ndarray:
- return np.zeros(self.num_dofs)
-
-
-class BimanualAgent(Agent):
- def __init__(self, agent_left: Agent, agent_right: Agent):
- self.agent_left = agent_left
- self.agent_right = agent_right
-
- def act(self, obs: Dict[str, Any]) -> np.ndarray:
- left_obs = {}
- right_obs = {}
- for key, val in obs.items():
- L = val.shape[0]
- half_dim = L // 2
- assert L == half_dim * 2, f"{key} must be even, something is wrong"
- left_obs[key] = val[:half_dim]
- right_obs[key] = val[half_dim:]
- return np.concatenate(
- [self.agent_left.act(left_obs), self.agent_right.act(right_obs)]
- )
diff --git a/teleop/dynamixel/driver.py b/teleop/dynamixel/driver.py
deleted file mode 100644
index dc189c2..0000000
--- a/teleop/dynamixel/driver.py
+++ /dev/null
@@ -1,287 +0,0 @@
-import time
-from threading import Event, Lock, Thread
-from typing import Protocol, Sequence
-
-import numpy as np
-#! dynamixel_sdk
-from dynamixel_sdk.group_sync_read import GroupSyncRead
-from dynamixel_sdk.group_sync_write import GroupSyncWrite
-from dynamixel_sdk.packet_handler import PacketHandler
-from dynamixel_sdk.port_handler import PortHandler
-from dynamixel_sdk.robotis_def import (
- COMM_SUCCESS,
- DXL_HIBYTE,
- DXL_HIWORD,
- DXL_LOBYTE,
- DXL_LOWORD,
-)
-
-# Constants
-ADDR_TORQUE_ENABLE = 64
-ADDR_GOAL_POSITION = 116
-LEN_GOAL_POSITION = 4
-#! rewrite
-ADDR_PRESENT_POSITION = 132
-ADDR_PRESENT_POSITION = 140 #Position Trajectory(140)
-LEN_PRESENT_POSITION = 4
-TORQUE_ENABLE = 1
-TORQUE_DISABLE = 0
-
-
-class DynamixelDriverProtocol(Protocol):
- def set_joints(self, joint_angles: Sequence[float]):
- """Set the joint angles for the Dynamixel servos.
-
- Args:
- joint_angles (Sequence[float]): A list of joint angles.
- """
- ...
-
- def torque_enabled(self) -> bool:
- """Check if torque is enabled for the Dynamixel servos.
-
- Returns:
- bool: True if torque is enabled, False if it is disabled.
- """
- ...
-
- def set_torque_mode(self, enable: bool):
- """Set the torque mode for the Dynamixel servos.
-
- Args:
- enable (bool): True to enable torque, False to disable.
- """
- ...
-
- def get_joints(self) -> np.ndarray:
- """Get the current joint angles in radians.
-
- Returns:
- np.ndarray: An array of joint angles.
- """
- ...
-
- def close(self):
- """Close the driver."""
-
-
-class FakeDynamixelDriver(DynamixelDriverProtocol):
- def __init__(self, ids: Sequence[int]):
- self._ids = ids
- self._joint_angles = np.zeros(len(ids), dtype=int)
- self._torque_enabled = False
-
- def set_joints(self, joint_angles: Sequence[float]):
- if len(joint_angles) != len(self._ids):
- raise ValueError(
- "The length of joint_angles must match the number of servos"
- )
- if not self._torque_enabled:
- raise RuntimeError("Torque must be enabled to set joint angles")
- self._joint_angles = np.array(joint_angles)
-
- def torque_enabled(self) -> bool:
- return self._torque_enabled
-
- def set_torque_mode(self, enable: bool):
- self._torque_enabled = enable
-
- def get_joints(self) -> np.ndarray:
- return self._joint_angles.copy()
-
- def close(self):
- pass
-
-
-class DynamixelDriver(DynamixelDriverProtocol):
- def __init__(
- self, ids: Sequence[int], port: str = "/dev/ttyUSB0", baudrate: int = 57600
- ):
- """Initialize the DynamixelDriver class.
-
- Args:
- ids (Sequence[int]): A list of IDs for the Dynamixel servos.
- port (str): The USB port to connect to the arm.
- baudrate (int): The baudrate for communication.
- """
- self._ids = ids
- self._joint_angles = None
- #!
- self._lock = Lock()
-
- #! do not need to know the detail now
- # Initialize the port handler, packet handler, and group sync read/write
- self._portHandler = PortHandler(port)
- self._packetHandler = PacketHandler(2.0)
-
- self._groupSyncRead = GroupSyncRead(
- self._portHandler,
- self._packetHandler,
- ADDR_PRESENT_POSITION,
- LEN_PRESENT_POSITION,
- )
- self._groupSyncWrite = GroupSyncWrite(
- self._portHandler,
- self._packetHandler,
- ADDR_GOAL_POSITION,
- LEN_GOAL_POSITION,
- )
-
- # Open the port and set the baudrate
- if not self._portHandler.openPort():
- raise RuntimeError("Failed to open the port")
-
- if not self._portHandler.setBaudRate(baudrate):
- raise RuntimeError(f"Failed to change the baudrate, {baudrate}")
-
- # Add parameters for each Dynamixel servo to the group sync read
- for dxl_id in self._ids:
- if not self._groupSyncRead.addParam(dxl_id):
- raise RuntimeError(
- f"Failed to add parameter for Dynamixel with ID {dxl_id}"
- )
-
- # Disable torque for each Dynamixel servo
- self._torque_enabled = False
- try:
- self.set_torque_mode(self._torque_enabled)
- except Exception as e:
- print(f"port: {port}, {e}")
-
- # control the thread
- self._stop_thread = Event()
-
- self._start_reading_thread()
-
- def set_joints(self, joint_angles: Sequence[float]):
- if len(joint_angles) != len(self._ids):
- raise ValueError(
- "The length of joint_angles must match the number of servos"
- )
- if not self._torque_enabled:
- raise RuntimeError("Torque must be enabled to set joint angles")
-
- for dxl_id, angle in zip(self._ids, joint_angles):
- # Convert the angle to the appropriate value for the servo
- position_value = int(angle * 2048 / np.pi)
-
- # Allocate goal position value into byte array
- param_goal_position = [
- DXL_LOBYTE(DXL_LOWORD(position_value)),
- DXL_HIBYTE(DXL_LOWORD(position_value)),
- DXL_LOBYTE(DXL_HIWORD(position_value)),
- DXL_HIBYTE(DXL_HIWORD(position_value)),
- ]
-
- # Add goal position value to the Syncwrite parameter storage
- dxl_addparam_result = self._groupSyncWrite.addParam(
- dxl_id, param_goal_position
- )
- if not dxl_addparam_result:
- raise RuntimeError(
- f"Failed to set joint angle for Dynamixel with ID {dxl_id}"
- )
-
- # Syncwrite goal position
- dxl_comm_result = self._groupSyncWrite.txPacket()
- if dxl_comm_result != COMM_SUCCESS:
- raise RuntimeError("Failed to syncwrite goal position")
-
- # Clear syncwrite parameter storage
- self._groupSyncWrite.clearParam()
-
- def torque_enabled(self) -> bool:
- return self._torque_enabled
-
- def set_torque_mode(self, enable: bool):
- torque_value = TORQUE_ENABLE if enable else TORQUE_DISABLE
- with self._lock:
- for dxl_id in self._ids:
- dxl_comm_result, dxl_error = self._packetHandler.write1ByteTxRx(
- self._portHandler, dxl_id, ADDR_TORQUE_ENABLE, torque_value
- )
- if dxl_comm_result != COMM_SUCCESS or dxl_error != 0:
- print(dxl_comm_result)
- print(dxl_error)
- raise RuntimeError(
- f"Failed to set torque mode for Dynamixel with ID {dxl_id}"
- )
-
- self._torque_enabled = enable
-
- def _start_reading_thread(self):
- self._reading_thread = Thread(target=self._read_joint_angles)
- # self._reading_thread.daemon = True
- # self._reading_thread.start()
-
- def _read_joint_angles(self):
- # Continuously read joint angles and update the joint_angles array
- while not self._stop_thread.is_set():
- time.sleep(0.001)
- with self._lock:
- _joint_angles = np.zeros(len(self._ids), dtype=int)
- dxl_comm_result = self._groupSyncRead.txRxPacket()
- if dxl_comm_result != COMM_SUCCESS:
- print(f"warning, comm failed: {dxl_comm_result}")
- continue
- for i, dxl_id in enumerate(self._ids):
- if self._groupSyncRead.isAvailable(
- dxl_id, ADDR_PRESENT_POSITION, LEN_PRESENT_POSITION
- ):
- angle = self._groupSyncRead.getData(
- dxl_id, ADDR_PRESENT_POSITION, LEN_PRESENT_POSITION
- )
- angle = np.int32(np.uint32(angle))
- _joint_angles[i] = angle
- else:
- raise RuntimeError(
- f"Failed to get joint angles for Dynamixel with ID {dxl_id}"
- )
- self._joint_angles = _joint_angles
- # self._groupSyncRead.clearParam() # TODO what does this do? should i add it
-
- def get_joints(self) -> np.ndarray:
- # Return a copy of the joint_angles array to avoid race conditions
- while self._joint_angles is None:
- time.sleep(0.1)
- with self._lock:
- _j = self._joint_angles.copy()
- return _j / 2048.0 * np.pi
-
- def close(self):
- self._stop_thread.set()
- self._reading_thread.join()
- self._portHandler.closePort()
-
-
-def main():
- # Set the port, baudrate, and servo IDs
- ids = [1,2]
-
- # Create a DynamixelDriver instance
- try:
- driver = DynamixelDriver(ids)
- except FileNotFoundError:
- driver = DynamixelDriver(ids, port="/dev/cu.usbserial-FT7WBMUB")
-
- driver.set_torque_mode(True)
- driver.set_torque_mode(False)
-
- # Print the joint angles
- try:
- while True:
- joint_angles = driver.get_joints()
- print(f"Joint angles for IDs {ids}: {joint_angles}")
- # print(f"Joint angles for IDs {ids[1]}: {joint_angles[1]}")
- except KeyboardInterrupt:
- driver.close()
-
- # driver.set_torque_mode(True)
- # joint_angles = driver.get_joints()
- # print(f"Joint angles for IDs {ids}: {joint_angles}")
- # driver.set_joints([6, 6])
- # driver.set_joints([7, 8])
-
-
-if __name__ == "__main__":
- main()
diff --git a/teleop/dynamixel/dynamixel_robot.py b/teleop/dynamixel/dynamixel_robot.py
deleted file mode 100644
index 5f5dddd..0000000
--- a/teleop/dynamixel/dynamixel_robot.py
+++ /dev/null
@@ -1,161 +0,0 @@
-from typing import Dict, Optional, Sequence, Tuple
-
-import numpy as np
-
-# from robots.robot import Robot
-import sys
-from .robot import Robot
-from .driver import DynamixelDriver,DynamixelDriverProtocol,FakeDynamixelDriver
-# from robot import Robot
-# from driver import DynamixelDriver,DynamixelDriverProtocol,FakeDynamixelDriver
-
-
-class DynamixelRobot(Robot):
- """A class representing a UR robot."""
-
- def __init__(
- self,
- joint_ids: Sequence[int],
- joint_offsets: Optional[Sequence[float]] = None,
- joint_signs: Optional[Sequence[int]] = None,
- real: bool = False,
- port: str = "/dev/ttyUSB0",
- baudrate: int = 57600,
- gripper_config: Optional[Tuple[int, float, float]] = None,
- start_joints: Optional[np.ndarray] = None,
- ):
-
-
- print(f"attempting to connect to port: {port}")
-
- # used to set gripper, reserved for later
- self.gripper_open_close: Optional[Tuple[float, float]]
-
- if gripper_config is not None:
- assert joint_offsets is not None
- assert joint_signs is not None
-
- joint_ids = tuple(joint_ids) + (gripper_config[0],)
- joint_offsets = tuple(joint_offsets) + (0.0,)
- joint_signs = tuple(joint_signs) + (1,)
- self.gripper_open_close = (
- gripper_config[1] * np.pi / 180,
- gripper_config[2] * np.pi / 180,
- )
- else:
- self.gripper_open_close = None
-
- # all the self variable will start with _
-
- # set joint config
- self._joint_ids = joint_ids
- self._driver: DynamixelDriverProtocol
-
- if joint_offsets is None:
- self._joint_offsets = np.zeros(len(joint_ids))
- else:
- self._joint_offsets = np.array(joint_offsets)
-
- if joint_signs is None:
- self._joint_signs = np.ones(len(joint_ids))
- else:
- self._joint_signs = np.array(joint_signs)
-
- # check
- assert len(self._joint_ids) == len(self._joint_offsets), (
- f"joint_ids: {len(self._joint_ids)}, "
- f"joint_offsets: {len(self._joint_offsets)}"
- )
- assert len(self._joint_ids) == len(self._joint_signs), (
- f"joint_ids: {len(self._joint_ids)}, "
- f"joint_signs: {len(self._joint_signs)}"
- )
- assert np.all(
- np.abs(self._joint_signs) == 1
- ), f"joint_signs: {self._joint_signs}"
-
- # when called in gello_agent, real == True, used to do test
- if real:
- self._driver = DynamixelDriver(joint_ids, port=port, baudrate=baudrate)
- # we dault set the torque_mode(False)
- self._driver.set_torque_mode(False)
- else:
- self._driver = FakeDynamixelDriver(joint_ids)
-
- self._torque_on = False
- self._last_pos = None
- self._alpha = 0.99
-
- #! this part might important! need to check if the robot start at different joints
- if start_joints is not None:
- # loop through all joints and add +- 2pi to the joint offsets to get the closest to start joints
- new_joint_offsets = []
- current_joints = self.get_joint_state()
- assert current_joints.shape == start_joints.shape
-
- if gripper_config is not None:
- current_joints = current_joints[:-1]
- start_joints = start_joints[:-1]
-
- for c_joint, s_joint, joint_offset in zip(
- current_joints, start_joints, self._joint_offsets
- ):
- new_joint_offsets.append(
- np.pi * 2 * np.round((s_joint - c_joint) / (2 * np.pi))
- + joint_offset
- )
-
- if gripper_config is not None:
- new_joint_offsets.append(self._joint_offsets[-1])
- self._joint_offsets = np.array(new_joint_offsets)
-
-
- #! might change to @property
- def num_dofs(self) -> int:
- return len(self._joint_ids)
-
- #! now the joint num is different
- def get_joint_state(self) -> np.ndarray:
- pos = (self._driver.get_joints() - self._joint_offsets) * self._joint_signs
- assert len(pos) == self.num_dofs()
-
- if self.gripper_open_close is not None:
- # map pos to [0, 1]
- g_pos = (pos[-1] - self.gripper_open_close[0]) / (
- self.gripper_open_close[1] - self.gripper_open_close[0]
- )
- g_pos = min(max(0, g_pos), 1)
- pos[-1] = g_pos
-
- if self._last_pos is None:
- self._last_pos = pos
- else:
- # exponential smoothing
- pos = self._last_pos * (1 - self._alpha) + pos * self._alpha
- self._last_pos = pos
-
- new_pos = np.append(pos, 0)
- return new_pos
-
- def map_to_valid_range(self, radians_array):
- mapped_radians = np.mod(radians_array, 2 * np.pi)
- return mapped_radians
-
- def command_joint_state(self, joint_state: np.ndarray) -> None:
- # print("command : ", [f"{x:.3f}" for x in joint_state])
- set_value = (joint_state + self._joint_offsets).tolist()
- # print("_set value : ", [f"{x:.3f}" for x in set_value])
- set_value = self.map_to_valid_range(set_value)
- # print("set value : ", [f"{x:.3f}" for x in set_value])
- self._driver.set_joints(set_value)
-
- def set_torque_mode(self, mode: bool):
- if mode == self._torque_on:
- return
- self._driver.set_torque_mode(mode)
- self._torque_on = mode
-
- def get_observations(self) -> Dict[str, np.ndarray]:
- return {"joint_state": self.get_joint_state()}
-
-
diff --git a/teleop/dynamixel/robot.py b/teleop/dynamixel/robot.py
deleted file mode 100644
index b4a6e96..0000000
--- a/teleop/dynamixel/robot.py
+++ /dev/null
@@ -1,128 +0,0 @@
-from abc import abstractmethod
-from typing import Dict, Protocol
-
-import numpy as np
-
-
-class Robot(Protocol):
- """Robot protocol.
-
- A protocol for a robot that can be controlled.
- """
-
- @abstractmethod
- def num_dofs(self) -> int:
- """Get the number of joints of the robot.
-
- Returns:
- int: The number of joints of the robot.
- """
- raise NotImplementedError
-
- @abstractmethod
- def get_joint_state(self) -> np.ndarray:
- """Get the current state of the leader robot.
-
- Returns:
- T: The current state of the leader robot.
- """
- raise NotImplementedError
-
- @abstractmethod
- def command_joint_state(self, joint_state: np.ndarray) -> None:
- """Command the leader robot to a given state.
-
- Args:
- joint_state (np.ndarray): The state to command the leader robot to.
- """
- raise NotImplementedError
-
- @abstractmethod
- def get_observations(self) -> Dict[str, np.ndarray]:
- """Get the current observations of the robot.
-
- This is to extract all the information that is available from the robot,
- such as joint positions, joint velocities, etc. This may also include
- information from additional sensors, such as cameras, force sensors, etc.
-
- Returns:
- Dict[str, np.ndarray]: A dictionary of observations.
- """
- raise NotImplementedError
-
-
-class PrintRobot(Robot):
- """A robot that prints the commanded joint state."""
-
- def __init__(self, num_dofs: int, dont_print: bool = False):
- self._num_dofs = num_dofs
- self._joint_state = np.zeros(num_dofs)
- self._dont_print = dont_print
-
- def num_dofs(self) -> int:
- return self._num_dofs
-
- def get_joint_state(self) -> np.ndarray:
- return self._joint_state
-
- def command_joint_state(self, joint_state: np.ndarray) -> None:
- assert len(joint_state) == (self._num_dofs), (
- f"Expected joint state of length {self._num_dofs}, "
- f"got {len(joint_state)}."
- )
- self._joint_state = joint_state
- if not self._dont_print:
- print(self._joint_state)
-
- def get_observations(self) -> Dict[str, np.ndarray]:
- joint_state = self.get_joint_state()
- pos_quat = np.zeros(7)
- return {
- "joint_positions": joint_state,
- "joint_velocities": joint_state,
- "ee_pos_quat": pos_quat,
- "gripper_position": np.array(0),
- }
-
-
-class BimanualRobot(Robot):
- def __init__(self, robot_l: Robot, robot_r: Robot):
- self._robot_l = robot_l
- self._robot_r = robot_r
-
- def num_dofs(self) -> int:
- return self._robot_l.num_dofs() + self._robot_r.num_dofs()
-
- def get_joint_state(self) -> np.ndarray:
- return np.concatenate(
- (self._robot_l.get_joint_state(), self._robot_r.get_joint_state())
- )
-
- def command_joint_state(self, joint_state: np.ndarray) -> None:
- self._robot_l.command_joint_state(joint_state[: self._robot_l.num_dofs()])
- self._robot_r.command_joint_state(joint_state[self._robot_l.num_dofs() :])
-
- def get_observations(self) -> Dict[str, np.ndarray]:
- l_obs = self._robot_l.get_observations()
- r_obs = self._robot_r.get_observations()
- assert l_obs.keys() == r_obs.keys()
- return_obs = {}
- for k in l_obs.keys():
- try:
- return_obs[k] = np.concatenate((l_obs[k], r_obs[k]))
- except Exception as e:
- print(e)
- print(k)
- print(l_obs[k])
- print(r_obs[k])
- raise RuntimeError()
-
- return return_obs
-
-
-def main():
- pass
-
-
-if __name__ == "__main__":
- main()
diff --git a/teleop/image_server/image_client.py b/teleop/image_server/image_client.py
index 55ae572..45e4375 100644
--- a/teleop/image_server/image_client.py
+++ b/teleop/image_server/image_client.py
@@ -1,42 +1,154 @@
import cv2
import zmq
-import pickle
-import zlib
+import numpy as np
+import time
+import struct
+from collections import deque
+from multiprocessing import shared_memory
-def start_client():
- # set ZeroMQ context and socket
- context = zmq.Context()
- socket = context.socket(zmq.PULL)
- socket.connect("tcp://192.168.123.162:5555")
- print("The client is connected and waiting to receive data...")
+class ImageClient:
+ def __init__(self, img_shape = None, img_shm_name = None, image_show = False, server_address = "192.168.123.164", port = 5555, Unit_Test = False):
+ self.running = True
+ self._image_show = image_show
+ self._server_address = server_address
+ self._port = port
- while True:
- try:
- compressed_data = b''
- while True:
- chunk = socket.recv()
- compressed_data += chunk
- if len(chunk) < 60000:
- break
+ self.enable_shm = False
+ if img_shape is not None and img_shm_name is not None:
+ self._image_shm = shared_memory.SharedMemory(name=img_shm_name)
+ self._img_array = np.ndarray(img_shape, dtype = np.uint8, buffer = self._image_shm.buf)
+ self.enable_shm = True
+
+ # Performance evaluation parameters
+ self._enable_performance_eval = Unit_Test
+ if self._enable_performance_eval:
+ self._init_performance_metrics()
+
+ def _init_performance_metrics(self):
+ self._frame_count = 0 # Total frames received
+ self._last_frame_id = -1 # Last received frame ID
+
+ # Real-time FPS calculation using a time window
+ self._time_window = 1.0 # Time window size (in seconds)
+ self._frame_times = deque() # Timestamps of frames received within the time window
+
+ # Data transmission quality metrics
+ self._latencies = deque() # Latencies of frames within the time window
+ self._lost_frames = 0 # Total lost frames
+ self._total_frames = 0 # Expected total frames based on frame IDs
+
+ def _update_performance_metrics(self, timestamp, frame_id, receive_time):
+ # Update latency
+ latency = receive_time - timestamp
+ self._latencies.append(latency)
+
+ # Remove latencies outside the time window
+ while self._latencies and self._frame_times and self._latencies[0] < receive_time - self._time_window:
+ self._latencies.popleft()
+
+ # Update frame times
+ self._frame_times.append(receive_time)
+ # Remove timestamps outside the time window
+ while self._frame_times and self._frame_times[0] < receive_time - self._time_window:
+ self._frame_times.popleft()
- data = zlib.decompress(compressed_data)
- frame_data = pickle.loads(data)
+ # Update frame counts for lost frame calculation
+ expected_frame_id = self._last_frame_id + 1 if self._last_frame_id != -1 else frame_id
+ if frame_id != expected_frame_id:
+ lost = frame_id - expected_frame_id
+ if lost < 0:
+ print(f"[Image Client] Received out-of-order frame ID: {frame_id}")
+ else:
+ self._lost_frames += lost
+ print(f"[Image Client] Detected lost frames: {lost}, Expected frame ID: {expected_frame_id}, Received frame ID: {frame_id}")
+ self._last_frame_id = frame_id
+ self._total_frames = frame_id + 1
+
+ self._frame_count += 1
+
+ def _print_performance_metrics(self, receive_time):
+ if self._frame_count % 30 == 0:
+ # Calculate real-time FPS
+ real_time_fps = len(self._frame_times) / self._time_window if self._time_window > 0 else 0
+
+ # Calculate latency metrics
+ if self._latencies:
+ avg_latency = sum(self._latencies) / len(self._latencies)
+ max_latency = max(self._latencies)
+ min_latency = min(self._latencies)
+ jitter = max_latency - min_latency
+ else:
+ avg_latency = max_latency = min_latency = jitter = 0
+
+ # Calculate lost frame rate
+ lost_frame_rate = (self._lost_frames / self._total_frames) * 100 if self._total_frames > 0 else 0
+
+ print(f"[Image Client] Real-time FPS: {real_time_fps:.2f}, Avg Latency: {avg_latency*1000:.2f} ms, Max Latency: {max_latency*1000:.2f} ms, \
+ Min Latency: {min_latency*1000:.2f} ms, Jitter: {jitter*1000:.2f} ms, Lost Frame Rate: {lost_frame_rate:.2f}%")
+
+ def _close(self):
+ self._socket.close()
+ self._context.term()
+ if self._image_show:
+ cv2.destroyAllWindows()
+ print("Image client has been closed.")
+
+
+ def receive_process(self):
+ # Set up ZeroMQ context and socket
+ self._context = zmq.Context()
+ self._socket = self._context.socket(zmq.SUB)
+ self._socket.connect(f"tcp://{self._server_address}:{self._port}")
+ self._socket.setsockopt_string(zmq.SUBSCRIBE, "")
+
+ print("\nImage client has started, waiting to receive data...")
+ try:
+ while self.running:
+ # Receive message
+ message = self._socket.recv()
+ receive_time = time.time()
- # decode and display the image
- frame = cv2.imdecode(frame_data, cv2.IMREAD_COLOR)
+ if self._enable_performance_eval:
+ header_size = struct.calcsize('dI')
+ try:
+ # Attempt to extract header and image data
+ header = message[:header_size]
+ jpg_bytes = message[header_size:]
+ timestamp, frame_id = struct.unpack('dI', header)
+ except struct.error as e:
+ print(f"[Image Client] Error unpacking header: {e}, discarding message.")
+ continue
+ else:
+ # No header, entire message is image data
+ jpg_bytes = message
+ # Decode image
+ np_img = np.frombuffer(jpg_bytes, dtype=np.uint8)
+ current_image = cv2.imdecode(np_img, cv2.IMREAD_COLOR)
+ if current_image is None:
+ print("[Image Client] Failed to decode image.")
+ continue
- # convert BGR to RGB
- frame_rgb = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)
+ if self.enable_shm:
+ np.copyto(self._img_array, np.array(current_image))
+
+ if self._image_show:
+ cv2.imshow('Image Client Stream', current_image)
+ if cv2.waitKey(1) & 0xFF == ord('q'):
+ self.running = False
- cv2.imshow('Video Stream', frame_rgb)
+ if self._enable_performance_eval:
+ self._update_performance_metrics(timestamp, frame_id, receive_time)
+ self._print_performance_metrics(receive_time)
- if cv2.waitKey(1) & 0xFF == ord('q'):
- break
+ except KeyboardInterrupt:
+ print("Image client interrupted by user.")
except Exception as e:
- print(f"An error occurred while receiving data: {e}")
- break
- context.term()
- cv2.destroyAllWindows()
+ print(f"[Image Client] An error occurred while receiving data: {e}")
+ finally:
+ self._close()
if __name__ == "__main__":
- start_client()
+ # Initialize the client with performance evaluation enabled
+ # client = ImageClient(image_show = True, server_address='127.0.0.1', Unit_Test=True) # local test
+ client = ImageClient(image_show = True, server_address='192.168.123.164', Unit_Test=False) # deployment test
+ client.receive_process()
\ No newline at end of file
diff --git a/teleop/image_server/image_server.py b/teleop/image_server/image_server.py
index 0f5fb9b..6723b23 100644
--- a/teleop/image_server/image_server.py
+++ b/teleop/image_server/image_server.py
@@ -1,48 +1,96 @@
import cv2
import zmq
-import pickle
-import zlib
-
-def start_server():
- # camera init
- cap = cv2.VideoCapture(0, cv2.CAP_V4L2)
- cap.set(cv2.CAP_PROP_FOURCC, cv2.VideoWriter.fourcc('M', 'J', 'P', 'G'))
- cap.set(cv2.CAP_PROP_FRAME_WIDTH, 2560)
- cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 720)
- cap.set(cv2.CAP_PROP_FPS, 30)
-
- # set ZeroMQ context and socket
- context = zmq.Context()
- socket = context.socket(zmq.PUSH)
- socket.setsockopt(zmq.SNDHWM, 1)
- socket.bind("tcp://*:5555")
- print("The server has started, waiting for client connections...")
-
- while True:
- ret, frame = cap.read()
- if not ret:
- print("frame read is error")
- break
-
- # encoding image
- ret2, frame = cv2.imencode('.jpg', frame)
- if not ret2:
- continue
-
- # Compressing data using pickle and zlib
- data = pickle.dumps(frame)
- compressed_data = zlib.compress(data)
-
- # sending data in pieces
- chunk_size = 60000
- num_chunks = len(compressed_data) // chunk_size + 1
- for i in range(num_chunks):
- start = i * chunk_size
- end = start + chunk_size
- chunk = compressed_data[start:end]
- socket.send(chunk)
- cap.release()
- context.term()
+import time
+import struct
+from collections import deque
+
+class ImageServer:
+ def __init__(self, fps = 30, port = 5555, Unit_Test = False):
+ self.fps = fps
+ self.port = port
+ self.enable_performance_eval = Unit_Test
+
+ # initiate binocular camera: 480 * (640 * 2)
+ self.cap = cv2.VideoCapture(0, cv2.CAP_V4L2)
+ self.cap.set(cv2.CAP_PROP_FOURCC, cv2.VideoWriter.fourcc('M', 'J', 'P', 'G'))
+ self.cap.set(cv2.CAP_PROP_FRAME_WIDTH, 640 * 2)
+ self.cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 480)
+ self.cap.set(cv2.CAP_PROP_FPS, self.fps)
+
+ # set ZeroMQ context and socket
+ self.context = zmq.Context()
+ self.socket = self.context.socket(zmq.PUB)
+ self.socket.bind(f"tcp://*:{self.port}")
+
+ if self.enable_performance_eval:
+ self._init_performance_metrics()
+
+ print("Image server has started, waiting for client connections...")
+ print(f"Image Resolution: width is {self.cap.get(cv2.CAP_PROP_FRAME_WIDTH)}, height is {self.cap.get(cv2.CAP_PROP_FRAME_HEIGHT)}\n")
+
+ def _init_performance_metrics(self):
+ self.frame_count = 0 # Total frames sent
+ self.time_window = 1.0 # Time window for FPS calculation (in seconds)
+ self.frame_times = deque() # Timestamps of frames sent within the time window
+ self.start_time = time.time() # Start time of the streaming
+
+ def _update_performance_metrics(self, current_time):
+ # Add current time to frame times deque
+ self.frame_times.append(current_time)
+ # Remove timestamps outside the time window
+ while self.frame_times and self.frame_times[0] < current_time - self.time_window:
+ self.frame_times.popleft()
+ # Increment frame count
+ self.frame_count += 1
+
+ def _print_performance_metrics(self, current_time):
+ if self.frame_count % 30 == 0:
+ elapsed_time = current_time - self.start_time
+ real_time_fps = len(self.frame_times) / self.time_window
+ print(f"[Image Server] Real-time FPS: {real_time_fps:.2f}, Total frames sent: {self.frame_count}, Elapsed time: {elapsed_time:.2f} sec")
+
+ def _close(self):
+ self.cap.release()
+ self.socket.close()
+ self.context.term()
+ print("[Image Server] The server has been closed.")
+
+ def send_process(self):
+ try:
+ while True:
+ ret, frame = self.cap.read()
+ if not ret:
+ print("[Image Server] Frame read is error.")
+ break
+
+ ret, buffer = cv2.imencode('.jpg', frame)
+ if not ret:
+ print("[Image Server] Frame imencode is failed.")
+ continue
+
+ jpg_bytes = buffer.tobytes()
+
+ if self.enable_performance_eval:
+ timestamp = time.time()
+ frame_id = self.frame_count
+ header = struct.pack('dI', timestamp, frame_id) # 8-byte double, 4-byte unsigned int
+ message = header + jpg_bytes
+ else:
+ message = jpg_bytes
+
+ self.socket.send(message)
+
+ if self.enable_performance_eval:
+ current_time = time.time()
+ self._update_performance_metrics(current_time)
+ self._print_performance_metrics(current_time)
+
+ except KeyboardInterrupt:
+ print("[Image Server] Interrupted by user.")
+ finally:
+ self._close()
if __name__ == "__main__":
- start_server()
+ # server = ImageServer(Unit_Test = True) # test
+ server = ImageServer(Unit_Test = False) # deployment
+ server.send_process()
\ No newline at end of file
diff --git a/teleop/open_television/constants.py b/teleop/open_television/constants.py
new file mode 100644
index 0000000..0d771ed
--- /dev/null
+++ b/teleop/open_television/constants.py
@@ -0,0 +1,40 @@
+import numpy as np
+
+
+T_to_unitree_left_wrist = np.array([[1, 0, 0, 0],
+ [0, 0, -1, 0],
+ [0, 1, 0, 0],
+ [0, 0, 0, 1]])
+
+T_to_unitree_right_wrist = np.array([[1, 0, 0, 0],
+ [0, 0, 1, 0],
+ [0, -1, 0, 0],
+ [0, 0, 0, 1]])
+
+T_to_unitree_hand = np.array([[0, 0, 1, 0],
+ [-1,0, 0, 0],
+ [0, -1,0, 0],
+ [0, 0, 0, 1]])
+
+T_robot_openxr = np.array([[0, 0, -1, 0],
+ [-1, 0, 0, 0],
+ [0, 1, 0, 0],
+ [0, 0, 0, 1]])
+
+
+
+const_head_vuer_mat = np.array([[1, 0, 0, 0],
+ [0, 1, 0, 1.5],
+ [0, 0, 1, -0.2],
+ [0, 0, 0, 1]])
+
+const_right_wrist_vuer_mat = np.array([[1, 0, 0, 0.5],
+ [0, 1, 0, 1],
+ [0, 0, 1, -0.5],
+ [0, 0, 0, 1]])
+
+const_left_wrist_vuer_mat = np.array([[1, 0, 0, -0.5],
+ [0, 1, 0, 1],
+ [0, 0, 1, -0.5],
+ [0, 0, 0, 1]])
+
diff --git a/teleop/open_television/television.py b/teleop/open_television/television.py
new file mode 100644
index 0000000..2d0a0db
--- /dev/null
+++ b/teleop/open_television/television.py
@@ -0,0 +1,149 @@
+import time
+from vuer import Vuer
+from vuer.schemas import ImageBackground, Hands
+from multiprocessing import Array, Process, shared_memory
+import numpy as np
+import asyncio
+import cv2
+
+from multiprocessing import context
+Value = context._default_context.Value
+
+
+class TeleVision:
+ def __init__(self, img_shape, img_shm_name, cert_file="./cert.pem", key_file="./key.pem", ngrok=False):
+ self.img_height = img_shape[0]
+ self.img_width = img_shape[1] // 2
+
+ if ngrok:
+ self.vuer = Vuer(host='0.0.0.0', queries=dict(grid=False), queue_len=3)
+ else:
+ self.vuer = Vuer(host='0.0.0.0', cert=cert_file, key=key_file, queries=dict(grid=False), queue_len=3)
+
+ self.vuer.add_handler("HAND_MOVE")(self.on_hand_move)
+ self.vuer.add_handler("CAMERA_MOVE")(self.on_cam_move)
+
+ existing_shm = shared_memory.SharedMemory(name=img_shm_name)
+ self.img_array = np.ndarray(img_shape, dtype=np.uint8, buffer=existing_shm.buf)
+ self.vuer.spawn(start=False)(self.main_image)
+ # self.vuer.spawn(start=False)(self.main_image_stereo)
+
+ self.left_hand_shared = Array('d', 16, lock=True)
+ self.right_hand_shared = Array('d', 16, lock=True)
+ self.left_landmarks_shared = Array('d', 75, lock=True)
+ self.right_landmarks_shared = Array('d', 75, lock=True)
+
+ self.head_matrix_shared = Array('d', 16, lock=True)
+ self.aspect_shared = Value('d', 1.0, lock=True)
+
+ self.process = Process(target=self.vuer_run)
+ self.process.daemon = True
+ self.process.start()
+
+
+ def vuer_run(self):
+ self.vuer.run()
+
+ async def on_cam_move(self, event, session, fps=60):
+ try:
+ self.head_matrix_shared[:] = event.value["camera"]["matrix"]
+ self.aspect_shared.value = event.value['camera']['aspect']
+ except:
+ pass
+
+ async def on_hand_move(self, event, session, fps=60):
+ try:
+ self.left_hand_shared[:] = event.value["leftHand"]
+ self.right_hand_shared[:] = event.value["rightHand"]
+ self.left_landmarks_shared[:] = np.array(event.value["leftLandmarks"]).flatten()
+ self.right_landmarks_shared[:] = np.array(event.value["rightLandmarks"]).flatten()
+ except:
+ pass
+
+ async def main_image(self, session, fps=60):
+ session.upsert @ Hands(fps=fps, stream=True, key="hands", showLeft=False, showRight=False)
+ while True:
+ display_image = cv2.cvtColor(self.img_array, cv2.COLOR_BGR2RGB)
+ aspect_ratio = self.img_width / self.img_height
+ session.upsert(
+ [
+ ImageBackground(
+ display_image[:, :self.img_width],
+ aspect=1.778,
+ height=1,
+ distanceToCamera=1,
+ # The underlying rendering engine supported a layer binary bitmask for both objects and the camera.
+ # Below we set the two image planes, left and right, to layers=1 and layers=2.
+ # Note that these two masks are associated with left eyeβs camera and the right eyeβs camera.
+ layers=1,
+ format="jpeg",
+ quality=50,
+ key="background-left",
+ interpolate=True,
+ ),
+ ImageBackground(
+ display_image[:, self.img_width:],
+ aspect=1.778,
+ height=1,
+ distanceToCamera=1,
+ layers=2,
+ format="jpeg",
+ quality=50,
+ key="background-right",
+ interpolate=True,
+ ),
+ ],
+ to="bgChildren",
+ )
+ # 'jpeg' encoding should give you about 30fps with a 16ms wait in-between.
+ await asyncio.sleep(0.016 * 2)
+
+ @property
+ def left_hand(self):
+ return np.array(self.left_hand_shared[:]).reshape(4, 4, order="F")
+
+
+ @property
+ def right_hand(self):
+ return np.array(self.right_hand_shared[:]).reshape(4, 4, order="F")
+
+
+ @property
+ def left_landmarks(self):
+ return np.array(self.left_landmarks_shared[:]).reshape(25, 3)
+
+ @property
+ def right_landmarks(self):
+ return np.array(self.right_landmarks_shared[:]).reshape(25, 3)
+
+ @property
+ def head_matrix(self):
+ return np.array(self.head_matrix_shared[:]).reshape(4, 4, order="F")
+
+ @property
+ def aspect(self):
+ return float(self.aspect_shared.value)
+
+if __name__ == '__main__':
+ 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)
+ import threading
+ from image_server.image_client import ImageClient
+
+ # image
+ img_shape = (480, 640 * 2, 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)
+ img_client = ImageClient(img_shape = img_shape, img_shm_name = img_shm.name)
+ image_receive_thread = threading.Thread(target=img_client.receive_process, daemon=True)
+ image_receive_thread.start()
+
+ # television
+ tv = TeleVision(img_shape, img_shm.name)
+ print("vuer unit test program running...")
+ print("you can press ^C to interrupt program.")
+ while True:
+ time.sleep(0.03)
\ No newline at end of file
diff --git a/teleop/open_television/tv_wrapper.py b/teleop/open_television/tv_wrapper.py
new file mode 100644
index 0000000..d4ce189
--- /dev/null
+++ b/teleop/open_television/tv_wrapper.py
@@ -0,0 +1,147 @@
+import numpy as np
+from teleop.open_television.television import TeleVision
+from teleop.open_television.constants import *
+from teleop.utils.mat_tool import mat_update, fast_mat_inv
+
+"""
+(basis) OpenXR Convention : y up, z back, x right.
+(basis) Robot Convention : z up, y left, x front.
+p.s. Vuer's all raw data follows OpenXR Convention, WORLD coordinate.
+
+under (basis) Robot Convention, wrist's initial pose convention:
+
+ # (Left Wrist) XR/AppleVisionPro Convention:
+ - the x-axis pointing from wrist toward middle.
+ - the y-axis pointing from index toward pinky.
+ - the z-axis pointing from palm toward back of the hand.
+
+ # (Right Wrist) XR/AppleVisionPro Convention:
+ - the x-axis pointing from wrist toward middle.
+ - the y-axis pointing from pinky toward index.
+ - the z-axis pointing from palm toward back of the hand.
+
+ # (Left Wrist URDF) Unitree Convention:
+ - the x-axis pointing from wrist toward middle.
+ - the y-axis pointing from palm toward back of the hand.
+ - the z-axis pointing from pinky toward index.
+
+ # (Right Wrist URDF) Unitree Convention:
+ - the x-axis pointing from wrist toward middle.
+ - the y-axis pointing from back of the hand toward palm.
+ - the z-axis pointing from pinky toward index.
+
+under (basis) Robot Convention, hand's initial pose convention:
+
+ # (Left Hand) XR/AppleVisionPro Convention:
+ - the x-axis pointing from wrist toward middle.
+ - the y-axis pointing from index toward pinky.
+ - the z-axis pointing from palm toward back of the hand.
+
+ # (Right Hand) XR/AppleVisionPro Convention:
+ - the x-axis pointing from wrist toward middle.
+ - the y-axis pointing from pinky toward index.
+ - the z-axis pointing from palm toward back of the hand.
+
+ # (Left Hand URDF) Unitree Convention:
+ - The x-axis pointing from palm toward back of the hand.
+ - The y-axis pointing from middle toward wrist.
+ - The z-axis pointing from pinky toward index.
+
+ # (Right Hand URDF) Unitree Convention:
+ - The x-axis pointing from palm toward back of the hand.
+ - The y-axis pointing from middle toward wrist.
+ - The z-axis pointing from index toward pinky.
+
+ p.s. From website: https://registry.khronos.org/OpenXR/specs/1.1/man/html/openxr.html.
+ You can find **(Left/Right Wrist) XR/AppleVisionPro Convention** related information like this below:
+ "The wrist joint is located at the pivot point of the wrist, which is location invariant when twisting the hand without moving the forearm.
+ The backward (+Z) direction is parallel to the line from wrist joint to middle finger metacarpal joint, and points away from the finger tips.
+ The up (+Y) direction points out towards back of the hand and perpendicular to the skin at wrist.
+ The X direction is perpendicular to the Y and Z directions and follows the right hand rule."
+ Note: The above context is of course under **(basis) OpenXR Convention**.
+
+ p.s. **(Wrist/Hand URDF) Unitree Convention** information come from URDF files.
+"""
+
+class TeleVisionWrapper:
+ def __init__(self, img_shape, img_shm_name):
+ self.tv = TeleVision(img_shape, img_shm_name)
+
+ def get_data(self):
+
+ # --------------------------------wrist-------------------------------------
+
+ # TeleVision obtains a basis coordinate that is OpenXR Convention
+ head_vuer_mat = mat_update(const_head_vuer_mat, self.tv.head_matrix.copy())
+ left_wrist_vuer_mat = mat_update(const_left_wrist_vuer_mat, self.tv.left_hand.copy())
+ right_wrist_vuer_mat = mat_update(const_right_wrist_vuer_mat, self.tv.right_hand.copy())
+
+ # Change basis convention: VuerMat ((basis) OpenXR Convention) to WristMat ((basis) Robot Convention)
+ # p.s. WristMat = T_{robot}_{openxr} * VuerMat * T_{robot}_{openxr}^T
+ # Reason for right multiply fast_mat_inv(T_robot_openxr):
+ # This is similarity transformation: B = PAP^{-1}, that is B ~ A
+ # For example:
+ # - For a pose data T_r under the Robot Convention, left-multiplying WristMat means:
+ # - WristMat * T_r ==> T_{robot}_{openxr} * VuerMat * T_{openxr}_{robot} * T_r
+ # - First, transform to the OpenXR Convention (The function of T_{openxr}_{robot})
+ # - then, apply the rotation VuerMat in the OpenXR Convention (The function of VuerMat)
+ # - finally, transform back to the Robot Convention (The function of T_{robot}_{openxr})
+ # This results in the same rotation effect under the Robot Convention as in the OpenXR Convention.
+ head_mat = T_robot_openxr @ head_vuer_mat @ fast_mat_inv(T_robot_openxr)
+ left_wrist_mat = T_robot_openxr @ left_wrist_vuer_mat @ fast_mat_inv(T_robot_openxr)
+ right_wrist_mat = T_robot_openxr @ right_wrist_vuer_mat @ fast_mat_inv(T_robot_openxr)
+
+ # Change wrist convention: WristMat ((Left Wrist) XR/AppleVisionPro Convention) to UnitreeWristMat((Left Wrist URDF) Unitree Convention)
+ # Reason for right multiply (T_to_unitree_left_wrist) : Rotate 90 degrees counterclockwise about its own x-axis.
+ # Reason for right multiply (T_to_unitree_right_wrist): Rotate 90 degrees clockwise about its own x-axis.
+ unitree_left_wrist = left_wrist_mat @ T_to_unitree_left_wrist
+ unitree_right_wrist = right_wrist_mat @ T_to_unitree_right_wrist
+
+ # Transfer from WORLD to HEAD coordinate (translation only).
+ unitree_left_wrist[0:3, 3] = unitree_left_wrist[0:3, 3] - head_mat[0:3, 3]
+ unitree_right_wrist[0:3, 3] = unitree_right_wrist[0:3, 3] - head_mat[0:3, 3]
+
+ # --------------------------------hand-------------------------------------
+
+ # Homogeneous, [xyz] to [xyz1]
+ # p.s. np.concatenate([25,3]^T,(1,25)) ==> hand_vuer_mat.shape is (4,25)
+ # Now under (basis) OpenXR Convention, mat shape like this:
+ # x0 x1 x2 Β·Β·Β· x23 x24
+ # y0 y1 y1 Β·Β·Β· y23 y24
+ # z0 z1 z2 Β·Β·Β· z23 z24
+ # 1 1 1 Β·Β·Β· 1 1
+ left_hand_vuer_mat = np.concatenate([self.tv.left_landmarks.copy().T, np.ones((1, self.tv.left_landmarks.shape[0]))])
+ right_hand_vuer_mat = np.concatenate([self.tv.right_landmarks.copy().T, np.ones((1, self.tv.right_landmarks.shape[0]))])
+
+ # Change basis convention: from (basis) OpenXR Convention to (basis) Robot Convention
+ # Just a change of basis for 3D points. No rotation, only translation. No need to right-multiply fast_mat_inv(T_robot_openxr).
+ left_hand_mat = T_robot_openxr @ left_hand_vuer_mat
+ right_hand_mat = T_robot_openxr @ right_hand_vuer_mat
+
+ # Transfer from WORLD to WRIST coordinate. (this process under (basis) Robot Convention)
+ # p.s. HandMat_WristBased = WristMat_{wrold}_{wrist}^T * HandMat_{wrold}
+ # HandMat_WristBased = WristMat_{wrist}_{wrold} * HandMat_{wrold}, that is HandMat_{wrist}
+ left_hand_mat_wb = fast_mat_inv(left_wrist_mat) @ left_hand_mat
+ right_hand_mat_wb = fast_mat_inv(right_wrist_mat) @ right_hand_mat
+ # Change hand convention: HandMat ((Left Hand) XR/AppleVisionPro Convention) to UnitreeHandMat((Left Hand URDF) Unitree Convention)
+ # Reason for left multiply : T_to_unitree_hand @ left_hand_mat_wb ==> (4,4) @ (4,25) ==> (4,25), (4,25)[0:3, :] ==> (3,25), (3,25).T ==> (25,3)
+ # Now under (Left Hand URDF) Unitree Convention, mat shape like this:
+ # [x0, y0, z0]
+ # [x1, y1, z1]
+ # Β·Β·Β·
+ # [x23,y23,z23]
+ # [x24,y24,z24]
+ unitree_left_hand = (T_to_unitree_hand @ left_hand_mat_wb)[0:3, :].T
+ unitree_right_hand = (T_to_unitree_hand @ right_hand_mat_wb)[0:3, :].T
+
+ # --------------------------------offset-------------------------------------
+
+ head_rmat = head_mat[:3, :3]
+ # The origin of the coordinate for IK Solve is the WAIST joint motor. You can use teleop/robot_control/robot_arm_ik.py Unit_Test to check it.
+ # The origin of the coordinate of unitree_left_wrist is HEAD. So it is necessary to translate the origin of unitree_left_wrist from HEAD to WAIST.
+ unitree_left_wrist[0, 3] +=0.20
+ unitree_right_wrist[0,3] +=0.20
+ unitree_left_wrist[2, 3] +=0.45
+ unitree_right_wrist[2,3] +=0.45
+
+ return head_rmat, unitree_left_wrist, unitree_right_wrist, unitree_left_hand, unitree_right_hand
\ No newline at end of file
diff --git a/teleop/robot_control/hand_retargeting.py b/teleop/robot_control/hand_retargeting.py
new file mode 100644
index 0000000..294eb81
--- /dev/null
+++ b/teleop/robot_control/hand_retargeting.py
@@ -0,0 +1,22 @@
+from dex_retargeting.retargeting_config import RetargetingConfig
+from pathlib import Path
+import yaml
+from enum import Enum
+
+class HandType(Enum):
+ INSPIRE_HAND = "../assets/inspire_hand/inspire_hand.yml"
+ UNITREE_DEX3 = "../assets/unitree_hand/unitree_dex3.yml"
+
+class HandRetargeting:
+ def __init__(self, hand_type: HandType):
+ RetargetingConfig.set_default_urdf_dir('../assets')
+
+ config_file_path = hand_type.value
+
+ with Path(config_file_path).open('r') as f:
+ self.cfg = yaml.safe_load(f)
+
+ left_retargeting_config = RetargetingConfig.from_dict(self.cfg['left'])
+ right_retargeting_config = RetargetingConfig.from_dict(self.cfg['right'])
+ self.left_retargeting = left_retargeting_config.build()
+ self.right_retargeting = right_retargeting_config.build()
\ No newline at end of file
diff --git a/teleop/robot_control/robot_arm.py b/teleop/robot_control/robot_arm.py
index 6751601..2466efe 100644
--- a/teleop/robot_control/robot_arm.py
+++ b/teleop/robot_control/robot_arm.py
@@ -5,35 +5,23 @@ import time
from unitree_dds_wrapper.idl import unitree_hg
from unitree_dds_wrapper.publisher import Publisher
from unitree_dds_wrapper.subscription import Subscription
-from unitree_dds_wrapper.utils.crc import crc32
import struct
from enum import IntEnum
-import copy
kTopicLowCommand = "rt/lowcmd"
kTopicLowState = "rt/lowstate"
-kNumMotors = 35
-
-
-
-class MotorCommand:
- def __init__(self):
- self.q_ref = np.zeros(kNumMotors)
- self.dq_ref = np.zeros(kNumMotors)
- self.tau_ff = np.zeros(kNumMotors)
- self.kp = np.zeros(kNumMotors)
- self.kd = np.zeros(kNumMotors)
+G1_29_Num_Motors = 35
+
class MotorState:
def __init__(self):
- self.q = np.zeros(kNumMotors)
- self.dq = np.zeros(kNumMotors)
+ self.q = None
+ self.dq = None
-class BaseState:
+class G1_29_LowState:
def __init__(self):
- self.omega = np.zeros(3)
- self.rpy = np.zeros(3)
+ self.motor_state = [MotorState() for _ in range(G1_29_Num_Motors)]
class DataBuffer:
def __init__(self):
@@ -48,86 +36,77 @@ class DataBuffer:
with self.lock:
self.data = data
-np.set_printoptions(linewidth=240)
-
-class H1ArmController:
+class G1_29_ArmController:
def __init__(self):
- print("Initialize H1ArmController...")
- self.q_desList = np.zeros(kNumMotors)
- self.q_tau_ff = np.zeros(kNumMotors)
- self.msg = unitree_hg.msg.dds_.LowCmd_()
- self.__packFmtHGLowCmd = '<2B2x' + 'B3x5fI' * 35 + '5I'
+ print("Initialize G1_29_ArmController...")
+ self.q_target = np.zeros(14)
+ self.tauff_target = np.zeros(14)
+ self.msg = unitree_hg.msg.dds_.LowCmd_()
+ self.msg.mode_machine = 3 # g1 is 3, h1_2 is 4
+ self.__packFmtHGLowCmd = '<2B2x' + 'B3x5fI' * 35 + '5I'
self.msg.head = [0xFE, 0xEF]
+
self.lowcmd_publisher = Publisher(unitree_hg.msg.dds_.LowCmd_, kTopicLowCommand)
self.lowstate_subscriber = Subscription(unitree_hg.msg.dds_.LowState_, kTopicLowState)
- self.motor_state_buffer = DataBuffer()
- self.motor_command_buffer = DataBuffer()
- self.base_state_buffer = DataBuffer()
-
- self.kp_low = 140.0
- self.kd_low = 7.5
-
- self.kp_high = 200.0
- self.kd_high = 5.0
-
- self.kp_wrist = 35.0
- self.kd_wrist = 6.0
-
- self.control_dt = 0.01
- self.hip_pitch_init_pos = -0.5
- self.knee_init_pos = 1.0
- self.ankle_init_pos = -0.5
- self.shoulder_pitch_init_pos = -1.4
- self.time = 0.0
- self.init_duration = 10.0
- self.report_dt = 0.1
- self.ratio = 0.0
- self.q_target = []
- while not self.lowstate_subscriber.msg:
- print("lowstate_subscriber is not ok! Please check dds.")
- time.sleep(0.01)
-
- for id in JointIndex:
- self.msg.motor_cmd[id].q = self.lowstate_subscriber.msg.motor_state[id].q
- self.q_target.append(self.msg.motor_cmd[id].q)
- print(f"Init q_pose is :{self.q_target}")
- duration = 1000
- init_q = np.array([self.lowstate_subscriber.msg.motor_state[id].q for id in JointIndex])
- print("Lock Leg...")
- for i in range(duration):
- time.sleep(0.001)
- q_t = init_q + (self.q_target - init_q) * i / duration
- for i, id in enumerate(JointIndex):
- self.msg.motor_cmd[id].mode = 1
- if id not in JointArmIndex:
- self.msg.motor_cmd[id].kp = 200
- self.msg.motor_cmd[id].kd = 5
- self.msg.motor_cmd[id].q = q_t[i]
- self.pre_communication()
- self.lowcmd_publisher.msg = self.msg
- self.lowcmd_publisher.write()
- print("Lock Leg OK!")
+ self.lowstate_buffer = DataBuffer()
+
+ self.kp_high = 100.0
+ self.kd_high = 3.0
+ self.kp_low = 80.0
+ self.kd_low = 3.0
+ self.kp_wrist = 40.0
+ self.kd_wrist = 1.5
+
+ self.all_motor_q = None
+ self.arm_velocity_limit = 20.0
+ self.control_dt = 1.0 / 250.0
- self.report_rpy_thread = threading.Thread(target=self.SubscribeState)
- self.report_rpy_thread.start()
+ self._speed_gradual_max = False
+ self._gradual_start_time = None
+ self._gradual_time = None
- self.control_thread = threading.Thread(target=self.Control)
- self.control_thread.start()
+ self.subscribe_thread = threading.Thread(target=self._subscribe_motor_state)
+ self.subscribe_thread.daemon = True
+ self.subscribe_thread.start()
- self.command_writer_thread = threading.Thread(target=self.LowCommandWriter)
- self.command_writer_thread.start()
- print("Initialize H1ArmController OK!")
+ while not self.lowstate_buffer.GetData():
+ time.sleep(0.01)
+ print("Waiting to subscribe dds...")
+
+ self.all_motor_q = self.get_current_motor_q()
+ print(f"Current all body motor state q:\n{self.all_motor_q} \n")
+ print(f"Current two arms motor state q:\n{self.get_current_dual_arm_q()}\n")
+ print("Lock all joints except two arms...\n")
+ for id in G1_29_JointIndex:
+ self.msg.motor_cmd[id].mode = 1
+ if id in G1_29_JointArmIndex:
+ if self._Is_wrist_motor(id):
+ self.msg.motor_cmd[id].kp = self.kp_wrist
+ self.msg.motor_cmd[id].kd = self.kd_wrist
+ else:
+ self.msg.motor_cmd[id].kp = self.kp_low
+ self.msg.motor_cmd[id].kd = self.kd_low
+ else:
+ if self._Is_weak_motor(id):
+ self.msg.motor_cmd[id].kp = self.kp_low
+ self.msg.motor_cmd[id].kd = self.kd_low
+ else:
+ self.msg.motor_cmd[id].kp = self.kp_high
+ self.msg.motor_cmd[id].kd = self.kd_high
+ self.msg.motor_cmd[id].q = self.all_motor_q[id]
+ self.pre_communication()
+ self.lowcmd_publisher.msg = self.msg
+ self.lowcmd_publisher.write()
+ print("Lock OK!\n")
- def LowStateHandler(self, message):
- low_state = message
- self.RecordMotorState(low_state)
- self.RecordBaseState(low_state)
+ self.publish_thread = threading.Thread(target=self._ctrl_motor_state)
+ self.ctrl_lock = threading.Lock()
+ self.publish_thread.daemon = True
+ self.publish_thread.start()
- def SetMotorPose(self,q_desList,q_tau_ff):
- self.q_desList = q_desList
- self.q_tau_ff = q_tau_ff
+ print("Initialize G1_29_ArmController OK!\n")
def __Trans(self, packData):
calcData = []
@@ -162,9 +141,6 @@ class H1ArmController:
return crc
- def pre_communication(self):
- self.__pack_crc()
-
def __pack_crc(self):
origData = []
origData.append(self.msg.mode_pr)
@@ -185,166 +161,231 @@ class H1ArmController:
calcdata = self.__Trans(calcdata)
self.msg.crc = self.__Crc32(calcdata)
- def LowCommandWriter(self):
- while True:
- mc_tmp_ptr = self.motor_command_buffer.GetData()
- if mc_tmp_ptr:
- for i in JointArmIndex:
- self.msg.motor_cmd[i].tau = mc_tmp_ptr.tau_ff[i]
- self.msg.motor_cmd[i].q = mc_tmp_ptr.q_ref[i]
- self.msg.motor_cmd[i].dq = mc_tmp_ptr.dq_ref[i]
- self.msg.motor_cmd[i].kp = mc_tmp_ptr.kp[i]
- self.msg.motor_cmd[i].kd = mc_tmp_ptr.kd[i]
- self.pre_communication()
- self.lowcmd_publisher.msg = self.msg
- self.lowcmd_publisher.write()
- time.sleep(0.002)
-
- def Control(self):
+ def pre_communication(self):
+ self.__pack_crc()
+
+ def clip_arm_q_target(self, target_q, velocity_limit):
+ current_q = self.get_current_dual_arm_q()
+ delta = target_q - current_q
+ motion_scale = np.max(np.abs(delta)) / (velocity_limit * self.control_dt)
+ cliped_arm_q_target = current_q + delta / max(motion_scale, 1.0)
+ return cliped_arm_q_target
+
+ def _ctrl_motor_state(self):
while True:
- ms_tmp_ptr = self.motor_state_buffer.GetData()
- if ms_tmp_ptr:
- tem_q_desList = copy.deepcopy(self.q_desList)
- tem_q_tau_ff = copy.deepcopy(self.q_tau_ff)
- motor_command_tmp = MotorCommand()
- self.time += self.control_dt
- self.time = min(max(self.time, 0.0), self.init_duration)
- self.ratio = self.time / self.init_duration
- for i in range(kNumMotors):
- if self.IsWeakMotor(i):
- motor_command_tmp.kp[i] = self.kp_low
- motor_command_tmp.kd[i] = self.kd_low
- elif self.IsWristMotor(i):
- motor_command_tmp.kp[i] = self.kp_wrist
- motor_command_tmp.kd[i] = self.kd_wrist
- else:
- motor_command_tmp.kp[i] = self.kp_high
- motor_command_tmp.kd[i] = self.kd_high
- motor_command_tmp.dq_ref[i] = 0.0
- motor_command_tmp.tau_ff[i] = tem_q_tau_ff[i]
- q_des = tem_q_desList[i]
-
- q_des = (q_des - ms_tmp_ptr.q[i]) * self.ratio + ms_tmp_ptr.q[i]
- motor_command_tmp.q_ref[i] = q_des
- self.motor_command_buffer.SetData(motor_command_tmp)
- time.sleep(0.002)
+ start_time = time.time()
+
+ with self.ctrl_lock:
+ arm_q_target = self.q_target
+ arm_tauff_target = self.tauff_target
+
+ cliped_arm_q_target = self.clip_arm_q_target(arm_q_target, velocity_limit = self.arm_velocity_limit)
+
+ for idx, id in enumerate(G1_29_JointArmIndex):
+ self.msg.motor_cmd[id].q = cliped_arm_q_target[idx]
+ self.msg.motor_cmd[id].dq = 0
+ self.msg.motor_cmd[id].tau = arm_tauff_target[idx]
+
+ self.pre_communication()
+ self.lowcmd_publisher.msg = self.msg
+ self.lowcmd_publisher.write()
+
+ if self._speed_gradual_max is True:
+ t_elapsed = start_time - self._gradual_start_time
+ self.arm_velocity_limit = 20.0 + (10.0 * min(1.0, t_elapsed / 5.0))
+
+ current_time = time.time()
+ all_t_elapsed = current_time - start_time
+ sleep_time = max(0, (self.control_dt - all_t_elapsed))
+ time.sleep(sleep_time)
+ # print(f"arm_velocity_limit:{self.arm_velocity_limit}")
+ # print(f"sleep_time:{sleep_time}")
+
+ def ctrl_dual_arm(self, q_target, tauff_target):
+ '''Set control target values q & tau of the left and right arm motors.'''
+ with self.ctrl_lock:
+ self.q_target = q_target
+ self.tauff_target = tauff_target
- def GetMotorState(self):
- ms_tmp_ptr = self.motor_state_buffer.GetData()
- if ms_tmp_ptr:
- return ms_tmp_ptr.q[13:27],ms_tmp_ptr.dq[13:27]
- else:
- return None,None
-
- def SubscribeState(self):
+ def get_current_motor_q(self):
+ '''Return current state q of all body motors.'''
+ return np.array([self.lowstate_buffer.GetData().motor_state[id].q for id in G1_29_JointIndex])
+
+ def get_current_dual_arm_q(self):
+ '''Return current state q of the left and right arm motors.'''
+ return np.array([self.lowstate_buffer.GetData().motor_state[id].q for id in G1_29_JointArmIndex])
+
+ def get_current_dual_arm_dq(self):
+ '''Return current state dq of the left and right arm motors.'''
+ return np.array([self.lowstate_buffer.GetData().motor_state[id].dq for id in G1_29_JointArmIndex])
+
+ def _subscribe_motor_state(self):
while True:
if self.lowstate_subscriber.msg:
- self.LowStateHandler(self.lowstate_subscriber.msg)
+ lowstate = G1_29_LowState()
+ for id in range(G1_29_Num_Motors):
+ lowstate.motor_state[id].q = self.lowstate_subscriber.msg.motor_state[id].q
+ lowstate.motor_state[id].dq = self.lowstate_subscriber.msg.motor_state[id].dq
+ self.lowstate_buffer.SetData(lowstate)
time.sleep(0.002)
- def RecordMotorState(self, msg):
- ms_tmp = MotorState()
- for i in range(kNumMotors):
- ms_tmp.q[i] = msg.motor_state[i].q
- ms_tmp.dq[i] = msg.motor_state[i].dq
- self.motor_state_buffer.SetData(ms_tmp)
+ def speed_gradual_max(self, t = 5.0):
+ '''Parameter t is the total time required for arms velocity to gradually increase to its maximum value, in seconds. The default is 5.0.'''
+ self._gradual_start_time = time.time()
+ self._gradual_time = t
+ self._speed_gradual_max = True
- def RecordBaseState(self, msg):
- bs_tmp = BaseState()
- bs_tmp.omega = msg.imu_state.gyroscope
- bs_tmp.rpy = msg.imu_state.rpy
- self.base_state_buffer.SetData(bs_tmp)
+ def speed_instant_max(self):
+ '''set arms velocity to the maximum value immediately, instead of gradually increasing.'''
+ self.arm_velocity_limit = 30.0
- def IsWeakMotor(self, motor_index):
+ def _Is_weak_motor(self, motor_index):
weak_motors = [
- JointIndex.kLeftAnkle,
- JointIndex.kRightAnkle,
+ G1_29_JointIndex.kLeftAnklePitch,
+ G1_29_JointIndex.kRightAnklePitch,
# Left arm
- JointIndex.kLeftShoulderPitch,
- JointIndex.kLeftShoulderRoll,
- JointIndex.kLeftShoulderYaw,
- JointIndex.kLeftElbowPitch,
+ G1_29_JointIndex.kLeftShoulderPitch,
+ G1_29_JointIndex.kLeftShoulderRoll,
+ G1_29_JointIndex.kLeftShoulderYaw,
+ G1_29_JointIndex.kLeftElbow,
# Right arm
- JointIndex.kRightShoulderPitch,
- JointIndex.kRightShoulderRoll,
- JointIndex.kRightShoulderYaw,
- JointIndex.kRightElbowPitch,
+ G1_29_JointIndex.kRightShoulderPitch,
+ G1_29_JointIndex.kRightShoulderRoll,
+ G1_29_JointIndex.kRightShoulderYaw,
+ G1_29_JointIndex.kRightElbow,
]
return motor_index in weak_motors
- def IsWristMotor(self, motor_index):
+ def _Is_wrist_motor(self, motor_index):
wrist_motors = [
- JointIndex.kLeftElbowRoll,
- JointIndex.kLeftWristPitch,
- JointIndex.kLeftWristyaw,
- JointIndex.kRightElbowRoll,
- JointIndex.kRightWristPitch,
- JointIndex.kRightWristYaw,
+ G1_29_JointIndex.kLeftWristRoll,
+ G1_29_JointIndex.kLeftWristPitch,
+ G1_29_JointIndex.kLeftWristyaw,
+ G1_29_JointIndex.kRightWristRoll,
+ G1_29_JointIndex.kRightWristPitch,
+ G1_29_JointIndex.kRightWristYaw,
]
return motor_index in wrist_motors
-class JointArmIndex(IntEnum):
+class G1_29_JointArmIndex(IntEnum):
# Left arm
- kLeftShoulderPitch = 13
- kLeftShoulderRoll = 14
- kLeftShoulderYaw = 15
- kLeftElbowPitch = 16
- kLeftElbowRoll = 17
- kLeftWristPitch = 18
- kLeftWristyaw = 19
+ kLeftShoulderPitch = 15
+ kLeftShoulderRoll = 16
+ kLeftShoulderYaw = 17
+ kLeftElbow = 18
+ kLeftWristRoll = 19
+ kLeftWristPitch = 20
+ kLeftWristyaw = 21
# Right arm
- kRightShoulderPitch = 20
- kRightShoulderRoll = 21
- kRightShoulderYaw = 22
- kRightElbowPitch = 23
- kRightElbowRoll = 24
- kRightWristPitch = 25
- kRightWristYaw = 26
-
-class JointIndex(IntEnum):
+ kRightShoulderPitch = 22
+ kRightShoulderRoll = 23
+ kRightShoulderYaw = 24
+ kRightElbow = 25
+ kRightWristRoll = 26
+ kRightWristPitch = 27
+ kRightWristYaw = 28
+
+class G1_29_JointIndex(IntEnum):
# Left leg
- kLeftHipYaw = 0
+ kLeftHipPitch = 0
kLeftHipRoll = 1
- kLeftHipPitch = 2
+ kLeftHipYaw = 2
kLeftKnee = 3
- kLeftAnkle = 4
+ kLeftAnklePitch = 4
kLeftAnkleRoll = 5
# Right leg
- kRightHipYaw = 6
+ kRightHipPitch = 6
kRightHipRoll = 7
- kRightHipPitch = 8
+ kRightHipYaw = 8
kRightKnee = 9
- kRightAnkle = 10
+ kRightAnklePitch = 10
kRightAnkleRoll = 11
kWaistYaw = 12
+ kWaistRoll = 13
+ kWaistPitch = 14
# Left arm
- kLeftShoulderPitch = 13
- kLeftShoulderRoll = 14
- kLeftShoulderYaw = 15
- kLeftElbowPitch = 16
- kLeftElbowRoll = 17
- kLeftWristPitch = 18
- kLeftWristyaw = 19
+ kLeftShoulderPitch = 15
+ kLeftShoulderRoll = 16
+ kLeftShoulderYaw = 17
+ kLeftElbow = 18
+ kLeftWristRoll = 19
+ kLeftWristPitch = 20
+ kLeftWristyaw = 21
# Right arm
- kRightShoulderPitch = 20
- kRightShoulderRoll = 21
- kRightShoulderYaw = 22
- kRightElbowPitch = 23
- kRightElbowRoll = 24
- kRightWristPitch = 25
- kRightWristYaw = 26
-
- kNotUsedJoint = 27
- kNotUsedJoint1 = 28
- kNotUsedJoint2 = 29
- kNotUsedJoint3 = 30
- kNotUsedJoint4 = 31
- kNotUsedJoint5 = 32
- kNotUsedJoint6 = 33
- kNotUsedJoint7 = 34
+ kRightShoulderPitch = 22
+ kRightShoulderRoll = 23
+ kRightShoulderYaw = 24
+ kRightElbow = 25
+ kRightWristRoll = 26
+ kRightWristPitch = 27
+ kRightWristYaw = 28
+
+ # not used
+ kNotUsedJoint0 = 29
+ kNotUsedJoint1 = 30
+ kNotUsedJoint2 = 31
+ kNotUsedJoint3 = 32
+ kNotUsedJoint4 = 33
+ kNotUsedJoint5 = 34
+
+if __name__ == "__main__":
+ from robot_arm_ik import G1_29_ArmIK
+ import pinocchio as pin
+
+ arm_ik = G1_29_ArmIK(Unit_Test = True, Visualization = False)
+ g1arm = G1_29_ArmController()
+
+ # initial positon
+ L_tf_target = pin.SE3(
+ pin.Quaternion(1, 0, 0, 0),
+ np.array([0.25, +0.2, 0.1]),
+ )
+
+ R_tf_target = pin.SE3(
+ pin.Quaternion(1, 0, 0, 0),
+ np.array([0.25, -0.2, 0.1]),
+ )
+
+ rotation_speed = 0.005 # Rotation speed in radians per iteration
+ q_target = np.zeros(35)
+ tauff_target = np.zeros(35)
+
+ user_input = input("Please enter the start signal (enter 's' to start the subsequent program): \n")
+ if user_input.lower() == 's':
+ step = 0
+ g1arm.speed_gradual_max()
+ while True:
+ if step <= 120:
+ angle = rotation_speed * step
+ L_quat = pin.Quaternion(np.cos(angle / 2), 0, np.sin(angle / 2), 0) # y axis
+ R_quat = pin.Quaternion(np.cos(angle / 2), 0, 0, np.sin(angle / 2)) # z axis
+
+ L_tf_target.translation += np.array([0.001, 0.001, 0.001])
+ R_tf_target.translation += np.array([0.001, -0.001, 0.001])
+ else:
+ angle = rotation_speed * (240 - step)
+ L_quat = pin.Quaternion(np.cos(angle / 2), 0, np.sin(angle / 2), 0) # y axis
+ R_quat = pin.Quaternion(np.cos(angle / 2), 0, 0, np.sin(angle / 2)) # z axis
+
+ L_tf_target.translation -= np.array([0.001, 0.001, 0.001])
+ R_tf_target.translation -= np.array([0.001, -0.001, 0.001])
+
+ L_tf_target.rotation = L_quat.toRotationMatrix()
+ R_tf_target.rotation = R_quat.toRotationMatrix()
+
+ current_lr_arm_q = g1arm.get_current_dual_arm_q()
+ current_lr_arm_dq = g1arm.get_current_dual_arm_dq()
+
+ sol_q, sol_tauff = arm_ik.solve_ik(L_tf_target.homogeneous, R_tf_target.homogeneous, current_lr_arm_q, current_lr_arm_dq)
+
+ g1arm.ctrl_dual_arm(sol_q, sol_tauff)
+ step += 1
+ if step > 240:
+ step = 0
+ time.sleep(0.01)
\ No newline at end of file
diff --git a/teleop/robot_control/robot_arm_ik.py b/teleop/robot_control/robot_arm_ik.py
index 04279af..123f912 100644
--- a/teleop/robot_control/robot_arm_ik.py
+++ b/teleop/robot_control/robot_arm_ik.py
@@ -9,20 +9,24 @@ from pinocchio.visualize import MeshcatVisualizer
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)
+parent2_dir = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
+sys.path.append(parent2_dir)
-from robot_control.joint_smooth import WeightedMovingFilter
+from teleop.utils.weighted_moving_filter import WeightedMovingFilter
-class Arm_IK:
- def __init__(self):
+class G1_29_ArmIK:
+ def __init__(self, Unit_Test = False, Visualization = False):
np.set_printoptions(precision=5, suppress=True, linewidth=200)
- self.robot = pin.RobotWrapper.BuildFromURDF('../assets/g1/g1_body29_hand14.urdf', '../assets/g1/')
- # self.robot = pin.RobotWrapper.BuildFromURDF('../../assets/g1/g1_body29_hand14.urdf', '../../assets/g1/') # for test
+ self.Unit_Test = Unit_Test
+ self.Visualization = Visualization
- self.mixed_jointsToLockIDs = [
+ if not self.Unit_Test:
+ self.robot = pin.RobotWrapper.BuildFromURDF('../assets/g1/g1_body29_hand14.urdf', '../assets/g1/')
+ else:
+ self.robot = pin.RobotWrapper.BuildFromURDF('../../assets/g1/g1_body29_hand14.urdf', '../../assets/g1/') # for test
+
+ self.mixed_jointsToLockIDs = [
"left_hip_pitch_joint" ,
"left_hip_roll_joint" ,
"left_hip_yaw_joint" ,
@@ -77,50 +81,11 @@ class Arm_IK:
pin.FrameType.OP_FRAME)
)
- self.joint_smooth_filter = WeightedMovingFilter(np.array([0.4, 0.3, 0.2, 0.1]), 14)
-
- self.init_data = np.zeros(self.reduced_robot.model.nq)
-
- # # Initialize the Meshcat visualizer for visualization
- # self.vis = MeshcatVisualizer(self.reduced_robot.model, self.reduced_robot.collision_model, self.reduced_robot.visual_model)
- # self.vis.initViewer(open=True)
- # self.vis.loadViewerModel("pinocchio")
- # self.vis.displayFrames(True, frame_ids=[49, 81, 101, 102], axis_length = 0.15, axis_width = 5)
- # self.vis.display(pin.neutral(self.reduced_robot.model))
-
- # # for i in range(self.reduced_robot.model.nframes):
- # # frame = self.reduced_robot.model.frames[i]
- # # frame_id = self.reduced_robot.model.getFrameId(frame.name)
- # # print(f"Frame ID: {frame_id}, Name: {frame.name}")
-
- # # Enable the display of end effector target frames with short axis lengths and greater width.
- # frame_viz_names = ['L_ee_target', 'R_ee_target']
- # FRAME_AXIS_POSITIONS = (
- # np.array([[0, 0, 0], [1, 0, 0],
- # [0, 0, 0], [0, 1, 0],
- # [0, 0, 0], [0, 0, 1]]).astype(np.float32).T
- # )
- # FRAME_AXIS_COLORS = (
- # np.array([[1, 0, 0], [1, 0.6, 0],
- # [0, 1, 0], [0.6, 1, 0],
- # [0, 0, 1], [0, 0.6, 1]]).astype(np.float32).T
- # )
- # axis_length = 0.1
- # axis_width = 10
- # for frame_viz_name in frame_viz_names:
- # self.vis.viewer[frame_viz_name].set_object(
- # mg.LineSegments(
- # mg.PointsGeometry(
- # position=axis_length * FRAME_AXIS_POSITIONS,
- # color=FRAME_AXIS_COLORS,
- # ),
- # mg.LineBasicMaterial(
- # linewidth=axis_width,
- # vertexColors=True,
- # ),
- # )
- # )
-
+ # for i in range(self.reduced_robot.model.nframes):
+ # frame = self.reduced_robot.model.frames[i]
+ # frame_id = self.reduced_robot.model.getFrameId(frame.name)
+ # print(f"Frame ID: {frame_id}, Name: {frame.name}")
+
# Creating Casadi models and data for symbolic computing
self.cmodel = cpin.Model(self.reduced_robot.model)
self.cdata = self.cmodel.createData()
@@ -134,17 +99,24 @@ class Arm_IK:
# Get the hand joint ID and define the error function
self.L_hand_id = self.reduced_robot.model.getFrameId("L_ee")
self.R_hand_id = self.reduced_robot.model.getFrameId("R_ee")
- self.error = casadi.Function(
- "error",
+
+ self.translational_error = casadi.Function(
+ "translational_error",
+ [self.cq, self.cTf_l, self.cTf_r],
+ [
+ casadi.vertcat(
+ self.cdata.oMf[self.L_hand_id].translation - self.cTf_l[:3,3],
+ self.cdata.oMf[self.R_hand_id].translation - self.cTf_r[:3,3]
+ )
+ ],
+ )
+ self.rotational_error = casadi.Function(
+ "rotational_error",
[self.cq, self.cTf_l, self.cTf_r],
[
casadi.vertcat(
- cpin.log6(
- self.cdata.oMf[self.L_hand_id].inverse() * cpin.SE3(self.cTf_l)
- ).vector,
- cpin.log6(
- self.cdata.oMf[self.R_hand_id].inverse() * cpin.SE3(self.cTf_r)
- ).vector
+ cpin.log3(self.cdata.oMf[self.L_hand_id].rotation @ self.cTf_l[:3,:3].T),
+ cpin.log3(self.cdata.oMf[self.R_hand_id].rotation @ self.cTf_r[:3,:3].T)
)
],
)
@@ -155,8 +127,9 @@ class Arm_IK:
self.var_q_last = self.opti.parameter(self.reduced_robot.model.nq) # for smooth
self.param_tf_l = self.opti.parameter(4, 4)
self.param_tf_r = self.opti.parameter(4, 4)
- self.totalcost = casadi.sumsqr(self.error(self.var_q, self.param_tf_l, self.param_tf_r))
- self.regularization = casadi.sumsqr(self.var_q)
+ self.translational_cost = casadi.sumsqr(self.translational_error(self.var_q, self.param_tf_l, self.param_tf_r))
+ self.rotation_cost = casadi.sumsqr(self.rotational_error(self.var_q, self.param_tf_l, self.param_tf_r))
+ self.regularization_cost = casadi.sumsqr(self.var_q)
self.smooth_cost = casadi.sumsqr(self.var_q - self.var_q_last)
# Setting optimization constraints and goals
@@ -165,20 +138,60 @@ class Arm_IK:
self.var_q,
self.reduced_robot.model.upperPositionLimit)
)
- # self.opti.minimize(20 * self.totalcost + 0.01 * self.regularization)
- self.opti.minimize(20 * self.totalcost + 0.01* self.regularization + 0.1 * self.smooth_cost) # for smooth
+ self.opti.minimize(50 * self.translational_cost + self.rotation_cost + 0.02 * self.regularization_cost + 0.1 * self.smooth_cost)
opts = {
'ipopt':{
'print_level':0,
'max_iter':50,
- 'tol':1e-4
+ 'tol':1e-6
},
- 'print_time':False
+ 'print_time':False,# print or not
+ 'calc_lam_p':False # https://github.com/casadi/casadi/wiki/FAQ:-Why-am-I-getting-%22NaN-detected%22in-my-optimization%3F
}
self.opti.solver("ipopt", opts)
- def adjust_pose(self, human_left_pose, human_right_pose, human_arm_length=0.60, robot_arm_length=0.75):
+ self.init_data = np.zeros(self.reduced_robot.model.nq)
+ self.smooth_filter = WeightedMovingFilter(np.array([0.4, 0.3, 0.2, 0.1]), 14)
+ self.vis = None
+
+ if self.Visualization:
+ # Initialize the Meshcat visualizer for visualization
+ self.vis = MeshcatVisualizer(self.reduced_robot.model, self.reduced_robot.collision_model, self.reduced_robot.visual_model)
+ self.vis.initViewer(open=True)
+ self.vis.loadViewerModel("pinocchio")
+ self.vis.displayFrames(True, frame_ids=[101, 102], axis_length = 0.15, axis_width = 5)
+ self.vis.display(pin.neutral(self.reduced_robot.model))
+
+ # Enable the display of end effector target frames with short axis lengths and greater width.
+ frame_viz_names = ['L_ee_target', 'R_ee_target']
+ FRAME_AXIS_POSITIONS = (
+ np.array([[0, 0, 0], [1, 0, 0],
+ [0, 0, 0], [0, 1, 0],
+ [0, 0, 0], [0, 0, 1]]).astype(np.float32).T
+ )
+ FRAME_AXIS_COLORS = (
+ np.array([[1, 0, 0], [1, 0.6, 0],
+ [0, 1, 0], [0.6, 1, 0],
+ [0, 0, 1], [0, 0.6, 1]]).astype(np.float32).T
+ )
+ axis_length = 0.1
+ axis_width = 10
+ for frame_viz_name in frame_viz_names:
+ self.vis.viewer[frame_viz_name].set_object(
+ mg.LineSegments(
+ mg.PointsGeometry(
+ position=axis_length * FRAME_AXIS_POSITIONS,
+ color=FRAME_AXIS_COLORS,
+ ),
+ mg.LineBasicMaterial(
+ linewidth=axis_width,
+ vertexColors=True,
+ ),
+ )
+ )
+ # If the robot arm is not the same size as your arm :)
+ def scale_arms(self, human_left_pose, human_right_pose, human_arm_length=0.60, robot_arm_length=0.75):
scale_factor = robot_arm_length / human_arm_length
robot_left_pose = human_left_pose.copy()
robot_right_pose = human_right_pose.copy()
@@ -186,74 +199,111 @@ class Arm_IK:
robot_right_pose[:3, 3] *= scale_factor
return robot_left_pose, robot_right_pose
- def ik_fun(self, left_pose, right_pose, motorstate=None, motorV=None):
- if motorstate is not None:
- self.init_data = motorstate
+ def solve_ik(self, left_wrist, right_wrist, current_lr_arm_motor_q = None, current_lr_arm_motor_dq = None):
+ if current_lr_arm_motor_q is not None:
+ self.init_data = current_lr_arm_motor_q
self.opti.set_initial(self.var_q, self.init_data)
- # left_pose, right_pose = self.adjust_pose(left_pose, right_pose)
-
- # self.vis.viewer['L_ee_target'].set_transform(left_pose) # for visualization
- # self.vis.viewer['R_ee_target'].set_transform(right_pose) # for visualization
+ # left_wrist, right_wrist = self.scale_arms(left_wrist, right_wrist)
+ if self.Visualization:
+ self.vis.viewer['L_ee_target'].set_transform(left_wrist) # for visualization
+ self.vis.viewer['R_ee_target'].set_transform(right_wrist) # for visualization
- self.opti.set_value(self.param_tf_l, left_pose)
- self.opti.set_value(self.param_tf_r, right_pose)
+ self.opti.set_value(self.param_tf_l, left_wrist)
+ self.opti.set_value(self.param_tf_r, right_wrist)
self.opti.set_value(self.var_q_last, self.init_data) # for smooth
try:
- # sol = self.opti.solve()
- sol = self.opti.solve_limited()
+ sol = self.opti.solve()
+ # sol = self.opti.solve_limited()
+
sol_q = self.opti.value(self.var_q)
+ self.smooth_filter.add_data(sol_q)
+ sol_q = self.smooth_filter.filtered_data
- self.joint_smooth_filter.add_data(sol_q)
- sol_q = self.joint_smooth_filter.filtered_data
+ if current_lr_arm_motor_dq is not None:
+ v = current_lr_arm_motor_dq * 0.0
+ else:
+ v = (sol_q - self.init_data) * 0.0
- # self.vis.display(sol_q) # for visualization
self.init_data = sol_q
- if motorV is not None:
- v =motorV * 0.0
- else:
- v = (sol_q-self.init_data ) * 0.0
+ sol_tauff = pin.rnea(self.reduced_robot.model, self.reduced_robot.data, sol_q, v, np.zeros(self.reduced_robot.model.nv))
- tau_ff = pin.rnea(self.reduced_robot.model, self.reduced_robot.data, sol_q, v, np.zeros(self.reduced_robot.model.nv))
+ if self.Visualization:
+ self.vis.display(sol_q) # for visualization
- return sol_q, tau_ff ,True
+ return sol_q, sol_tauff
except Exception as e:
print(f"ERROR in convergence, plotting debug info.{e}")
- # sol_q = self.opti.debug.value(self.var_q) # return original value
- return sol_q, '',False
+
+ sol_q = self.opti.debug.value(self.var_q)
+ self.smooth_filter.add_data(sol_q)
+ sol_q = self.smooth_filter.filtered_data
+
+ if current_lr_arm_motor_dq is not None:
+ v = current_lr_arm_motor_dq * 0.0
+ else:
+ v = (sol_q - self.init_data) * 0.0
+
+ self.init_data = sol_q
+
+ sol_tauff = pin.rnea(self.reduced_robot.model, self.reduced_robot.data, sol_q, v, np.zeros(self.reduced_robot.model.nv))
+
+ print(f"sol_q:{sol_q} \nmotorstate: \n{current_lr_arm_motor_q} \nleft_pose: \n{left_wrist} \nright_pose: \n{right_wrist}")
+ if self.Visualization:
+ self.vis.display(sol_q) # for visualization
+
+ # return sol_q, sol_tauff
+ return current_lr_arm_motor_q, np.zeros(self.reduced_robot.model.nv)
if __name__ == "__main__":
- arm_ik = Arm_IK()
+ arm_ik = G1_29_ArmIK(Unit_Test = True, Visualization = True)
# initial positon
L_tf_target = pin.SE3(
pin.Quaternion(1, 0, 0, 0),
- np.array([0.23, +0.2, 0.2]),
+ np.array([0.25, +0.25, 0.1]),
)
R_tf_target = pin.SE3(
pin.Quaternion(1, 0, 0, 0),
- np.array([0.23, -0.2, 0.2]),
+ np.array([0.25, -0.25, 0.1]),
)
- rotation_speed = 0.005 # Rotation speed in radians per iteration
+ rotation_speed = 0.005
+ noise_amplitude_translation = 0.001
+ noise_amplitude_rotation = 0.1
- user_input = input("Please enter the start signal (enter 's' to start the subsequent program):")
+ user_input = input("Please enter the start signal (enter 's' to start the subsequent program):\n")
if user_input.lower() == 's':
-
- for i in range(150):
- angle = rotation_speed * i
- L_quat = pin.Quaternion(np.cos(angle / 2), 0, np.sin(angle / 2), 0) # y axis
- R_quat = pin.Quaternion(np.cos(angle / 2), 0, 0, np.sin(angle / 2)) # z axis
-
- L_tf_target.translation += np.array([0.001, 0.001, 0.001])
- R_tf_target.translation += np.array([0.001, -0.001, 0.001])
- L_tf_target.rotation = L_quat.toRotationMatrix()
- R_tf_target.rotation = R_quat.toRotationMatrix()
-
- arm_ik.ik_fun(L_tf_target.homogeneous, R_tf_target.homogeneous)
- time.sleep(0.05)
\ No newline at end of file
+ step = 0
+ while True:
+ # Apply rotation noise with bias towards y and z axes
+ rotation_noise_L = pin.Quaternion(
+ np.cos(np.random.normal(0, noise_amplitude_rotation) / 2),0,np.random.normal(0, noise_amplitude_rotation / 2),0).normalized() # y bias
+
+ rotation_noise_R = pin.Quaternion(
+ np.cos(np.random.normal(0, noise_amplitude_rotation) / 2),0,0,np.random.normal(0, noise_amplitude_rotation / 2)).normalized() # z bias
+
+ if step <= 120:
+ angle = rotation_speed * step
+ L_tf_target.rotation = (rotation_noise_L * pin.Quaternion(np.cos(angle / 2), 0, np.sin(angle / 2), 0)).toRotationMatrix() # y axis
+ R_tf_target.rotation = (rotation_noise_R * pin.Quaternion(np.cos(angle / 2), 0, 0, np.sin(angle / 2))).toRotationMatrix() # z axis
+ L_tf_target.translation += (np.array([0.001, 0.001, 0.001]) + np.random.normal(0, noise_amplitude_translation, 3))
+ R_tf_target.translation += (np.array([0.001, -0.001, 0.001]) + np.random.normal(0, noise_amplitude_translation, 3))
+ else:
+ angle = rotation_speed * (240 - step)
+ L_tf_target.rotation = (rotation_noise_L * pin.Quaternion(np.cos(angle / 2), 0, np.sin(angle / 2), 0)).toRotationMatrix() # y axis
+ R_tf_target.rotation = (rotation_noise_R * pin.Quaternion(np.cos(angle / 2), 0, 0, np.sin(angle / 2))).toRotationMatrix() # z axis
+ L_tf_target.translation -= (np.array([0.001, 0.001, 0.001]) + np.random.normal(0, noise_amplitude_translation, 3))
+ R_tf_target.translation -= (np.array([0.001, -0.001, 0.001]) + np.random.normal(0, noise_amplitude_translation, 3))
+
+ arm_ik.solve_ik(L_tf_target.homogeneous, R_tf_target.homogeneous)
+
+ step += 1
+ if step > 240:
+ step = 0
+ time.sleep(0.1)
\ No newline at end of file
diff --git a/teleop/robot_control/robot_hand.py b/teleop/robot_control/robot_hand_inspire.py
similarity index 68%
rename from teleop/robot_control/robot_hand.py
rename to teleop/robot_control/robot_hand_inspire.py
index 8ef3080..b452be1 100644
--- a/teleop/robot_control/robot_hand.py
+++ b/teleop/robot_control/robot_hand_inspire.py
@@ -1,32 +1,30 @@
-
+# this file is legacy, need to fix.
from unitree_dds_wrapper.idl import unitree_go
from unitree_dds_wrapper.publisher import Publisher
from unitree_dds_wrapper.subscription import Subscription
+from avp_teleoperate.teleop.open_television.constants import inspire_tip_indices
+from teleop.robot_control.hand_retargeting import HandRetargeting, HandType
import numpy as np
import threading
import time
+inspire_tip_indices = [4, 9, 14, 19, 24]
-class H1HandController:
+class InspireController:
def __init__(self):
self.cmd = unitree_go.msg.dds_.MotorCmds_()
self.state = unitree_go.msg.dds_.MotorStates_()
- self.labels = {
- "open": np.ones(6),
- "close": np.zeros(6),
- "half": np.full(6, 0.5)
- }
self.lock = threading.Lock()
- self.init_dds()
-
- def init_dds(self):
self.handcmd = Publisher(unitree_go.msg.dds_.MotorCmds_, "rt/inspire/cmd")
self.handstate = Subscription(unitree_go.msg.dds_.MotorStates_, "rt/inspire/state")
self.cmd.cmds = [unitree_go.msg.dds_.MotorCmd_() for _ in range(12)]
self.state.states = [unitree_go.msg.dds_.MotorState_() for _ in range(12)]
- self.report_rpy_thread = threading.Thread(target=self.subscribe_state)
- self.report_rpy_thread.start()
+ self.subscribe_state_thread = threading.Thread(target=self.subscribe_state)
+ self.subscribe_state_thread.daemon = True
+ self.subscribe_state_thread.start()
+
+ self.hand_retargeting = HandRetargeting(HandType.INSPIRE_HAND)
def subscribe_state(self):
while True:
@@ -34,23 +32,14 @@ class H1HandController:
self.state = self.handstate.msg
time.sleep(0.01)
- def ctrl(self, label):
- if label in self.labels:
- self._ctrl(self.labels[label], self.labels[label])
- else:
- print(f"Invalid label: {label}")
-
- def crtl(self,right_angles,left_angles):
- self._ctrl(right_angles,left_angles)
-
- def _ctrl(self, right_angles, left_angles):
+ def ctrl(self, left_angles, right_angles):
for i in range(6):
self.cmd.cmds[i].q = right_angles[i]
self.cmd.cmds[i+6].q = left_angles[i]
self.handcmd.msg.cmds = self.cmd.cmds
self.handcmd.write()
- def get_hand_state(self):
+ def get_current_dual_hand_q(self):
with self.lock:
q = np.array([self.state.states[i].q for i in range(12)])
return q
diff --git a/teleop/robot_control/robot_hand_unitree.py b/teleop/robot_control/robot_hand_unitree.py
new file mode 100644
index 0000000..db845e6
--- /dev/null
+++ b/teleop/robot_control/robot_hand_unitree.py
@@ -0,0 +1,97 @@
+from unitree_dds_wrapper.robots.trihand.trihand_pub_cmd import UnitreeTrihand as trihand_pub
+from unitree_dds_wrapper.robots.trihand.trihand_sub_state import UnitreeTrihand as trihand_sub
+
+import numpy as np
+import time
+from multiprocessing import Array
+from teleop.robot_control.hand_retargeting import HandRetargeting, HandType
+import threading
+
+unitree_tip_indices = [4, 9, 14]
+
+class Dex3_1_Controller:
+ def __init__(self, fps = 100.0):
+ self.dex3_pub = trihand_pub()
+
+ kp = np.full(7, 1.5)
+ kd = np.full(7, 0.2)
+ q = np.full(7,0.0)
+ dq = np.full(7,0.0)
+ tau = np.full(7,0.0)
+ self.dex3_pub.left_hand.kp = kp
+ self.dex3_pub.left_hand.kd = kd
+ self.dex3_pub.left_hand.q = q
+ self.dex3_pub.left_hand.dq = dq
+ self.dex3_pub.left_hand.tau = tau
+
+ self.dex3_pub.right_hand.kp = kp
+ self.dex3_pub.right_hand.kd = kd
+ self.dex3_pub.right_hand.q = q
+ self.dex3_pub.right_hand.dq = dq
+ self.dex3_pub.right_hand.tau = tau
+
+ self.dual_hand_state_array = [0.0] * 14
+ self.lr_hand_state_lock = threading.Lock()
+ # self.dual_hand_state_array = Array('d', 14, lock=True)
+
+ self.sub_state = trihand_sub()
+ self.sub_state.wait_for_connection()
+
+ self.subscribe_state_thread = threading.Thread(target=self.subscribe_state)
+ self.subscribe_state_thread.daemon = True
+ self.subscribe_state_thread.start()
+
+ self.hand_retargeting = HandRetargeting(HandType.UNITREE_DEX3)
+
+ self.running = True
+ self.fps = fps
+
+ print("UnitreeDex3 Controller init ok.\n")
+
+ def subscribe_state(self):
+ while True:
+ lq,rq= self.sub_state.sub()
+ with self.lr_hand_state_lock:
+ self.dual_hand_state_array[:] = np.concatenate((lq, rq))
+ # self.dual_hand_state_array[:] = np.concatenate((lq,rq))
+ time.sleep(0.002)
+
+
+ def ctrl(self, left_angles, right_angles):
+ """set current left, right hand motor state target q"""
+ self.dex3_pub.left_hand.q = left_angles
+ self.dex3_pub.right_hand.q = right_angles
+ self.dex3_pub.pub()
+ # print("hand ctrl publish ok.")
+
+ def get_current_dual_hand_q(self):
+ """return current left, right hand motor state q"""
+ with self.lr_hand_state_lock:
+ return self.dual_hand_state_array[:].copy()
+
+ def control_process(self, left_hand_array, right_hand_array, dual_hand_state_array = None, dual_hand_aciton_array = None):
+ left_qpos = np.full(7, 0)
+ right_qpos = np.full(7, 0)
+ try:
+ while self.running:
+ start_time = time.time()
+ left_hand_mat = np.array(left_hand_array[:]).reshape(25, 3).copy()
+ right_hand_mat = np.array(right_hand_array[:]).reshape(25, 3).copy()
+
+ is_initial = np.all(left_hand_mat == 0.0)
+ if not is_initial:
+ left_qpos = self.hand_retargeting.left_retargeting.retarget(left_hand_mat[unitree_tip_indices])[[0,1,2,3,4,5,6]]
+ right_qpos = self.hand_retargeting.right_retargeting.retarget(right_hand_mat[unitree_tip_indices])[[0,1,2,3,4,5,6]]
+
+ self.ctrl(left_qpos, right_qpos)
+
+ if dual_hand_state_array and dual_hand_aciton_array:
+ dual_hand_state_array[:] = self.get_current_dual_hand_q()
+ dual_hand_aciton_array[:] = np.concatenate((left_qpos, right_qpos))
+
+ current_time = time.time()
+ time_elapsed = current_time - start_time
+ sleep_time = max(0, (1 / self.fps) - time_elapsed)
+ time.sleep(sleep_time)
+ finally:
+ print("Dex3_1_Controller has been closed.")
\ No newline at end of file
diff --git a/teleop/teleop_active_cam.py b/teleop/teleop_active_cam.py
deleted file mode 100644
index 69952eb..0000000
--- a/teleop/teleop_active_cam.py
+++ /dev/null
@@ -1,86 +0,0 @@
-import math
-import numpy as np
-
-np.set_printoptions(precision=2, suppress=True)
-import matplotlib.pyplot as plt
-from scipy.spatial.transform import Rotation as R
-from pytransform3d import rotations
-
-import time
-import cv2
-from constants_vuer import *
-from TeleVision import OpenTeleVision
-import pyzed.sl as sl
-from dynamixel.active_cam import DynamixelAgent
-from multiprocessing import Array, Process, shared_memory, Queue, Manager, Event, Semaphore
-
-resolution = (720, 1280)
-crop_size_w = 1
-crop_size_h = 0
-resolution_cropped = (resolution[0] - crop_size_h, resolution[1] - 2 * crop_size_w)
-
-agent = DynamixelAgent(port="/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT8IT033-if00-port0")
-agent._robot.set_torque_mode(True)
-
-# Create a Camera object
-zed = sl.Camera()
-
-# Create a InitParameters object and set configuration parameters
-init_params = sl.InitParameters()
-init_params.camera_resolution = sl.RESOLUTION.HD720 # Use HD720 opr HD1200 video mode, depending on camera type.
-init_params.camera_fps = 60 # Set fps at 60
-
-# Open the camera
-err = zed.open(init_params)
-if err != sl.ERROR_CODE.SUCCESS:
- print("Camera Open : " + repr(err) + ". Exit program.")
- exit()
-
-# Capture 50 frames and stop
-i = 0
-image_left = sl.Mat()
-image_right = sl.Mat()
-runtime_parameters = sl.RuntimeParameters()
-
-img_shape = (resolution_cropped[0], 2 * resolution_cropped[1], 3)
-img_height, img_width = resolution_cropped[:2]
-shm = shared_memory.SharedMemory(create=True, size=np.prod(img_shape) * np.uint8().itemsize)
-img_array = np.ndarray((img_shape[0], img_shape[1], 3), dtype=np.uint8, buffer=shm.buf)
-image_queue = Queue()
-toggle_streaming = Event()
-tv = OpenTeleVision(resolution_cropped, shm.name, image_queue, toggle_streaming)
-
-while True:
- start = time.time()
-
- head_mat = grd_yup2grd_zup[:3, :3] @ tv.head_matrix[:3, :3] @ grd_yup2grd_zup[:3, :3].T
- if np.sum(head_mat) == 0:
- head_mat = np.eye(3)
- head_rot = rotations.quaternion_from_matrix(head_mat[0:3, 0:3])
- try:
- ypr = rotations.euler_from_quaternion(head_rot, 2, 1, 0, False)
- # print(ypr)
- # agent._robot.command_joint_state([0., 0.4])
- agent._robot.command_joint_state(ypr[:2])
- # print("success")
- except:
- # print("failed")
- # exit()
- pass
-
- if zed.grab(runtime_parameters) == sl.ERROR_CODE.SUCCESS:
- zed.retrieve_image(image_left, sl.VIEW.LEFT)
- zed.retrieve_image(image_right, sl.VIEW.RIGHT)
- timestamp = zed.get_timestamp(sl.TIME_REFERENCE.CURRENT) # Get the timestamp at the time the image was captured
- # print("Image resolution: {0} x {1} || Image timestamp: {2}\n".format(image.get_width(), image.get_height(),
- # timestamp.get_milliseconds()))
-
- bgr = np.hstack((image_left.numpy()[crop_size_h:, crop_size_w:-crop_size_w],
- image_right.numpy()[crop_size_h:, crop_size_w:-crop_size_w]))
- rgb = cv2.cvtColor(bgr, cv2.COLOR_BGRA2RGB)
-
- np.copyto(img_array, rgb)
-
- end = time.time()
- # print(1/(end-start))
-zed.close()
\ No newline at end of file
diff --git a/teleop/teleop_hand_and_arm.py b/teleop/teleop_hand_and_arm.py
index 293f64a..75eed7a 100644
--- a/teleop/teleop_hand_and_arm.py
+++ b/teleop/teleop_hand_and_arm.py
@@ -1,19 +1,9 @@
import numpy as np
-
-from TeleVision import OpenTeleVision
-from Preprocessor import VuerPreprocessor
-from constants_vuer import tip_indices
-from dex_retargeting.retargeting_config import RetargetingConfig
-
-from pathlib import Path
import time
-import yaml
-from multiprocessing import Process, shared_memory, Queue, Manager, Event, Lock
-
+import argparse
import cv2
-import zmq
-import pickle
-import zlib
+from multiprocessing import Process, shared_memory, Array
+import threading
import os
import sys
@@ -21,146 +11,170 @@ current_dir = os.path.dirname(os.path.abspath(__file__))
parent_dir = os.path.dirname(current_dir)
sys.path.append(parent_dir)
-from robot_control.robot_hand import H1HandController
-from teleop.robot_control.robot_arm import H1ArmController
-from teleop.robot_control.robot_arm_ik import Arm_IK
-
-
-def image_receiver(image_queue, resolution, crop_size_w, crop_size_h):
- context = zmq.Context()
- socket = context.socket(zmq.PULL)
- socket.connect("tcp://192.168.123.162:5555")
-
- while True:
- compressed_data = b''
- while True:
- chunk = socket.recv()
- compressed_data += chunk
- if len(chunk) < 60000:
- break
- data = zlib.decompress(compressed_data)
- frame_data = pickle.loads(data)
-
- # Decode and display the image
- frame = cv2.imdecode(frame_data, cv2.IMREAD_COLOR)
- sm.write_image(frame)
- # Control receiving frequency
- time.sleep(0.01)
-
-class SharedMemoryImage:
- def __init__(self, img_shape):
- self.resolution = img_shape#(720, 1280)
- self.crop_size_w = 0
- self.crop_size_h = 0
- self.resolution_cropped = (self.resolution[0]-self.crop_size_h, self.resolution[1] - 2 * self.crop_size_w)
-
- self.img_shape = (self.resolution_cropped[0], 2 * self.resolution_cropped[1], 3)
- self.img_height, self.img_width = self.resolution_cropped[:2]
-
- self.shm = shared_memory.SharedMemory(create=True, size=np.prod(self.img_shape) * np.uint8().itemsize)
- self.img_array = np.ndarray((self.img_shape[0], self.img_shape[1], 3), dtype=np.uint8, buffer=self.shm.buf)
- self.lock = Lock()
-
- def write_image(self, image):
- with self.lock:
- np.copyto(self.img_array, image)
-
- def read_image(self):
- with self.lock:
- image_copy = self.img_array.copy()
- return image_copy
-
- def cleanup(self):
- self.shm.close()
- self.shm.unlink()
-
-class VuerTeleop:
- def __init__(self, config_file_path):
- self.resolution = (480,640) #(720, 1280)
- self.crop_size_w = 0
- self.crop_size_h = 0
- self.resolution_cropped = (self.resolution[0]-self.crop_size_h, self.resolution[1]-2*self.crop_size_w)
-
- self.img_shape = (self.resolution_cropped[0], 2 * self.resolution_cropped[1], 3)
- self.img_height, self.img_width = self.resolution_cropped[:2]
-
- self.shm = shared_memory.SharedMemory(create=True, size=np.prod(self.img_shape) * np.uint8().itemsize)
- self.img_array = np.ndarray((self.img_shape[0], self.img_shape[1], 3), dtype=np.uint8, buffer=self.shm.buf)
- image_queue = Queue()
- toggle_streaming = Event()
- self.tv = OpenTeleVision(self.resolution_cropped, self.shm.name, image_queue, toggle_streaming)
- self.processor = VuerPreprocessor()
-
- RetargetingConfig.set_default_urdf_dir('../assets')
- with Path(config_file_path).open('r') as f:
- cfg = yaml.safe_load(f)
- left_retargeting_config = RetargetingConfig.from_dict(cfg['left'])
- right_retargeting_config = RetargetingConfig.from_dict(cfg['right'])
- self.left_retargeting = left_retargeting_config.build()
- self.right_retargeting = right_retargeting_config.build()
-
- def step(self):
- head_mat, left_wrist_mat, right_wrist_mat, left_hand_mat, right_hand_mat = self.processor.process(self.tv)
- head_rmat = head_mat[:3, :3]
-
- left_wrist_mat[2, 3] +=0.45
- right_wrist_mat[2,3] +=0.45
- left_wrist_mat[0, 3] +=0.20
- right_wrist_mat[0,3] +=0.20
-
- left_qpos = self.left_retargeting.retarget(left_hand_mat[tip_indices])[[4, 5, 6, 7, 10, 11, 8, 9, 0, 1, 2, 3]]
- right_qpos = self.right_retargeting.retarget(right_hand_mat[tip_indices])[[4, 5, 6, 7, 10, 11, 8, 9, 0, 1, 2, 3]]
-
- return head_rmat, left_wrist_mat, right_wrist_mat, left_qpos, right_qpos
+from teleop.open_television.tv_wrapper import TeleVisionWrapper
+from teleop.robot_control.robot_arm import G1_29_ArmController
+from teleop.robot_control.robot_arm_ik import G1_29_ArmIK
+from teleop.robot_control.robot_hand_unitree import Dex3_1_Controller
+from teleop.image_server.image_client import ImageClient
+from teleop.utils.episode_writer import EpisodeWriter
if __name__ == '__main__':
- manager = Manager()
- image_queue = manager.Queue()
- teleoperator = VuerTeleop('inspire_hand.yml')
- h1hand = H1HandController()
- h1arm = H1ArmController()
- arm_ik = Arm_IK()
- sm = SharedMemoryImage((480,640))
- image_process = Process(target=image_receiver, args=(sm, teleoperator.resolution, teleoperator.crop_size_w, teleoperator.crop_size_h))
- image_process.start()
-
+ parser = argparse.ArgumentParser()
+ parser.add_argument('--record', type=bool, default=True, help='save data or not')
+ parser.add_argument('--task_dir', type=str, default='data', help='path to save data')
+ parser.add_argument('--frequency', type=int, default=30.0, help='save data\'s frequency')
+ args = parser.parse_args()
+ print(f"args:{args}\n")
+
+ # image
+ img_shape = (480, 640 * 2, 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)
+ img_client = ImageClient(img_shape = img_shape, img_shm_name = img_shm.name)
+ image_receive_thread = threading.Thread(target=img_client.receive_process, daemon=True)
+ image_receive_thread.daemon = True
+ image_receive_thread.start()
+
+ # television and arm
+ tv_wrapper = TeleVisionWrapper(img_shape, img_shm.name)
+ arm_ctrl = G1_29_ArmController()
+ arm_ik = G1_29_ArmIK()
+
+ # hand
+ hand_ctrl = Dex3_1_Controller()
+ left_hand_array = Array('d', 75, lock=True)
+ right_hand_array = Array('d', 75, lock=True)
+ dual_hand_state_array = Array('d', 14, lock=True) # current left, right hand state data
+ dual_hand_aciton_array = Array('d', 14, lock=True) # current left and right hand action data to be controlled
+ hand_control_process = Process(target=hand_ctrl.control_process, args=(left_hand_array, right_hand_array, dual_hand_state_array, dual_hand_aciton_array))
+ hand_control_process.daemon = True
+ hand_control_process.start()
+
+ if args.record:
+ recorder = EpisodeWriter(task_dir=args.task_dir, frequency=args.frequency)
+
try:
- user_input = input("Please enter the start signal (enter 's' to start the subsequent program):")
- if user_input.lower() == 's':
- while True:
- armstate = None
- armv = None
- frame = sm.read_image()
- np.copyto(teleoperator.img_array, np.array(frame))
- handstate = h1hand.get_hand_state()
-
- q_poseList=np.zeros(35)
- q_tau_ff=np.zeros(35)
- armstate,armv = h1arm.GetMotorState()
-
- head_rmat, left_pose, right_pose, left_qpos, right_qpos = teleoperator.step()
- sol_q ,tau_ff, flag = arm_ik.ik_fun(left_pose, right_pose, armstate,armv)
-
- if flag:
- q_poseList[13:27] = sol_q
- q_tau_ff[13:27] = tau_ff
- else:
- q_poseList[13:27] = armstate
- q_tau_ff = np.zeros(35)
-
- h1arm.SetMotorPose(q_poseList, q_tau_ff)
-
- if right_pose is not None and left_qpos is not None:
- # 4,5: index 6,7: middle, 0,1: pinky, 2,3: ring, 8,9: thumb
- right_angles = [1.7 - right_qpos[i] for i in [4, 6, 2, 0]]
- right_angles.append(1.2 - right_qpos[8])
- right_angles.append(0.5 - right_qpos[9])
-
- left_angles = [1.7- left_qpos[i] for i in [4, 6, 2, 0]]
- left_angles.append(1.2 - left_qpos[8])
- left_angles.append(0.5 - left_qpos[9])
- h1hand.crtl(right_angles,left_angles)
+ user_input = input("Please enter the start signal (enter 'r' to start the subsequent program):\n")
+ if user_input.lower() == 'r':
+ arm_ctrl.speed_gradual_max()
+ if args.record:
+ press_key_s_count = 0
+
+ running = True
+ recording = False
+ while running:
+ start_time = time.time()
+ head_rmat, left_wrist, right_wrist, left_hand, right_hand = tv_wrapper.get_data()
+
+ # send hand skeleton data to hand_ctrl.control_process
+ left_hand_array[:] = left_hand.flatten()
+ right_hand_array[:] = right_hand.flatten()
+
+ # get current arm motor data. solve ik using motor data and wrist pose, then use ik results to control arms.
+ time_ik_start = time.time()
+ current_lr_arm_q = arm_ctrl.get_current_dual_arm_q()
+ current_lr_arm_dq = arm_ctrl.get_current_dual_arm_dq()
+ sol_q, sol_tauff = arm_ik.solve_ik(left_wrist, right_wrist, current_lr_arm_q, current_lr_arm_dq)
+ time_ik_end = time.time()
+ # print(f"ik:\t{round(time_ik_end - time_ik_start, 6)}")
+ arm_ctrl.ctrl_dual_arm(sol_q, sol_tauff)
+
+ # record data
+ if args.record:
+ current_image = img_array.copy()
+ left_image = current_image[:, :640]
+ right_image = current_image[:, 640:]
+ left_arm_state = current_lr_arm_q[:7]
+ right_arm_state = current_lr_arm_q[-7:]
+ left_hand_state = dual_hand_state_array[:7]
+ right_hand_state = dual_hand_state_array[-7:]
+ left_arm_action = sol_q[:7]
+ right_arm_action = sol_q[-7:]
+ left_hand_action = dual_hand_aciton_array[:7]
+ right_hand_action = dual_hand_aciton_array[-7:]
+
+ cv2.imshow("record image", current_image)
+ key = cv2.waitKey(1) & 0xFF
+ if key == ord('q'):
+ running = False
+ elif key == ord('s'):
+ press_key_s_count += 1
+ if press_key_s_count % 2 == 1:
+ print("Start recording...")
+ recording = True
+ recorder.create_episode()
+ else:
+ print("End recording...")
+ recording = False
+ recorder.save_episode()
+
+ if recording:
+ colors = {}
+ depths = {}
+ colors[f"color_{0}"] = left_image
+ colors[f"color_{1}"] = right_image
+ states = {
+ "left_arm": {
+ "qpos": left_arm_state.tolist(), # numpy.array -> list
+ "qvel": [],
+ "torque": [],
+ },
+ "right_arm": {
+ "qpos": right_arm_state.tolist(),
+ "qvel": [],
+ "torque": [],
+ },
+ "left_hand": {
+ "qpos": left_hand_state, # Array returns a list after slicing
+ "qvel": [],
+ "torque": [],
+ },
+ "right_hand": {
+ "qpos": right_hand_state,
+ "qvel": [],
+ "torque": [],
+ },
+ "body": None,
+ }
+ actions = {
+ "left_arm": {
+ "qpos": left_arm_action.tolist(),
+ "qvel": [],
+ "torque": [],
+ },
+ "right_arm": {
+ "qpos": right_arm_action.tolist(),
+ "qvel": [],
+ "torque": [],
+ },
+ "left_hand": {
+ "qpos": left_hand_action,
+ "qvel": [],
+ "torque": [],
+ },
+ "right_hand": {
+ "qpos": right_hand_action,
+ "qvel": [],
+ "torque": [],
+ },
+ "body": None,
+ }
+ recorder.add_item(colors=colors, depths=depths, states=states, actions=actions)
+
+ current_time = time.time()
+ time_elapsed = current_time - start_time
+ sleep_time = max(0, (1 / float(args.frequency)) - time_elapsed)
+ time.sleep(sleep_time)
+ # print(f"main process sleep: {sleep_time}")
except KeyboardInterrupt:
+ img_shm.unlink()
+ img_shm.close()
+ print("KeyboardInterrupt, exiting program...")
exit(0)
+ finally:
+ img_shm.unlink()
+ img_shm.close()
+ print("Finally, exiting program...")
+ exit(0)
\ No newline at end of file
diff --git a/teleop/teleop_hand.py b/teleop/teleop_test_gym.py
similarity index 75%
rename from teleop/teleop_hand.py
rename to teleop/teleop_test_gym.py
index 9dce152..252a9b7 100644
--- a/teleop/teleop_hand.py
+++ b/teleop/teleop_test_gym.py
@@ -1,61 +1,21 @@
+# TODO: this file need to be fixed.
from isaacgym import gymapi
-from isaacgym import gymutil
from isaacgym import gymtorch
-
import math
import numpy as np
import torch
-
-from TeleVision import OpenTeleVision
-from Preprocessor import VuerPreprocessorLegacy as VuerPreprocessor
-from constants_vuer import tip_indices
-from dex_retargeting.retargeting_config import RetargetingConfig
+import time
from pytransform3d import rotations
-from pathlib import Path
-import argparse
-import time
-import yaml
-from multiprocessing import Array, Process, shared_memory, Queue, Manager, Event, Semaphore
-
-class VuerTeleop:
- def __init__(self, config_file_path):
- self.resolution = (720, 1280)
- self.crop_size_w = 0
- self.crop_size_h = 0
- self.resolution_cropped = (self.resolution[0]-self.crop_size_h, self.resolution[1]-2*self.crop_size_w)
-
- self.img_shape = (self.resolution_cropped[0], 2 * self.resolution_cropped[1], 3)
- self.img_height, self.img_width = self.resolution_cropped[:2]
-
- self.shm = shared_memory.SharedMemory(create=True, size=np.prod(self.img_shape) * np.uint8().itemsize)
- self.img_array = np.ndarray((self.img_shape[0], self.img_shape[1], 3), dtype=np.uint8, buffer=self.shm.buf)
- image_queue = Queue()
- toggle_streaming = Event()
- self.tv = OpenTeleVision(self.resolution_cropped, self.shm.name, image_queue, toggle_streaming)
- self.processor = VuerPreprocessor()
-
- RetargetingConfig.set_default_urdf_dir('../assets')
- with Path(config_file_path).open('r') as f:
- cfg = yaml.safe_load(f)
- left_retargeting_config = RetargetingConfig.from_dict(cfg['left'])
- right_retargeting_config = RetargetingConfig.from_dict(cfg['right'])
- self.left_retargeting = left_retargeting_config.build()
- self.right_retargeting = right_retargeting_config.build()
-
- def step(self):
- head_mat, left_wrist_mat, right_wrist_mat, left_hand_mat, right_hand_mat = self.processor.process(self.tv)
-
- head_rmat = head_mat[:3, :3]
-
- left_pose = np.concatenate([left_wrist_mat[:3, 3] + np.array([-0.6, 0, 1.6]),
- rotations.quaternion_from_matrix(left_wrist_mat[:3, :3])[[1, 2, 3, 0]]])
- right_pose = np.concatenate([right_wrist_mat[:3, 3] + np.array([-0.6, 0, 1.6]),
- rotations.quaternion_from_matrix(right_wrist_mat[:3, :3])[[1, 2, 3, 0]]])
- left_qpos = self.left_retargeting.retarget(left_hand_mat[tip_indices])[[4, 5, 6, 7, 10, 11, 8, 9, 0, 1, 2, 3]]
- right_qpos = self.right_retargeting.retarget(right_hand_mat[tip_indices])[[4, 5, 6, 7, 10, 11, 8, 9, 0, 1, 2, 3]]
-
- return head_rmat, left_pose, right_pose, left_qpos, right_qpos
+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,
@@ -104,8 +64,8 @@ class Sim:
cube_asset = self.gym.create_box(self.sim, 0.05, 0.05, 0.05, cube_asset_options)
asset_root = "../assets"
- left_asset_path = "inspire_hand/inspire_hand_left.urdf"
- right_asset_path = "inspire_hand/inspire_hand_right.urdf"
+ 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
@@ -252,15 +212,36 @@ class Sim:
if __name__ == '__main__':
- teleoperator = VuerTeleop('inspire_hand.yml')
+ # 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:
- head_rmat, left_pose, right_pose, left_qpos, right_qpos = teleoperator.step()
- left_img, right_img = simulator.step(head_rmat, left_pose, right_pose, left_qpos, right_qpos)
- np.copyto(teleoperator.img_array, np.hstack((left_img, right_img)))
-
+ 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)
diff --git a/teleop/utils/episode_writer.py b/teleop/utils/episode_writer.py
new file mode 100755
index 0000000..7d3e50f
--- /dev/null
+++ b/teleop/utils/episode_writer.py
@@ -0,0 +1,142 @@
+import os
+import cv2
+import json
+import datetime
+import numpy as np
+import time
+
+
+class EpisodeWriter(object):
+ def __init__(self, task_dir, frequency=30, image_size=[640, 480]):
+ """
+ image_size: [width, height]
+ """
+ print("==> EpisodeWriter initializing...\n")
+ self.task_dir = task_dir
+ self.frequency = frequency
+ self.image_size = image_size
+
+ self.data = {}
+ self.episode_data = []
+ self.item_id = -1
+ self.episode_id = -1
+ if os.path.exists(self.task_dir):
+ episode_dirs = [episode_dir for episode_dir in os.listdir(self.task_dir) if 'episode_' in episode_dir]
+ episode_last = sorted(episode_dirs)[-1] if len(episode_dirs) > 0 else None
+ self.episode_id = 0 if episode_last is None else int(episode_last.split('_')[-1])
+ print(f"==> task_dir directory already exist, now self.episode_id isοΌ{self.episode_id}\n")
+ else:
+ os.makedirs(self.task_dir)
+ print(f"==> episode directory does not exist, now create one.\n")
+ self.data_info()
+ self.text_desc()
+ print("==> EpisodeWriter initialized successfully.\n")
+
+ def data_info(self, version='1.0.0', date=None, author=None):
+ self.info = {
+ "version": "1.0.0" if version is None else version,
+ "date": "" if date is None else datetime.date.today().strftime('%Y-%m-%d'),
+ "author": "unitree" if author is None else author,
+ "image": {"width":self.image_size[0], "height":self.image_size[1], "fps":self.frequency},
+ "depth": {"width":self.image_size[0], "height":self.image_size[1], "fps":self.frequency},
+ "audio": {"sample_rate": 16000, "channels": 1, "format":"PCM", "bits":16}, # PCM_S16
+ "joint_names":{
+ "left_arm": ['kLeftShoulderPitch' ,'kLeftShoulderRoll', 'kLeftShoulderYaw', 'kLeftElbow', 'kLeftWristRoll', 'kLeftWristPitch', 'kLeftWristyaw'],
+ "left_hand": [],
+ "right_arm": [],
+ "right_hand": [],
+ "body": [],
+ },
+
+ "tactile_names": {
+ "left_hand": [],
+ "right_hand": [],
+ },
+ }
+ def text_desc(self):
+ self.text = {
+ "goal": "Pick up the red cup on the table.",
+ "desc": "Pick up the cup from the table and place it in another position. The operation should be smooth and the water in the cup should not spill out",
+ "steps":"step1: searching for cups. step2: go to the target location. step3: pick up the cup",
+ }
+
+
+ def create_episode(self):
+ """
+ Create a new episode, each episode needs to specify the episode_id.
+ text: Text descriptions of operation goals, steps, etc. The text description of each episode is the same.
+ goal: operation goal
+ desc: description
+ steps: operation steps
+ """
+
+ self.item_id = -1
+ self.episode_data = []
+ self.episode_id = self.episode_id + 1
+
+ self.episode_dir = os.path.join(self.task_dir, f"episode_{str(self.episode_id).zfill(4)}")
+ self.color_dir = os.path.join(self.episode_dir, 'colors')
+ self.depth_dir = os.path.join(self.episode_dir, 'depths')
+ self.audio_dir = os.path.join(self.episode_dir, 'audios')
+ self.json_path = os.path.join(self.episode_dir, 'data.json')
+ os.makedirs(self.episode_dir, exist_ok=True)
+ os.makedirs(self.color_dir, exist_ok=True)
+ os.makedirs(self.depth_dir, exist_ok=True)
+ os.makedirs(self.audio_dir, exist_ok=True)
+
+ def add_item(self, colors, depths=None, states=None, actions=None, tactiles=None, audios=None, log = True):
+ self.item_id += 1
+ item_data = {
+ 'idx': self.item_id,
+ 'colors': {"color_0": None},
+ 'depths': {"depth_0": None},
+ 'states': {'left_arm':{}, 'right_arm':{}, 'left_hand':{}, 'right_hand':{}, 'body': {}},
+ 'actions': {'left_arm':{}, 'right_arm':{}, 'left_hand':{}, 'right_hand':{}, 'body': {}},
+ 'tactiles': {'left_hand':[], 'right_hand':[]},
+ 'audios': { "mic0": None},
+ }
+
+ # save images
+ if colors is not None:
+ for idx, (_, color) in enumerate(colors.items()):
+ color_key = f'color_{idx}'
+ color_name = f'{str(self.item_id).zfill(6)}_{color_key}.jpg'
+ cv2.imwrite(os.path.join(self.color_dir, color_name), color)
+ item_data['colors'][color_key] = os.path.join('colors', color_name)
+
+ # save depths
+ if depths is not None:
+ for idx, (_, depth) in enumerate(depths.items()):
+ depth_key = f'depth_{idx}'
+ depth_name = f'{str(self.item_id).zfill(6)}_{depth_key}.png'
+ cv2.imwrite(os.path.join(self.depth_dir, depth_name), depth)
+ item_data['depths'][depth_key] = os.path.join('depths', depth_name)
+
+ # save audios
+ if audios is not None:
+ for mic, audio in audios.items():
+ audio_name = f'audio_{str(self.item_id).zfill(6)}_{mic}.npy'
+ np.save(os.path.join(self.audio_dir, audio_name), audio.astype(np.int16))
+ item_data['audios'][mic] = os.path.join('audios', audio_name)
+
+ item_data['states'] = states
+ item_data['actions'] = actions
+ item_data['tactiles'] = tactiles
+
+ self.episode_data.append(item_data)
+
+ if log:
+ curent_record_time = time.time()
+ print(f"==> episode_id:{self.episode_id} item_id:{self.item_id} current_time:{curent_record_time}")
+
+
+ def save_episode(self):
+ """
+ with open("./hmm.json",'r',encoding='utf-8') as json_file:
+ model=json.load(json_file)
+ """
+ self.data['info'] = self.info
+ self.data['text'] = self.text
+ self.data['data'] = self.episode_data
+ with open(self.json_path,'w',encoding='utf-8') as jsonf:
+ jsonf.write(json.dumps(self.data, indent=4, ensure_ascii=False))
\ No newline at end of file
diff --git a/teleop/motion_utils.py b/teleop/utils/mat_tool.py
similarity index 94%
rename from teleop/motion_utils.py
rename to teleop/utils/mat_tool.py
index fc68166..d3ad531 100644
--- a/teleop/motion_utils.py
+++ b/teleop/utils/mat_tool.py
@@ -11,4 +11,4 @@ def fast_mat_inv(mat):
ret = np.eye(4)
ret[:3, :3] = mat[:3, :3].T
ret[:3, 3] = -mat[:3, :3].T @ mat[:3, 3]
- return ret
+ return ret
\ No newline at end of file
diff --git a/teleop/robot_control/joint_smooth.py b/teleop/utils/weighted_moving_filter.py
similarity index 90%
rename from teleop/robot_control/joint_smooth.py
rename to teleop/utils/weighted_moving_filter.py
index d8a1ae2..c0c9769 100644
--- a/teleop/robot_control/joint_smooth.py
+++ b/teleop/utils/weighted_moving_filter.py
@@ -24,6 +24,10 @@ class WeightedMovingFilter:
def add_data(self, new_data):
assert len(new_data) == self._data_size
+
+ if len(self._data_queue) > 0 and np.array_equal(new_data, self._data_queue[-1]):
+ return # skip duplicate data
+
if len(self._data_queue) >= self._window_size:
self._data_queue.pop(0)
@@ -61,7 +65,7 @@ def visualize_filter_comparison(filter_params, steps):
# col0 should not 2b filtered
plt.subplot(len(filter_params), 2, idx * 2 + 1)
- plt.plot(filtered_data[:, 0], label=f'Filtered (Window {len(weights)})')
+ plt.plot(filtered_data[:, 0], label=f'Filtered (Window {filter._window_size})')
plt.plot(original_data[:, 0], 'r--', label='Original', alpha=0.5)
plt.title(f'Joint 1 - Should not to be filtered.')
plt.xlabel('Step')
@@ -70,9 +74,9 @@ def visualize_filter_comparison(filter_params, steps):
# col13 should 2b filtered
plt.subplot(len(filter_params), 2, idx * 2 + 2)
- plt.plot(filtered_data[:, 13], label=f'Filtered (Window {len(weights)})')
+ plt.plot(filtered_data[:, 13], label=f'Filtered (Window {filter._window_size})')
plt.plot(original_data[:, 13], 'r--', label='Original', alpha=0.5)
- plt.title(f'Joint 13 - Window {len(weights)}, Weights {weights}')
+ plt.title(f'Joint 13 - Window {filter._window_size}, Weights {weights}')
plt.xlabel('Step')
plt.ylabel('Value')
plt.legend()
diff --git a/teleop/webrtc/client.js b/teleop/webrtc/client.js
deleted file mode 100644
index b4e8c6c..0000000
--- a/teleop/webrtc/client.js
+++ /dev/null
@@ -1,77 +0,0 @@
-var pc = null;
-
-function negotiate() {
- pc.addTransceiver('video', { direction: 'recvonly' });
- pc.addTransceiver('audio', { direction: 'recvonly' });
- return pc.createOffer().then((offer) => {
- return pc.setLocalDescription(offer);
- }).then(() => {
- // wait for ICE gathering to complete
- return new Promise((resolve) => {
- if (pc.iceGatheringState === 'complete') {
- resolve();
- } else {
- const checkState = () => {
- if (pc.iceGatheringState === 'complete') {
- pc.removeEventListener('icegatheringstatechange', checkState);
- resolve();
- }
- };
- pc.addEventListener('icegatheringstatechange', checkState);
- }
- });
- }).then(() => {
- var offer = pc.localDescription;
- return fetch('/offer', {
- body: JSON.stringify({
- sdp: offer.sdp,
- type: offer.type,
- }),
- headers: {
- 'Content-Type': 'application/json'
- },
- method: 'POST'
- });
- }).then((response) => {
- return response.json();
- }).then((answer) => {
- console.log(">>>", answer);
- return pc.setRemoteDescription(answer);
- }).catch((e) => {
- alert(e);
- });
-}
-
-function start() {
- var config = {
- sdpSemantics: 'unified-plan'
- };
-
- if (document.getElementById('use-stun').checked) {
- config.iceServers = [{ urls: ['stun:stun.l.google.com:19302'] }];
- }
-
- pc = new RTCPeerConnection(config);
-
- // connect audio / video
- pc.addEventListener('track', (evt) => {
- if (evt.track.kind == 'video') {
- document.getElementById('video').srcObject = evt.streams[0];
- } else {
- document.getElementById('audio').srcObject = evt.streams[0];
- }
- });
-
- document.getElementById('start').style.display = 'none';
- negotiate();
- document.getElementById('stop').style.display = 'inline-block';
-}
-
-function stop() {
- document.getElementById('stop').style.display = 'none';
-
- // close peer connection
- setTimeout(() => {
- pc.close();
- }, 500);
-}
\ No newline at end of file
diff --git a/teleop/webrtc/index.html b/teleop/webrtc/index.html
deleted file mode 100644
index 159ff99..0000000
--- a/teleop/webrtc/index.html
+++ /dev/null
@@ -1,43 +0,0 @@
-
-
-
-
-
- WebRTC webcam
-
-
-
-
-
-
- Use STUN server
-
-Start
-Stop
-
-
-
-
-
-
\ No newline at end of file
diff --git a/teleop/webrtc/orig_webcam_example.py b/teleop/webrtc/orig_webcam_example.py
deleted file mode 100644
index a486be1..0000000
--- a/teleop/webrtc/orig_webcam_example.py
+++ /dev/null
@@ -1,164 +0,0 @@
-import argparse
-import asyncio
-import json
-import logging
-import os
-import platform
-import ssl
-
-from aiohttp import web
-from aiortc import RTCPeerConnection, RTCSessionDescription
-from aiortc.contrib.media import MediaPlayer, MediaRelay
-from aiortc.rtcrtpsender import RTCRtpSender
-
-ROOT = os.path.dirname(__file__)
-
-
-relay = None
-webcam = None
-
-
-def create_local_tracks(play_from, decode):
- global relay, webcam
-
- if play_from:
- player = MediaPlayer(play_from, decode=decode)
- return player.audio, player.video
- else:
- options = {"framerate": "30", "video_size": "640x480"}
- if relay is None:
- if platform.system() == "Darwin":
- webcam = MediaPlayer(
- "default:none", format="avfoundation", options=options
- )
- elif platform.system() == "Windows":
- webcam = MediaPlayer(
- "video=Integrated Camera", format="dshow", options=options
- )
- else:
- webcam = MediaPlayer("/dev/video0", format="v4l2", options=options)
- relay = MediaRelay()
- return None, relay.subscribe(webcam.video)
-
-
-def force_codec(pc, sender, forced_codec):
- kind = forced_codec.split("/")[0]
- codecs = RTCRtpSender.getCapabilities(kind).codecs
- transceiver = next(t for t in pc.getTransceivers() if t.sender == sender)
- transceiver.setCodecPreferences(
- [codec for codec in codecs if codec.mimeType == forced_codec]
- )
-
-
-async def index(request):
- content = open(os.path.join(ROOT, "index.html"), "r").read()
- return web.Response(content_type="text/html", text=content)
-
-
-async def javascript(request):
- content = open(os.path.join(ROOT, "client.js"), "r").read()
- return web.Response(content_type="application/javascript", text=content)
-
-
-async def offer(request):
- params = await request.json()
- offer = RTCSessionDescription(sdp=params["sdp"], type=params["type"])
-
- pc = RTCPeerConnection()
- pcs.add(pc)
-
- @pc.on("connectionstatechange")
- async def on_connectionstatechange():
- print("Connection state is %s" % pc.connectionState)
- if pc.connectionState == "failed":
- await pc.close()
- pcs.discard(pc)
-
- # open media source
- audio, video = create_local_tracks(
- args.play_from, decode=not args.play_without_decoding
- )
-
- if audio:
- audio_sender = pc.addTrack(audio)
- if args.audio_codec:
- force_codec(pc, audio_sender, args.audio_codec)
- elif args.play_without_decoding:
- raise Exception("You must specify the audio codec using --audio-codec")
-
- if video:
- video_sender = pc.addTrack(video)
- if args.video_codec:
- force_codec(pc, video_sender, args.video_codec)
- elif args.play_without_decoding:
- raise Exception("You must specify the video codec using --video-codec")
-
- await pc.setRemoteDescription(offer)
-
- answer = await pc.createAnswer()
- await pc.setLocalDescription(answer)
-
- return web.Response(
- content_type="application/json",
- text=json.dumps(
- {"sdp": pc.localDescription.sdp, "type": pc.localDescription.type}
- ),
- )
-
-
-pcs = set()
-
-
-async def on_shutdown(app):
- # close peer connections
- coros = [pc.close() for pc in pcs]
- await asyncio.gather(*coros)
- pcs.clear()
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser(description="WebRTC webcam demo")
- parser.add_argument("--cert-file", help="SSL certificate file (for HTTPS)")
- parser.add_argument("--key-file", help="SSL key file (for HTTPS)")
- parser.add_argument("--play-from", help="Read the media from a file and sent it.")
- parser.add_argument(
- "--play-without-decoding",
- help=(
- "Read the media without decoding it (experimental). "
- "For now it only works with an MPEGTS container with only H.264 video."
- ),
- action="store_true",
- )
- parser.add_argument(
- "--host", default="0.0.0.0", help="Host for HTTP server (default: 0.0.0.0)"
- )
- parser.add_argument(
- "--port", type=int, default=8080, help="Port for HTTP server (default: 8080)"
- )
- parser.add_argument("--verbose", "-v", action="count")
- parser.add_argument(
- "--audio-codec", help="Force a specific audio codec (e.g. audio/opus)"
- )
- parser.add_argument(
- "--video-codec", help="Force a specific video codec (e.g. video/H264)"
- )
-
- args = parser.parse_args()
-
- if args.verbose:
- logging.basicConfig(level=logging.DEBUG)
- else:
- logging.basicConfig(level=logging.INFO)
-
- if args.cert_file:
- ssl_context = ssl.SSLContext()
- ssl_context.load_cert_chain(args.cert_file, args.key_file)
- else:
- ssl_context = None
-
- app = web.Application()
- app.on_shutdown.append(on_shutdown)
- app.router.add_get("/", index)
- app.router.add_get("/client.js", javascript)
- app.router.add_post("/offer", offer)
- web.run_app(app, host=args.host, port=args.port, ssl_context=ssl_context)
\ No newline at end of file
diff --git a/teleop/webrtc/webcam.py b/teleop/webrtc/webcam.py
deleted file mode 100644
index b95c0f6..0000000
--- a/teleop/webrtc/webcam.py
+++ /dev/null
@@ -1,206 +0,0 @@
-import argparse
-import asyncio
-import json
-import logging
-import os
-import ssl
-
-import cv2
-import numpy as np
-import time
-from pyzed import sl
-from aiortc import MediaStreamTrack
-import av
-
-from aiohttp import web
-from aiortc import RTCPeerConnection, RTCSessionDescription
-from aiortc.rtcrtpsender import RTCRtpSender
-
-ROOT = os.path.dirname(__file__)
-
-
-# relay = None
-# webcam = None
-
-left_mat = sl.Mat()
-right_mat = sl.Mat()
-
-class VideoTransformTrack(MediaStreamTrack):
- kind = "video"
-
- def __init__(self, camera):
- super().__init__()
- self.camera = camera
- self.runtime_parameters = sl.RuntimeParameters()
- self._direction = "sendonly"
- self.start_time = time.time()
- self.timescale = 1000 # Use a timescale of 1000 for milliseconds
- self.frame_index = 0
-
- async def recv(self):
- frame = await self.get_frame()
- if frame is not None:
- # Timestamp is calculated based on the frame index and the frame rate of the video
- timestamp = int((time.time() - self.start_time) * self.timescale)
- # Create an aiortc VideoFrame, setting timestamp and time_base accordingly
- video_frame = av.VideoFrame.from_ndarray(frame, format="bgr24")
- video_frame.pts = timestamp
- video_frame.time_base = self.timescale
- return video_frame
- else:
- return None
-
- async def get_frame(self):
- if self.camera.grab(self.runtime_parameters) == sl.ERROR_CODE.SUCCESS:
- self.camera.retrieve_image(left_mat, sl.VIEW.LEFT)
- self.camera.retrieve_image(right_mat, sl.VIEW.RIGHT)
- # Convert to BGR format as required by aiortc
- bgra = np.vstack((left_mat.numpy(), right_mat.numpy()))
- frame = cv2.cvtColor(bgra, cv2.COLOR_BGRA2BGR)
- return frame
- else:
- return None
-
-
-def create_local_tracks(play_from, decode):
- camera = sl.Camera()
- init_params = sl.InitParameters(camera_resolution=sl.RESOLUTION.HD720, camera_fps=30)
- if camera.open(init_params) == sl.ERROR_CODE.SUCCESS:
- print("ZED Camera successfully opened.")
- return None, VideoTransformTrack(camera) # Assuming you only want video track
- else:
- print("Failed to open ZED camera")
- return None, None
-
-
-def force_codec(pc, sender, forced_codec):
- kind = forced_codec.split("/")[0]
- codecs = RTCRtpSender.getCapabilities(kind).codecs
- transceiver = next(t for t in pc.getTransceivers() if t.sender == sender)
- transceiver.setCodecPreferences(
- [codec for codec in codecs if codec.mimeType == forced_codec]
- )
-
-
-async def index(request):
- content = open(os.path.join(ROOT, "index.html"), "r").read()
- return web.Response(content_type="text/html", text=content)
-
-
-async def javascript(request):
- content = open(os.path.join(ROOT, "client.js"), "r").read()
- return web.Response(content_type="application/javascript", text=content)
-
-
-async def offer(request):
- params = await request.json()
- offer = RTCSessionDescription(sdp=params["sdp"], type=params["type"])
-
- pc = RTCPeerConnection()
- pcs.add(pc)
-
- @pc.on('icecandidate')
- async def on_ice_candidate(event):
- if event.candidate:
- if event.candidate.type == 'host':
- # Handle or signal only the host candidate
- print(f"Host candidate: {event.candidate}")
- else:
- # Ignore non-host candidates
- pass
-
- @pc.on("connectionstatechange")
- async def on_connectionstatechange():
- print("Connection state is %s" % pc.connectionState)
- if pc.connectionState == "failed":
- await pc.close()
- pcs.discard(pc)
-
- # open media source
- audio, video = create_local_tracks(
- args.play_from, decode=not args.play_without_decoding
- )
-
- if audio:
- audio_sender = pc.addTrack(audio)
- if args.audio_codec:
- force_codec(pc, audio_sender, args.audio_codec)
- elif args.play_without_decoding:
- raise Exception("You must specify the audio codec using --audio-codec")
-
- if video:
- video_sender = pc.addTrack(video)
- if args.video_codec:
- force_codec(pc, video_sender, args.video_codec)
- elif args.play_without_decoding:
- raise Exception("You must specify the video codec using --video-codec")
-
- await pc.setRemoteDescription(offer)
-
- answer = await pc.createAnswer()
- await pc.setLocalDescription(answer)
-
- return web.Response(
- content_type="application/json",
- text=json.dumps(
- {"sdp": pc.localDescription.sdp, "type": pc.localDescription.type}
- ),
- )
-
-
-pcs = set()
-
-
-async def on_shutdown(app):
- # close peer connections
- coros = [pc.close() for pc in pcs]
- await asyncio.gather(*coros)
- pcs.clear()
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser(description="WebRTC webcam demo")
- parser.add_argument("--cert-file", help="SSL certificate file (for HTTPS)")
- parser.add_argument("--key-file", help="SSL key file (for HTTPS)")
- parser.add_argument("--play-from", help="Read the media from a file and sent it.")
- parser.add_argument(
- "--play-without-decoding",
- help=(
- "Read the media without decoding it (experimental). "
- "For now it only works with an MPEGTS container with only H.264 video."
- ),
- action="store_true",
- )
- parser.add_argument(
- "--host", default="0.0.0.0", help="Host for HTTP server (default: 0.0.0.0)"
- )
- parser.add_argument(
- "--port", type=int, default=8080, help="Port for HTTP server (default: 8080)"
- )
- parser.add_argument("--verbose", "-v", action="count")
- parser.add_argument(
- "--audio-codec", help="Force a specific audio codec (e.g. audio/opus)"
- )
- parser.add_argument(
- "--video-codec", help="Force a specific video codec (e.g. video/H264)"
- )
-
- args = parser.parse_args()
-
- if args.verbose:
- logging.basicConfig(level=logging.DEBUG)
- else:
- logging.basicConfig(level=logging.INFO)
-
- if args.cert_file:
- ssl_context = ssl.SSLContext()
- ssl_context.load_cert_chain(args.cert_file, args.key_file)
- else:
- ssl_context = None
-
- app = web.Application()
- app.on_shutdown.append(on_shutdown)
- app.router.add_get("/", index)
- app.router.add_get("/client.js", javascript)
- app.router.add_post("/offer", offer)
- web.run_app(app, host=args.host, port=args.port, ssl_context=ssl_context)
\ No newline at end of file
diff --git a/teleop/webrtc/webcam_server.py b/teleop/webrtc/webcam_server.py
deleted file mode 100644
index 8b5c49c..0000000
--- a/teleop/webrtc/webcam_server.py
+++ /dev/null
@@ -1,206 +0,0 @@
-import asyncio
-import json
-import logging
-import os
-import platform
-import ssl
-
-import aiohttp_cors
-from aiohttp import web
-from aiortc import RTCPeerConnection, RTCSessionDescription
-from aiortc.contrib.media import MediaPlayer, MediaRelay
-from aiortc.rtcrtpsender import RTCRtpSender
-from multiprocessing import Process, Array, Value, shared_memory
-
-ROOT = os.path.dirname(__file__)
-
-relay = None
-webcam = None
-
-
-from aiortc import MediaStreamTrack
-from av import VideoFrame
-import numpy as np
-import time
-
-class ZedVideoTrack(MediaStreamTrack):
-
- kind = "video"
-
- def __init__(self, img_shape, shm_name, fps):
- super().__init__() # Initialize base class
- self.img_shape = (2*img_shape[0], img_shape[1], 3)
- self.img_height, self.img_width = img_shape[:2]
- existing_shm = shared_memory.SharedMemory(name=shm_name)
- self.img_array = np.ndarray((self.img_shape[0], self.img_shape[1], 3), dtype=np.uint8, buffer=existing_shm.buf)
-
- self.frame_interval = 1 / fps
- self._last_frame_time = time.time()
-
- async def recv(self):
- """
- This method is called when a new frame is needed.
- """
- now = time.time()
- wait_time = self._last_frame_time + self.frame_interval - now
- if wait_time > 0:
- await asyncio.sleep(wait_time)
- self._last_frame_time = time.time()
-
- frame = self.img_array # Assuming this is an async function to fetch a frame
- av_frame = VideoFrame.from_ndarray(frame, format='bgr24') # Convert numpy array to AVFrame
- av_frame.pts = None
- av_frame.time_base = None
- return av_frame
-
-def create_local_tracks(play_from, decode):
- global relay, webcam
-
- if play_from:
- player = MediaPlayer(play_from, decode=decode)
- return player.audio, player.video
- else:
- options = {"framerate": "30", "video_size": "640x480"}
- if relay is None:
- if platform.system() == "Darwin":
- webcam = MediaPlayer(
- "default:none", format="avfoundation", options=options
- )
- elif platform.system() == "Windows":
- webcam = MediaPlayer(
- "video=Integrated Camera", format="dshow", options=options
- )
- else:
- webcam = MediaPlayer("/dev/video0", format=None, options=options)
- relay = MediaRelay()
- return None, relay.subscribe(webcam.video)
-
-
-def force_codec(pc, sender, forced_codec):
- kind = forced_codec.split("/")[0]
- codecs = RTCRtpSender.getCapabilities(kind).codecs
- transceiver = next(t for t in pc.getTransceivers() if t.sender == sender)
- transceiver.setCodecPreferences(
- [codec for codec in codecs if codec.mimeType == forced_codec]
- )
-
-
-async def index(request):
- content = open(os.path.join(ROOT, "index.html"), "r").read()
- return web.Response(content_type="text/html", text=content)
-
-
-async def javascript(request):
- content = open(os.path.join(ROOT, "client.js"), "r").read()
- return web.Response(content_type="application/javascript", text=content)
-
-
-async def offer(request):
- params = await request.json()
- offer = RTCSessionDescription(sdp=params["sdp"], type=params["type"])
-
- pc = RTCPeerConnection()
- pcs.add(pc)
-
- @pc.on("connectionstatechange")
- async def on_connectionstatechange():
- print("Connection state is %s" % pc.connectionState)
- if pc.connectionState == "failed":
- await pc.close()
- pcs.discard(pc)
-
- # open media source
- audio, video = create_local_tracks(
- Args.play_from, decode=not Args.play_without_decoding
- )
-
- if audio:
- audio_sender = pc.addTrack(audio)
- if Args.audio_codec:
- force_codec(pc, audio_sender, Args.audio_codec)
- elif Args.play_without_decoding:
- raise Exception("You must specify the audio codec using --audio-codec")
-
- if video:
- video_sender = pc.addTrack(video)
- if Args.video_codec:
- force_codec(pc, video_sender, Args.video_codec)
- elif Args.play_without_decoding:
- raise Exception("You must specify the video codec using --video-codec")
-
- await pc.setRemoteDescription(offer)
-
- answer = await pc.createAnswer()
- await pc.setLocalDescription(answer)
-
- return web.Response(
- content_type="application/json",
- text=json.dumps(
- {"sdp": pc.localDescription.sdp, "type": pc.localDescription.type}
- ),
- )
-
-
-pcs = set()
-
-
-async def on_shutdown(app):
- # close peer connections
- coros = [pc.close() for pc in pcs]
- await asyncio.gather(*coros)
- pcs.clear()
-
-
-from params_proto import ParamsProto, Proto, Flag
-
-
-class Args(ParamsProto):
- description = "WebRTC webcam demo"
- cert_file = Proto(help="SSL certificate file (for HTTPS)")
- key_file = Proto(help="SSL key file (for HTTPS)")
-
- host = Proto(default="0.0.0.0", help="Host for HTTP server (default: 0.0.0.0)")
- port = Proto(default=8080, dtype=int, help="Port for HTTP server (default: 8080)")
-
- play_from = Proto(help="Read the media from a file and send it.")
- play_without_decoding = Flag(
- "Read the media without decoding it (experimental). "
- "For now it only works with an MPEGTS container with only H.264 video."
- )
-
- audio_codec = Proto(help="Force a specific audio codec (e.g. audio/opus)")
- video_codec = Proto(help="Force a specific video codec (e.g. video/H264)")
-
- verbose = Flag()
-
-
-if __name__ == '__main__':
-
- if Args.verbose:
- logging.basicConfig(level=logging.DEBUG)
- else:
- logging.basicConfig(level=logging.INFO)
-
- if Args.cert_file:
- print("Using SSL certificate file: %s" % Args.cert_file)
- ssl_context = ssl.SSLContext()
- ssl_context.load_cert_chain(Args.cert_file, Args.key_file)
- else:
- ssl_context = None
-
- app = web.Application()
- cors = aiohttp_cors.setup(app, defaults={
- "*": aiohttp_cors.ResourceOptions(
- allow_credentials=True,
- expose_headers="*",
- allow_headers="*",
- allow_methods="*",
- )
- })
-
- app.on_shutdown.append(on_shutdown)
- cors.add(app.router.add_get("/", index))
- cors.add(app.router.add_get("/client.js", javascript))
- cors.add(app.router.add_post("/offer", offer))
-
- web.run_app(app, host=Args.host, port=Args.port, ssl_context=ssl_context)
\ No newline at end of file
diff --git a/teleop/webrtc/zed_server.py b/teleop/webrtc/zed_server.py
deleted file mode 100644
index b036168..0000000
--- a/teleop/webrtc/zed_server.py
+++ /dev/null
@@ -1,195 +0,0 @@
-import asyncio
-import json
-import logging
-import os
-import platform
-import ssl
-
-import aiohttp_cors
-from aiohttp import web
-from aiortc import RTCPeerConnection, RTCSessionDescription
-from aiortc.contrib.media import MediaPlayer, MediaRelay
-from aiortc.rtcrtpsender import RTCRtpSender
-from multiprocessing import Process, Array, Value, shared_memory
-
-ROOT = os.path.dirname(__file__)
-
-relay = None
-webcam = None
-
-
-from aiortc import MediaStreamTrack
-from av import VideoFrame
-import numpy as np
-import time
-
-class ZedVideoTrack(MediaStreamTrack):
- kind = "video"
- def __init__(self, queue, toggle_streaming, fps):
- super().__init__() # Initialize base class
- # self.img_shape = (2*img_shape[0], img_shape[1], 3)
- # self.img_height, self.img_width = img_shape[:2]
- # self.shm_name = shm_name
- # existing_shm = shared_memory.SharedMemory(name=shm_name)
- # self.img_array = np.ndarray((self.img_shape[0], self.img_shape[1], 3), dtype=np.uint8, buffer=existing_shm.buf)
- self.img_queue = queue
- self.toggle_streaming = toggle_streaming
- self.streaming_started = False
- self.timescale = 1000 # Use a timescale of 1000 for milliseconds
- # self.frame_interval = 1 / fps
- self._last_frame_time = time.time()
- self.start_time = time.time()
-
- async def recv(self):
- """
- This method is called when a new frame is needed.
- """
- # now = time.time()
- # wait_time = self._last_frame_time + self.frame_interval - now
- # if wait_time > 0:
- # await asyncio.sleep(wait_time)
- # self._last_frame_time = time.time()
- # start = time.time()
- if not self.streaming_started:
- self.toggle_streaming.set()
- self.streaming_started = True
- frame = self.img_queue.get()
- # self.sem.release()
- # print("Time to get frame: ", time.time() - start, self.img_queue.qsize())
- # frame = self.img_array.copy() # Assuming this is an async function to fetch a frame
- # frame = np.random.randint(0, 256, size=(480, 640, 3), dtype=np.uint8)
- # print("recv")
- # start = time.time()
- av_frame = VideoFrame.from_ndarray(frame, format='rgb24') # Convert numpy array to AVFrame
- timestamp = int((time.time() - self.start_time) * self.timescale)
- av_frame.pts = timestamp
- av_frame.time_base = self.timescale
- # print("Time to process frame: ", time.time() - start)
- return av_frame
-
-
-def force_codec(pc, sender, forced_codec):
- kind = forced_codec.split("/")[0]
- codecs = RTCRtpSender.getCapabilities(kind).codecs
- transceiver = next(t for t in pc.getTransceivers() if t.sender == sender)
- transceiver.setCodecPreferences(
- [codec for codec in codecs if codec.mimeType == forced_codec]
- )
-
-
-async def index(request):
- content = open(os.path.join(ROOT, "index.html"), "r").read()
- return web.Response(content_type="text/html", text=content)
-
-
-async def javascript(request):
- content = open(os.path.join(ROOT, "client.js"), "r").read()
- return web.Response(content_type="application/javascript", text=content)
-
-class RTC():
- def __init__(self, img_shape, img_queue, toggle_streaming, fps) -> None:
- self.img_shape = img_shape
- self.img_queue = img_queue
- self.fps = fps
- self.toggle_streaming = toggle_streaming
-
- async def offer(self, request):
- params = await request.json()
- offer = RTCSessionDescription(sdp=params["sdp"], type=params["type"])
-
- pc = RTCPeerConnection()
- pcs.add(pc)
-
- @pc.on("connectionstatechange")
- async def on_connectionstatechange():
- print("Connection state is %s" % pc.connectionState)
- if pc.connectionState == "failed":
- await pc.close()
- pcs.discard(pc)
-
- # open media source
- zed_track = ZedVideoTrack(self.img_queue, self.toggle_streaming, self.fps)
- video_sender = pc.addTrack(zed_track)
- # if Args.video_codec:
- force_codec(pc, video_sender, "video/H264")
- # elif Args.play_without_decoding:
- # raise Exception("You must specify the video codec using --video-codec")
-
- await pc.setRemoteDescription(offer)
-
- answer = await pc.createAnswer()
- await pc.setLocalDescription(answer)
-
- return web.Response(
- content_type="application/json",
- text=json.dumps(
- {"sdp": pc.localDescription.sdp, "type": pc.localDescription.type}
- ),
- )
-
-
-pcs = set()
-
-async def on_shutdown(app):
- # close peer connections
- coros = [pc.close() for pc in pcs]
- await asyncio.gather(*coros)
- pcs.clear()
-
-
-from params_proto import ParamsProto, Proto, Flag
-
-
-class Args(ParamsProto):
- description = "WebRTC webcam demo"
- cert_file = Proto(help="SSL certificate file (for HTTPS)")
- key_file = Proto(help="SSL key file (for HTTPS)")
-
- host = Proto(default="0.0.0.0", help="Host for HTTP server (default: 0.0.0.0)")
- port = Proto(default=8080, dtype=int, help="Port for HTTP server (default: 8080)")
-
- play_from = Proto(help="Read the media from a file and send it.")
- play_without_decoding = Flag(
- "Read the media without decoding it (experimental). "
- "For now it only works with an MPEGTS container with only H.264 video."
- )
-
- audio_codec = Proto(help="Force a specific audio codec (e.g. audio/opus)")
- video_codec = Proto(help="Force a specific video codec (e.g. video/H264)")
- img_shape = Proto(help="")
- shm_name = Proto(help="")
- fps = Proto(help="")
-
- verbose = Flag()
-
-
-if __name__ == '__main__':
-
- if Args.verbose:
- logging.basicConfig(level=logging.DEBUG)
- else:
- logging.basicConfig(level=logging.INFO)
-
- if Args.cert_file:
- print("Using SSL certificate file: %s" % Args.cert_file)
- ssl_context = ssl.SSLContext()
- ssl_context.load_cert_chain(Args.cert_file, Args.key_file)
- else:
- ssl_context = None
-
- app = web.Application()
- cors = aiohttp_cors.setup(app, defaults={
- "*": aiohttp_cors.ResourceOptions(
- allow_credentials=True,
- expose_headers="*",
- allow_headers="*",
- allow_methods="*",
- )
- })
- rtc = RTC((960, 640), queue)
- app.on_shutdown.append(on_shutdown)
- cors.add(app.router.add_get("/", index))
- cors.add(app.router.add_get("/client.js", javascript))
- cors.add(app.router.add_post("/offer", rtc.offer))
-
- web.run_app(app, host=Args.host, port=Args.port, ssl_context=ssl_context)
\ No newline at end of file