Spaces:
Running
on
CPU Upgrade
Running
on
CPU Upgrade
Commit
·
3f7d1b3
0
Parent(s):
Initial commit
Browse files- .dockerignore +1 -0
- .gitattributes +35 -0
- .idea/.gitignore +8 -0
- .idea/JAX-IK.iml +8 -0
- .idea/inspectionProfiles/profiles_settings.xml +6 -0
- .idea/misc.xml +7 -0
- .idea/modules.xml +8 -0
- .idea/ruff.xml +13 -0
- .idea/vcs.xml +7 -0
- Dockerfile +29 -0
- Makefile +9 -0
- README.md +16 -0
- app.py +749 -0
- collision_objectives.py +83 -0
- packages.txt +2 -0
- requirements.txt +8 -0
- static/index.html +473 -0
.dockerignore
ADDED
|
@@ -0,0 +1 @@
|
|
|
|
|
|
|
| 1 |
+
files
|
.gitattributes
ADDED
|
@@ -0,0 +1,35 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
*.7z filter=lfs diff=lfs merge=lfs -text
|
| 2 |
+
*.arrow filter=lfs diff=lfs merge=lfs -text
|
| 3 |
+
*.bin filter=lfs diff=lfs merge=lfs -text
|
| 4 |
+
*.bz2 filter=lfs diff=lfs merge=lfs -text
|
| 5 |
+
*.ckpt filter=lfs diff=lfs merge=lfs -text
|
| 6 |
+
*.ftz filter=lfs diff=lfs merge=lfs -text
|
| 7 |
+
*.gz filter=lfs diff=lfs merge=lfs -text
|
| 8 |
+
*.h5 filter=lfs diff=lfs merge=lfs -text
|
| 9 |
+
*.joblib filter=lfs diff=lfs merge=lfs -text
|
| 10 |
+
*.lfs.* filter=lfs diff=lfs merge=lfs -text
|
| 11 |
+
*.mlmodel filter=lfs diff=lfs merge=lfs -text
|
| 12 |
+
*.model filter=lfs diff=lfs merge=lfs -text
|
| 13 |
+
*.msgpack filter=lfs diff=lfs merge=lfs -text
|
| 14 |
+
*.npy filter=lfs diff=lfs merge=lfs -text
|
| 15 |
+
*.npz filter=lfs diff=lfs merge=lfs -text
|
| 16 |
+
*.onnx filter=lfs diff=lfs merge=lfs -text
|
| 17 |
+
*.ot filter=lfs diff=lfs merge=lfs -text
|
| 18 |
+
*.parquet filter=lfs diff=lfs merge=lfs -text
|
| 19 |
+
*.pb filter=lfs diff=lfs merge=lfs -text
|
| 20 |
+
*.pickle filter=lfs diff=lfs merge=lfs -text
|
| 21 |
+
*.pkl filter=lfs diff=lfs merge=lfs -text
|
| 22 |
+
*.pt filter=lfs diff=lfs merge=lfs -text
|
| 23 |
+
*.pth filter=lfs diff=lfs merge=lfs -text
|
| 24 |
+
*.rar filter=lfs diff=lfs merge=lfs -text
|
| 25 |
+
*.safetensors filter=lfs diff=lfs merge=lfs -text
|
| 26 |
+
saved_model/**/* filter=lfs diff=lfs merge=lfs -text
|
| 27 |
+
*.tar.* filter=lfs diff=lfs merge=lfs -text
|
| 28 |
+
*.tar filter=lfs diff=lfs merge=lfs -text
|
| 29 |
+
*.tflite filter=lfs diff=lfs merge=lfs -text
|
| 30 |
+
*.tgz filter=lfs diff=lfs merge=lfs -text
|
| 31 |
+
*.wasm filter=lfs diff=lfs merge=lfs -text
|
| 32 |
+
*.xz filter=lfs diff=lfs merge=lfs -text
|
| 33 |
+
*.zip filter=lfs diff=lfs merge=lfs -text
|
| 34 |
+
*.zst filter=lfs diff=lfs merge=lfs -text
|
| 35 |
+
*tfevents* filter=lfs diff=lfs merge=lfs -text
|
.idea/.gitignore
ADDED
|
@@ -0,0 +1,8 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
# Default ignored files
|
| 2 |
+
/shelf/
|
| 3 |
+
/workspace.xml
|
| 4 |
+
# Editor-based HTTP Client requests
|
| 5 |
+
/httpRequests/
|
| 6 |
+
# Datasource local storage ignored files
|
| 7 |
+
/dataSources/
|
| 8 |
+
/dataSources.local.xml
|
.idea/JAX-IK.iml
ADDED
|
@@ -0,0 +1,8 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<?xml version="1.0" encoding="UTF-8"?>
|
| 2 |
+
<module type="PYTHON_MODULE" version="4">
|
| 3 |
+
<component name="NewModuleRootManager">
|
| 4 |
+
<content url="file://$MODULE_DIR$" />
|
| 5 |
+
<orderEntry type="jdk" jdkName="main" jdkType="Python SDK" />
|
| 6 |
+
<orderEntry type="sourceFolder" forTests="false" />
|
| 7 |
+
</component>
|
| 8 |
+
</module>
|
.idea/inspectionProfiles/profiles_settings.xml
ADDED
|
@@ -0,0 +1,6 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<component name="InspectionProjectProfileManager">
|
| 2 |
+
<settings>
|
| 3 |
+
<option name="USE_PROJECT_PROFILE" value="false" />
|
| 4 |
+
<version value="1.0" />
|
| 5 |
+
</settings>
|
| 6 |
+
</component>
|
.idea/misc.xml
ADDED
|
@@ -0,0 +1,7 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<?xml version="1.0" encoding="UTF-8"?>
|
| 2 |
+
<project version="4">
|
| 3 |
+
<component name="Black">
|
| 4 |
+
<option name="sdkName" value="Python 3.12" />
|
| 5 |
+
</component>
|
| 6 |
+
<component name="ProjectRootManager" version="2" project-jdk-name="main" project-jdk-type="Python SDK" />
|
| 7 |
+
</project>
|
.idea/modules.xml
ADDED
|
@@ -0,0 +1,8 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<?xml version="1.0" encoding="UTF-8"?>
|
| 2 |
+
<project version="4">
|
| 3 |
+
<component name="ProjectModuleManager">
|
| 4 |
+
<modules>
|
| 5 |
+
<module fileurl="file://$PROJECT_DIR$/.idea/JAX-IK.iml" filepath="$PROJECT_DIR$/.idea/JAX-IK.iml" />
|
| 6 |
+
</modules>
|
| 7 |
+
</component>
|
| 8 |
+
</project>
|
.idea/ruff.xml
ADDED
|
@@ -0,0 +1,13 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<?xml version="1.0" encoding="UTF-8"?>
|
| 2 |
+
<project version="4">
|
| 3 |
+
<component name="RuffConfigService">
|
| 4 |
+
<option name="alwaysUseGlobalRuff" value="true" />
|
| 5 |
+
<option name="enableRuffLogging" value="true" />
|
| 6 |
+
<option name="runRuffOnSave" value="true" />
|
| 7 |
+
<option name="useIntellijLspClient" value="false" />
|
| 8 |
+
<option name="useLsp4ij" value="true" />
|
| 9 |
+
<option name="useRuffFormat" value="true" />
|
| 10 |
+
<option name="useRuffImportOptimizer" value="true" />
|
| 11 |
+
<option name="useRuffServer" value="true" />
|
| 12 |
+
</component>
|
| 13 |
+
</project>
|
.idea/vcs.xml
ADDED
|
@@ -0,0 +1,7 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<?xml version="1.0" encoding="UTF-8"?>
|
| 2 |
+
<project version="4">
|
| 3 |
+
<component name="VcsDirectoryMappings">
|
| 4 |
+
<mapping directory="" vcs="Git" />
|
| 5 |
+
<mapping directory="$PROJECT_DIR$" vcs="Git" />
|
| 6 |
+
</component>
|
| 7 |
+
</project>
|
Dockerfile
ADDED
|
@@ -0,0 +1,29 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
FROM python:3.11
|
| 2 |
+
|
| 3 |
+
WORKDIR /code
|
| 4 |
+
|
| 5 |
+
COPY ./requirements.txt /code/requirements.txt
|
| 6 |
+
|
| 7 |
+
RUN pip install --no-cache-dir --upgrade -r /code/requirements.txt
|
| 8 |
+
|
| 9 |
+
RUN pip install psutil
|
| 10 |
+
|
| 11 |
+
RUN yes | pip uninstall jax-cuda12-plugin jax-cuda12-pjrt
|
| 12 |
+
|
| 13 |
+
# Set up a new user named "user" with user ID 1000
|
| 14 |
+
RUN useradd -m -u 1000 user
|
| 15 |
+
|
| 16 |
+
# Switch to the "user" user
|
| 17 |
+
USER user
|
| 18 |
+
|
| 19 |
+
# Set home to the user's home directory
|
| 20 |
+
ENV HOME=/home/user \
|
| 21 |
+
PATH=/home/user/.local/bin:$PATH
|
| 22 |
+
|
| 23 |
+
# Set the working directory to the user's home directory
|
| 24 |
+
WORKDIR $HOME/app
|
| 25 |
+
|
| 26 |
+
# Copy the current directory contents into the container at $HOME/app setting the owner to the user
|
| 27 |
+
COPY --chown=user . $HOME/app
|
| 28 |
+
|
| 29 |
+
CMD ["python", "app.py"]
|
Makefile
ADDED
|
@@ -0,0 +1,9 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
image_name := hvosstechfak/jaxik_demo
|
| 2 |
+
|
| 3 |
+
build:
|
| 4 |
+
docker build . -t ${image_name}
|
| 5 |
+
|
| 6 |
+
run:
|
| 7 |
+
-docker stop jaxik;
|
| 8 |
+
-docker rm jaxik;
|
| 9 |
+
docker run --ipc=host --name jaxik --network=host ${image_name}
|
README.md
ADDED
|
@@ -0,0 +1,16 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
---
|
| 2 |
+
title: JAX IK
|
| 3 |
+
emoji: ⚡
|
| 4 |
+
colorFrom: gray
|
| 5 |
+
colorTo: yellow
|
| 6 |
+
sdk: docker
|
| 7 |
+
sdk_version: 5.35.0
|
| 8 |
+
app_file: app.py
|
| 9 |
+
pinned: false
|
| 10 |
+
license: cc-by-nc-sa-4.0
|
| 11 |
+
short_description: https://github.com/hvoss-techfak/TF-JAX-IK
|
| 12 |
+
app_port: 17861
|
| 13 |
+
---
|
| 14 |
+
|
| 15 |
+
Please see the code here:
|
| 16 |
+
https://github.com/hvoss-techfak/TF-JAX-IK
|
app.py
ADDED
|
@@ -0,0 +1,749 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import logging, faulthandler, sys, time, os, requests, zipfile, io, gc, threading, psutil, json, configargparse
|
| 2 |
+
faulthandler.enable()
|
| 3 |
+
logging.basicConfig(level=logging.INFO, format='%(asctime)s - %(levelname)s - %(message)s')
|
| 4 |
+
logger = logging.getLogger("jax_ik_server")
|
| 5 |
+
|
| 6 |
+
def _excepthook(t, v, tb):
|
| 7 |
+
logger.exception("Uncaught exception", exc_info=(t, v, tb))
|
| 8 |
+
sys.excepthook = _excepthook
|
| 9 |
+
|
| 10 |
+
# Environment (CPU only)
|
| 11 |
+
os.environ['JAX_PLATFORMS'] = 'cpu'
|
| 12 |
+
os.environ['CUDA_VISIBLE_DEVICES'] = ''
|
| 13 |
+
|
| 14 |
+
import jax
|
| 15 |
+
jax.config.update("jax_default_device", "cpu")
|
| 16 |
+
import numpy as np
|
| 17 |
+
|
| 18 |
+
from fastapi import FastAPI, Request, Response
|
| 19 |
+
from fastapi.staticfiles import StaticFiles
|
| 20 |
+
from fastapi.middleware.cors import CORSMiddleware
|
| 21 |
+
from starlette.responses import FileResponse, JSONResponse
|
| 22 |
+
|
| 23 |
+
from jax_ik.helper import deform_mesh, load_mesh_data_from_gltf, load_mesh_data_from_urdf
|
| 24 |
+
from jax_ik.hand_specification import HandSpecification
|
| 25 |
+
from jax_ik.smplx_statics import left_arm_bounds_dict, right_arm_bounds_dict, complete_full_body_bounds_dict
|
| 26 |
+
from jax_ik.ik import InverseKinematicsSolver
|
| 27 |
+
from jax_ik.objectives import (
|
| 28 |
+
BoneZeroRotationObj,
|
| 29 |
+
CombinedDerivativeObj,
|
| 30 |
+
DistanceObjTraj,
|
| 31 |
+
SphereCollisionPenaltyObjTraj,
|
| 32 |
+
)
|
| 33 |
+
try:
|
| 34 |
+
from collision_objectives import FastSphereCollisionPenaltyObjTraj as _FastColl
|
| 35 |
+
except Exception: # fallback if file missing
|
| 36 |
+
_FastColl = SphereCollisionPenaltyObjTraj
|
| 37 |
+
|
| 38 |
+
def download_and_setup_files():
|
| 39 |
+
os.makedirs("files", exist_ok=True)
|
| 40 |
+
# Pepper
|
| 41 |
+
pepper_dir = "files/pepper_description-master"
|
| 42 |
+
if not os.path.isdir(pepper_dir):
|
| 43 |
+
logger.info("Downloading Pepper model...")
|
| 44 |
+
try:
|
| 45 |
+
r = requests.get(os.environ.get("PEPPER_DOWNLOAD"), stream=True)
|
| 46 |
+
r.raise_for_status()
|
| 47 |
+
with zipfile.ZipFile(io.BytesIO(r.content)) as z:
|
| 48 |
+
z.extractall("files/")
|
| 49 |
+
except Exception as e:
|
| 50 |
+
logger.warning(f"Pepper download failed: {e}")
|
| 51 |
+
# SMPLX
|
| 52 |
+
smplx_file = "files/smplx.glb"
|
| 53 |
+
if not os.path.isfile(smplx_file):
|
| 54 |
+
logger.info("Downloading SMPLX model...")
|
| 55 |
+
try:
|
| 56 |
+
r = requests.get(os.environ.get("SMPLX_DOWNLOAD"))
|
| 57 |
+
r.raise_for_status()
|
| 58 |
+
open(smplx_file, "wb").write(r.content)
|
| 59 |
+
except Exception as e:
|
| 60 |
+
logger.warning(f"SMPLX download failed: {e}")
|
| 61 |
+
|
| 62 |
+
class IKServer:
|
| 63 |
+
def __init__(self, args):
|
| 64 |
+
self.args = args
|
| 65 |
+
self.solve_lock = threading.Lock()
|
| 66 |
+
self.config_lock = threading.Lock()
|
| 67 |
+
self.process = psutil.Process(os.getpid())
|
| 68 |
+
|
| 69 |
+
# Failure / resilience counters
|
| 70 |
+
self.agent_fail_count = 0
|
| 71 |
+
self.urdf_fail_count = 0
|
| 72 |
+
self.last_agent_error = None
|
| 73 |
+
self.last_urdf_error = None
|
| 74 |
+
self.agent_solve_counter = 0
|
| 75 |
+
self.urdf_solve_counter = 0
|
| 76 |
+
self.max_fail_retries = 2 # total attempts (initial + retries)
|
| 77 |
+
self.circuit_breaker_threshold = 5 # open after N consecutive failures
|
| 78 |
+
self.circuit_open_until = 0 # epoch time until which solves short-circuit
|
| 79 |
+
self.circuit_backoff_seconds = 5
|
| 80 |
+
|
| 81 |
+
# Numeric safety
|
| 82 |
+
self.max_num_steps_global = 20000
|
| 83 |
+
self.max_learning_rate = 5.0
|
| 84 |
+
|
| 85 |
+
# Animation buffers
|
| 86 |
+
self.animation_frames_agent = []
|
| 87 |
+
self.animation_frames_urdf = []
|
| 88 |
+
|
| 89 |
+
# FastAPI app
|
| 90 |
+
self.app = FastAPI()
|
| 91 |
+
self.app.add_middleware(
|
| 92 |
+
CORSMiddleware,
|
| 93 |
+
allow_origins=["*"], allow_credentials=True,
|
| 94 |
+
allow_methods=["*"], allow_headers=["*"],
|
| 95 |
+
)
|
| 96 |
+
os.makedirs("static", exist_ok=True)
|
| 97 |
+
os.makedirs("files", exist_ok=True)
|
| 98 |
+
self.app.mount("/static", StaticFiles(directory="static"), name="static")
|
| 99 |
+
self.app.mount("/files", StaticFiles(directory="files"), name="files")
|
| 100 |
+
|
| 101 |
+
# Initialize models
|
| 102 |
+
self._init_agent()
|
| 103 |
+
self._setup_agent_objectives()
|
| 104 |
+
self._init_urdf()
|
| 105 |
+
self._setup_urdf_objectives()
|
| 106 |
+
|
| 107 |
+
# Cleanup timing
|
| 108 |
+
self.last_cleanup_time = time.time()
|
| 109 |
+
self.cleanup_interval = 30
|
| 110 |
+
|
| 111 |
+
self._register_routes()
|
| 112 |
+
logger.info("Server ready.")
|
| 113 |
+
if getattr(self.args, 'warmup', True):
|
| 114 |
+
threading.Thread(target=self._warmup_all, daemon=True).start()
|
| 115 |
+
|
| 116 |
+
# ---------- Utility / Safety ----------
|
| 117 |
+
def _safe_int(self, v, default, lo=None, hi=None):
|
| 118 |
+
try:
|
| 119 |
+
v = int(v)
|
| 120 |
+
except Exception:
|
| 121 |
+
v = default
|
| 122 |
+
if lo is not None and v < lo: v = lo
|
| 123 |
+
if hi is not None and v > hi: v = hi
|
| 124 |
+
return v
|
| 125 |
+
|
| 126 |
+
def _safe_float(self, v, default, lo=None, hi=None):
|
| 127 |
+
try:
|
| 128 |
+
v = float(v)
|
| 129 |
+
if np.isnan(v) or np.isinf(v): raise ValueError
|
| 130 |
+
except Exception:
|
| 131 |
+
v = default
|
| 132 |
+
if lo is not None and v < lo: v = lo
|
| 133 |
+
if hi is not None and v > hi: v = hi
|
| 134 |
+
return v
|
| 135 |
+
|
| 136 |
+
def _sanitize_num_steps(self, steps):
|
| 137 |
+
return self._safe_int(steps, self.args.num_steps, 1, self.max_num_steps_global)
|
| 138 |
+
|
| 139 |
+
def _sanitize_bones(self, bones, is_urdf=False):
|
| 140 |
+
if not isinstance(bones, (list, tuple)):
|
| 141 |
+
return []
|
| 142 |
+
allowed = self.urdf_available_bones if is_urdf else self.available_bones
|
| 143 |
+
return [b for b in bones if b in allowed]
|
| 144 |
+
|
| 145 |
+
def _create_solver(self, bones, is_urdf, num_steps):
|
| 146 |
+
if is_urdf:
|
| 147 |
+
return InverseKinematicsSolver(
|
| 148 |
+
model_file=self.urdf_file,
|
| 149 |
+
controlled_bones=bones,
|
| 150 |
+
bounds=None,
|
| 151 |
+
threshold=self.args.threshold,
|
| 152 |
+
num_steps=int(num_steps),
|
| 153 |
+
compute_sdf=False,
|
| 154 |
+
)
|
| 155 |
+
bounds = []
|
| 156 |
+
for b in bones:
|
| 157 |
+
if b in self.bounds_dict:
|
| 158 |
+
lower, upper = self.bounds_dict[b]
|
| 159 |
+
bounds.extend(list(zip(lower, upper)))
|
| 160 |
+
else:
|
| 161 |
+
bounds.extend([(-90, 90)] * 3)
|
| 162 |
+
return InverseKinematicsSolver(
|
| 163 |
+
model_file=self.args.gltf_file,
|
| 164 |
+
controlled_bones=bones,
|
| 165 |
+
bounds=bounds,
|
| 166 |
+
threshold=self.args.threshold,
|
| 167 |
+
num_steps=int(num_steps),
|
| 168 |
+
compute_sdf=False,
|
| 169 |
+
)
|
| 170 |
+
|
| 171 |
+
def _rebuild_solver_safe(self, is_urdf=False, force_defaults=False):
|
| 172 |
+
try:
|
| 173 |
+
if is_urdf:
|
| 174 |
+
bones = self.urdf_default_controlled_bones if force_defaults else self.urdf_current_controlled_bones
|
| 175 |
+
bones = self._sanitize_bones(bones, True) or self.urdf_default_controlled_bones
|
| 176 |
+
self.urdf_solver = self._create_solver(bones, True, self.urdf_current_num_steps)
|
| 177 |
+
self.urdf_initial_rotations = np.zeros(len(self.urdf_solver.controlled_bones)*3, dtype=np.float32)
|
| 178 |
+
self.urdf_best_angles = self.urdf_initial_rotations.copy()
|
| 179 |
+
else:
|
| 180 |
+
bones = self.default_controlled_bones if force_defaults else self.current_controlled_bones
|
| 181 |
+
bones = self._sanitize_bones(bones, False) or self.default_controlled_bones
|
| 182 |
+
self.solver = self._create_solver(bones, False, self.current_num_steps)
|
| 183 |
+
self.initial_rotations = np.zeros(len(self.solver.controlled_bones)*3, dtype=np.float32)
|
| 184 |
+
self.best_angles = self.initial_rotations.copy()
|
| 185 |
+
return True
|
| 186 |
+
except Exception as e:
|
| 187 |
+
(self.last_urdf_error if is_urdf else setattr(self, 'last_agent_error', str(e)))
|
| 188 |
+
logger.exception("Solver rebuild failed")
|
| 189 |
+
return False
|
| 190 |
+
|
| 191 |
+
def _attempt_solver_recovery(self, is_urdf=False):
|
| 192 |
+
logger.warning("Attempting full solver recovery (reset to defaults)")
|
| 193 |
+
if is_urdf:
|
| 194 |
+
self.urdf_current_controlled_bones = self.urdf_default_controlled_bones.copy()
|
| 195 |
+
return self._rebuild_solver_safe(True, force_defaults=True)
|
| 196 |
+
else:
|
| 197 |
+
self.current_controlled_bones = self.default_controlled_bones.copy()
|
| 198 |
+
return self._rebuild_solver_safe(False, force_defaults=True)
|
| 199 |
+
|
| 200 |
+
# ---------- Warmup ----------
|
| 201 |
+
def _warmup_agent(self):
|
| 202 |
+
try:
|
| 203 |
+
mand = [DistanceObjTraj(target_points=np.array([0.0,0.2,0.35]), bone_name=self.current_end_effector, use_head=True, weight=1.0)]
|
| 204 |
+
opt = [BoneZeroRotationObj(weight=0.01)]
|
| 205 |
+
_ = self.solver.solve(initial_rotations=self.initial_rotations, learning_rate=self.args.learning_rate,
|
| 206 |
+
mandatory_objective_functions=tuple(mand), optional_objective_functions=tuple(opt),
|
| 207 |
+
ik_points=1, verbose=False,patience=1,)
|
| 208 |
+
logger.info("Agent warmup complete")
|
| 209 |
+
except Exception as e:
|
| 210 |
+
logger.warning(f"Agent warmup failed: {e}")
|
| 211 |
+
def _warmup_urdf(self):
|
| 212 |
+
try:
|
| 213 |
+
mand = [DistanceObjTraj(target_points=np.array([0.3,0.3,0.35]), bone_name=self.urdf_current_end_effector, use_head=True, weight=1.0)]
|
| 214 |
+
opt = [BoneZeroRotationObj(weight=0.01)]
|
| 215 |
+
_ = self.urdf_solver.solve(initial_rotations=self.urdf_initial_rotations, learning_rate=self.args.learning_rate,
|
| 216 |
+
mandatory_objective_functions=tuple(mand), optional_objective_functions=tuple(opt),
|
| 217 |
+
ik_points=1, verbose=False,patience=1)
|
| 218 |
+
logger.info("URDF warmup complete")
|
| 219 |
+
except Exception as e:
|
| 220 |
+
logger.warning(f"URDF warmup failed: {e}")
|
| 221 |
+
def _warmup_all(self):
|
| 222 |
+
t0 = time.time()
|
| 223 |
+
logger.info("Starting background warmup...")
|
| 224 |
+
self._warmup_agent()
|
| 225 |
+
self._warmup_urdf()
|
| 226 |
+
logger.info(f"Warmup finished in {time.time()-t0:.2f}s")
|
| 227 |
+
|
| 228 |
+
# ---------- Initialization ----------
|
| 229 |
+
def _init_agent(self):
|
| 230 |
+
self.current_num_steps = self._sanitize_num_steps(self.args.num_steps)
|
| 231 |
+
basic = InverseKinematicsSolver(
|
| 232 |
+
model_file=self.args.gltf_file,
|
| 233 |
+
controlled_bones=["left_collar"],
|
| 234 |
+
bounds=[(-90,90)]*3,
|
| 235 |
+
threshold=self.args.threshold,
|
| 236 |
+
num_steps=self.current_num_steps,
|
| 237 |
+
compute_sdf=False,
|
| 238 |
+
)
|
| 239 |
+
self.available_bones = basic.fk_solver.bone_names
|
| 240 |
+
self.bounds_dict = complete_full_body_bounds_dict
|
| 241 |
+
if self.args.hand == "left":
|
| 242 |
+
self.default_controlled_bones = list(left_arm_bounds_dict.keys())#["left_collar","left_shoulder","left_elbow","left_wrist"]
|
| 243 |
+
self.default_end_effector = "left_index3"
|
| 244 |
+
else:
|
| 245 |
+
self.default_controlled_bones = list(right_arm_bounds_dict.keys())
|
| 246 |
+
self.default_end_effector = "right_index3"
|
| 247 |
+
self.selectable_bones = [b for b in self.available_bones if b in self.bounds_dict]
|
| 248 |
+
self.current_controlled_bones = self.default_controlled_bones.copy()
|
| 249 |
+
self.current_end_effector = self.default_end_effector
|
| 250 |
+
# Direct solver creation (no cache)
|
| 251 |
+
self.solver = self._create_solver(self.current_controlled_bones, False, self.current_num_steps)
|
| 252 |
+
self.initial_rotations = np.zeros(len(self.solver.controlled_bones) * 3, dtype=np.float32)
|
| 253 |
+
self.best_angles = self.initial_rotations.copy()
|
| 254 |
+
self.mesh_data = load_mesh_data_from_gltf(self.args.gltf_file, self.solver.fk_solver)
|
| 255 |
+
self.animation_frames_agent = self._frames_from_angles([self.initial_rotations], False)
|
| 256 |
+
|
| 257 |
+
def _init_urdf(self):
|
| 258 |
+
self.urdf_current_num_steps = self._sanitize_num_steps(self.args.num_steps)
|
| 259 |
+
self.urdf_file = "files/pepper_description-master/urdf/pepper.urdf"
|
| 260 |
+
basic = InverseKinematicsSolver(
|
| 261 |
+
model_file=self.urdf_file,
|
| 262 |
+
controlled_bones=["LShoulder"],
|
| 263 |
+
bounds=None,
|
| 264 |
+
threshold=self.args.threshold,
|
| 265 |
+
num_steps=self.urdf_current_num_steps,
|
| 266 |
+
compute_sdf=False,
|
| 267 |
+
)
|
| 268 |
+
self.urdf_available_bones = basic.fk_solver.bone_names
|
| 269 |
+
self.urdf_default_controlled_bones = ["LShoulder","LBicep","LElbow","LForeArm","l_wrist"]
|
| 270 |
+
self.urdf_default_end_effector = "LFinger13_link"
|
| 271 |
+
self.urdf_selectable_bones = list(self.urdf_available_bones)
|
| 272 |
+
self.urdf_current_controlled_bones = self.urdf_default_controlled_bones.copy()
|
| 273 |
+
self.urdf_current_end_effector = self.urdf_default_end_effector
|
| 274 |
+
self.urdf_solver = self._create_solver(self.urdf_current_controlled_bones, True, self.urdf_current_num_steps)
|
| 275 |
+
self.urdf_initial_rotations = np.zeros(len(self.urdf_solver.controlled_bones) * 3, dtype=np.float32)
|
| 276 |
+
self.urdf_best_angles = self.urdf_initial_rotations.copy()
|
| 277 |
+
self.urdf_mesh_data = load_mesh_data_from_urdf(self.urdf_file, self.urdf_solver.fk_solver)
|
| 278 |
+
self.animation_frames_urdf = self._frames_from_angles([self.urdf_initial_rotations], True)
|
| 279 |
+
|
| 280 |
+
# ---------- Objectives ----------
|
| 281 |
+
def _setup_agent_objectives(self):
|
| 282 |
+
self.distance_obj = DistanceObjTraj(
|
| 283 |
+
target_points=np.array([0.0,0.2,0.35]),
|
| 284 |
+
bone_name=self.current_end_effector,
|
| 285 |
+
use_head=True,
|
| 286 |
+
weight=1.0,
|
| 287 |
+
)
|
| 288 |
+
use_fast = os.environ.get("USE_FAST_COLLISION", "1") != "0"
|
| 289 |
+
CollCls = _FastColl if use_fast else SphereCollisionPenaltyObjTraj
|
| 290 |
+
self.collision_obj = CollCls(
|
| 291 |
+
{"center":[0.1,0.0,0.35],"radius":0.1},
|
| 292 |
+
min_clearance=0.0,
|
| 293 |
+
weight=1.0,
|
| 294 |
+
)
|
| 295 |
+
# store defaults for config exposure
|
| 296 |
+
self.collision_default_center = [0.1,0.0,0.35]
|
| 297 |
+
self.collision_default_radius = 0.1
|
| 298 |
+
self.collision_default_min_clearance = 0.0
|
| 299 |
+
|
| 300 |
+
def _setup_urdf_objectives(self):
|
| 301 |
+
self.urdf_distance_obj = DistanceObjTraj(
|
| 302 |
+
target_points=np.array([0.3,0.3,0.35]),
|
| 303 |
+
bone_name=self.urdf_current_end_effector,
|
| 304 |
+
use_head=True,
|
| 305 |
+
weight=1.0,
|
| 306 |
+
)
|
| 307 |
+
use_fast = os.environ.get("USE_FAST_COLLISION", "1") != "0"
|
| 308 |
+
CollCls = _FastColl if use_fast else SphereCollisionPenaltyObjTraj
|
| 309 |
+
self.urdf_collision_obj = CollCls(
|
| 310 |
+
{"center":[0.2,0.0,0.35],"radius":0.1},
|
| 311 |
+
min_clearance=0.0,
|
| 312 |
+
weight=1.0,
|
| 313 |
+
)
|
| 314 |
+
self.urdf_collision_default_center = [0.2,0.0,0.35]
|
| 315 |
+
self.urdf_collision_default_radius = 0.1
|
| 316 |
+
self.urdf_collision_default_min_clearance = 0.0
|
| 317 |
+
|
| 318 |
+
# ---------- Build objectives per request ----------
|
| 319 |
+
def _build_agent_objectives(self, payload):
|
| 320 |
+
tgt = np.array(payload.get("target",[0.0,0.2,0.35]))
|
| 321 |
+
self.distance_obj.update_params({"bone_name": self.current_end_effector, "target_points": tgt, "weight": float(payload.get("distance_weight",1.0))})
|
| 322 |
+
# collision updates (weight, center, radius, min_clearance)
|
| 323 |
+
collision_enabled = payload.get("collision_enabled", False)
|
| 324 |
+
coll_update = {"weight": float(payload.get("collision_weight",1.0)) if collision_enabled else 0.0}
|
| 325 |
+
center = payload.get("collision_center")
|
| 326 |
+
if isinstance(center, (list, tuple)) and len(center)==3:
|
| 327 |
+
coll_update["center"] = center
|
| 328 |
+
radius = payload.get("collision_radius")
|
| 329 |
+
if radius is not None:
|
| 330 |
+
coll_update["radius"] = float(radius)
|
| 331 |
+
if "collision_min_clearance" in payload:
|
| 332 |
+
coll_update["min_clearance"] = float(payload.get("collision_min_clearance", 0.0))
|
| 333 |
+
# Always update params so compiled graph stays stable
|
| 334 |
+
self.collision_obj.update_params(coll_update)
|
| 335 |
+
subpoints = self._safe_int(payload.get("subpoints",1), 1, 1, 100)
|
| 336 |
+
mandatory, optional = [], []
|
| 337 |
+
if payload.get("distance_enabled", True): mandatory.append(self.distance_obj)
|
| 338 |
+
# Always include collision objective to avoid JIT retrace when toggling
|
| 339 |
+
optional.append(self.collision_obj)
|
| 340 |
+
if payload.get("bone_zero_enabled", True):
|
| 341 |
+
optional.append(BoneZeroRotationObj(weight=float(payload.get("bone_zero_weight",0.05))))
|
| 342 |
+
if payload.get("derivative_enabled", True) and subpoints > 1:
|
| 343 |
+
optional.append(CombinedDerivativeObj(max_order=3, weights=[float(payload.get("derivative_weight",0.05))]*3))
|
| 344 |
+
elif not payload.get("bone_zero_enabled", True) and not payload.get("derivative_enabled", True):
|
| 345 |
+
optional.append(BoneZeroRotationObj(weight=0.01))
|
| 346 |
+
# Hand specification
|
| 347 |
+
hand_shape = payload.get("hand_shape","None")
|
| 348 |
+
hand_position = payload.get("hand_position","None")
|
| 349 |
+
params = {
|
| 350 |
+
"is_pointing": hand_shape=="Pointing",
|
| 351 |
+
"is_shaping": hand_shape=="Shaping",
|
| 352 |
+
"is_flat": hand_shape=="Flat",
|
| 353 |
+
"look_forward": hand_position=="Look Forward",
|
| 354 |
+
"look_45_up": hand_position=="Look 45° Up",
|
| 355 |
+
"look_45_down": hand_position=="Look 45° Down",
|
| 356 |
+
"look_up": hand_position=="Look Up",
|
| 357 |
+
"look_down": hand_position=="Look Down",
|
| 358 |
+
"look_45_x_downwards": hand_position=="Look 45° X Downwards",
|
| 359 |
+
"look_45_x_upwards": hand_position=="Look 45° X Upwards",
|
| 360 |
+
"look_x_inward": hand_position=="Look X Inward",
|
| 361 |
+
"look_to_body": hand_position=="Look to Body",
|
| 362 |
+
"arm_down": hand_position=="Arm Down",
|
| 363 |
+
"arm_45_down": hand_position=="Arm 45° Down",
|
| 364 |
+
"arm_flat": hand_position=="Arm Flat",
|
| 365 |
+
}
|
| 366 |
+
if any(params.values()):
|
| 367 |
+
spec = HandSpecification(**params)
|
| 368 |
+
optional.extend(spec.get_objectives(
|
| 369 |
+
left_hand=self.args.hand=="left",
|
| 370 |
+
controlled_bones=self.current_controlled_bones,
|
| 371 |
+
full_trajectory=subpoints>1,
|
| 372 |
+
last_position=True,
|
| 373 |
+
weight=0.5,
|
| 374 |
+
))
|
| 375 |
+
return mandatory, optional, subpoints
|
| 376 |
+
|
| 377 |
+
def _build_urdf_objectives(self, payload):
|
| 378 |
+
tgt = np.array(payload.get("target",[0.3,0.3,0.35]))
|
| 379 |
+
self.urdf_distance_obj.update_params({"bone_name": self.urdf_current_end_effector, "target_points": tgt, "weight": float(payload.get("distance_weight",1.0))})
|
| 380 |
+
collision_enabled = payload.get("collision_enabled", False)
|
| 381 |
+
coll_update = {"weight": float(payload.get("collision_weight",1.0)) if collision_enabled else 0.0}
|
| 382 |
+
center = payload.get("collision_center")
|
| 383 |
+
if isinstance(center, (list, tuple)) and len(center)==3:
|
| 384 |
+
coll_update["center"] = center
|
| 385 |
+
radius = payload.get("collision_radius")
|
| 386 |
+
if radius is not None:
|
| 387 |
+
coll_update["radius"] = float(radius)
|
| 388 |
+
if "collision_min_clearance" in payload:
|
| 389 |
+
coll_update["min_clearance"] = float(payload.get("collision_min_clearance", 0.0))
|
| 390 |
+
self.urdf_collision_obj.update_params(coll_update)
|
| 391 |
+
subpoints = self._safe_int(payload.get("subpoints",1),1,1,100)
|
| 392 |
+
mandatory, optional = [], []
|
| 393 |
+
if payload.get("distance_enabled", True): mandatory.append(self.urdf_distance_obj)
|
| 394 |
+
# Always include collision objective with weight possibly zero
|
| 395 |
+
optional.append(self.urdf_collision_obj)
|
| 396 |
+
if payload.get("bone_zero_enabled", True):
|
| 397 |
+
optional.append(BoneZeroRotationObj(weight=float(payload.get("bone_zero_weight",0.05))))
|
| 398 |
+
if payload.get("derivative_enabled", True) and subpoints > 1:
|
| 399 |
+
optional.append(CombinedDerivativeObj(max_order=3, weights=[float(payload.get("derivative_weight",0.05))]*3))
|
| 400 |
+
elif not payload.get("bone_zero_enabled", True) and not payload.get("derivative_enabled", True):
|
| 401 |
+
optional.append(BoneZeroRotationObj(weight=0.01))
|
| 402 |
+
return mandatory, optional, subpoints
|
| 403 |
+
|
| 404 |
+
# ---------- Frames ----------
|
| 405 |
+
def _frames_from_angles(self, angles_seq, is_urdf):
|
| 406 |
+
frames = []
|
| 407 |
+
for ang in angles_seq:
|
| 408 |
+
try:
|
| 409 |
+
if is_urdf:
|
| 410 |
+
verts = deform_mesh(ang, self.urdf_solver.fk_solver, self.urdf_mesh_data)
|
| 411 |
+
faces = self.urdf_mesh_data["faces"]
|
| 412 |
+
else:
|
| 413 |
+
verts = deform_mesh(ang, self.solver.fk_solver, self.mesh_data)
|
| 414 |
+
faces = self.mesh_data["faces"]
|
| 415 |
+
frames.append({"vertices": verts.tolist(), "faces": faces.tolist()})
|
| 416 |
+
except Exception as e:
|
| 417 |
+
logger.warning(f"Mesh deformation failed: {e}")
|
| 418 |
+
return frames
|
| 419 |
+
|
| 420 |
+
# ---------- Configuration ----------
|
| 421 |
+
def configure_agent(self, bones, eff, num_steps=None):
|
| 422 |
+
with self.config_lock:
|
| 423 |
+
if num_steps is None:
|
| 424 |
+
num_steps = self.current_num_steps
|
| 425 |
+
num_steps = self._sanitize_num_steps(num_steps)
|
| 426 |
+
bones = self._sanitize_bones(bones, False) or self.default_controlled_bones
|
| 427 |
+
if eff not in getattr(self, 'available_bones', []):
|
| 428 |
+
eff = self.default_end_effector
|
| 429 |
+
changed = (bones != self.current_controlled_bones or eff != self.current_end_effector or int(num_steps) != int(self.current_num_steps))
|
| 430 |
+
if changed:
|
| 431 |
+
try:
|
| 432 |
+
self.current_controlled_bones = bones
|
| 433 |
+
self.current_end_effector = eff
|
| 434 |
+
self.current_num_steps = int(num_steps)
|
| 435 |
+
self.solver = self._create_solver(bones, False, self.current_num_steps)
|
| 436 |
+
self.initial_rotations = np.zeros(len(self.solver.controlled_bones)*3, dtype=np.float32)
|
| 437 |
+
self.best_angles = self.initial_rotations.copy()
|
| 438 |
+
self._setup_agent_objectives()
|
| 439 |
+
except Exception as e:
|
| 440 |
+
self.agent_fail_count += 1
|
| 441 |
+
self.last_agent_error = str(e)
|
| 442 |
+
logger.exception("configure_agent failed; attempting default recovery")
|
| 443 |
+
if not self._attempt_solver_recovery(False):
|
| 444 |
+
raise
|
| 445 |
+
return {"controlled_bones": self.current_controlled_bones, "end_effector": self.current_end_effector, "num_steps": self.current_num_steps}
|
| 446 |
+
|
| 447 |
+
def configure_urdf(self, bones, eff, num_steps=None):
|
| 448 |
+
with self.config_lock:
|
| 449 |
+
if num_steps is None:
|
| 450 |
+
num_steps = self.urdf_current_num_steps
|
| 451 |
+
num_steps = self._sanitize_num_steps(num_steps)
|
| 452 |
+
bones = self._sanitize_bones(bones, True) or self.urdf_default_controlled_bones
|
| 453 |
+
if eff not in getattr(self, 'urdf_available_bones', []):
|
| 454 |
+
eff = self.urdf_default_end_effector
|
| 455 |
+
changed = (bones != self.urdf_current_controlled_bones or eff != self.urdf_current_end_effector or int(num_steps) != int(self.urdf_current_num_steps))
|
| 456 |
+
if changed:
|
| 457 |
+
try:
|
| 458 |
+
self.urdf_current_controlled_bones = bones
|
| 459 |
+
self.urdf_current_end_effector = eff
|
| 460 |
+
self.urdf_current_num_steps = int(num_steps)
|
| 461 |
+
self.urdf_solver = self._create_solver(bones, True, self.urdf_current_num_steps)
|
| 462 |
+
self.urdf_initial_rotations = np.zeros(len(self.urdf_solver.controlled_bones)*3, dtype=np.float32)
|
| 463 |
+
self.urdf_best_angles = self.urdf_initial_rotations.copy()
|
| 464 |
+
self._setup_urdf_objectives()
|
| 465 |
+
except Exception as e:
|
| 466 |
+
self.urdf_fail_count += 1
|
| 467 |
+
self.last_urdf_error = str(e)
|
| 468 |
+
logger.exception("configure_urdf failed; attempting default recovery")
|
| 469 |
+
if not self._attempt_solver_recovery(True):
|
| 470 |
+
raise
|
| 471 |
+
return {"controlled_bones": self.urdf_current_controlled_bones, "end_effector": self.urdf_current_end_effector, "num_steps": self.urdf_current_num_steps}
|
| 472 |
+
|
| 473 |
+
# ---------- Solve (hardened) ----------
|
| 474 |
+
def _solve_core(self, solver, init, mand, opt, subpoints, lr):
|
| 475 |
+
return solver.solve(
|
| 476 |
+
initial_rotations=init,
|
| 477 |
+
learning_rate=lr,
|
| 478 |
+
mandatory_objective_functions=tuple(mand),
|
| 479 |
+
optional_objective_functions=tuple(opt),
|
| 480 |
+
ik_points=subpoints,
|
| 481 |
+
verbose=False,
|
| 482 |
+
patience=100,
|
| 483 |
+
)
|
| 484 |
+
|
| 485 |
+
def solve_agent(self, payload, last_only=False):
|
| 486 |
+
if time.time() < self.circuit_open_until:
|
| 487 |
+
return {"status":"circuit_open","error":"agent circuit open","frames":len(self.animation_frames_agent)}
|
| 488 |
+
mand, opt, sub = self._build_agent_objectives(payload)
|
| 489 |
+
lr = self._safe_float(payload.get("learning_rate", self.args.learning_rate), self.args.learning_rate, 1e-5, self.max_learning_rate)
|
| 490 |
+
attempts = 0
|
| 491 |
+
best_angles = None; obj_val = float('inf'); steps = 0; error_msg=None; recovered=False
|
| 492 |
+
start=time.time()
|
| 493 |
+
while attempts < self.max_fail_retries:
|
| 494 |
+
attempts += 1
|
| 495 |
+
try:
|
| 496 |
+
best_angles, obj_val, steps = self._solve_core(self.solver, self.initial_rotations, mand, opt, sub, lr)
|
| 497 |
+
break
|
| 498 |
+
except Exception as e:
|
| 499 |
+
self.agent_fail_count += 1
|
| 500 |
+
error_msg = str(e)
|
| 501 |
+
self.last_agent_error = error_msg
|
| 502 |
+
logger.warning(f"Agent solve attempt {attempts} failed: {e}")
|
| 503 |
+
if attempts < self.max_fail_retries:
|
| 504 |
+
# First retry: rebuild current; second: full recovery
|
| 505 |
+
if attempts == 1:
|
| 506 |
+
self._rebuild_solver_safe(False, force_defaults=False)
|
| 507 |
+
else:
|
| 508 |
+
recovered = self._attempt_solver_recovery(False)
|
| 509 |
+
else:
|
| 510 |
+
break
|
| 511 |
+
if best_angles is None:
|
| 512 |
+
# Provide at least one frame (initial)
|
| 513 |
+
frame_angles = [self.initial_rotations]
|
| 514 |
+
if recovered:
|
| 515 |
+
frame_angles = [self.initial_rotations]
|
| 516 |
+
else:
|
| 517 |
+
self.best_angles = best_angles[-1].copy()
|
| 518 |
+
self.initial_rotations = self.best_angles.copy()
|
| 519 |
+
frame_angles = [best_angles[-1]] if last_only else best_angles
|
| 520 |
+
self.animation_frames_agent = self._frames_from_angles(frame_angles, False)
|
| 521 |
+
self.agent_solve_counter += 1
|
| 522 |
+
# Circuit breaker update
|
| 523 |
+
if best_angles is None and self.agent_fail_count >= self.circuit_breaker_threshold:
|
| 524 |
+
self.circuit_open_until = time.time() + self.circuit_backoff_seconds
|
| 525 |
+
status = "ok" if best_angles is not None else ("recovered" if recovered else "failed")
|
| 526 |
+
return {
|
| 527 |
+
"status":status,
|
| 528 |
+
"solve_time": time.time()-start,
|
| 529 |
+
"iterations": steps,
|
| 530 |
+
"objective": obj_val,
|
| 531 |
+
"frames": len(self.animation_frames_agent),
|
| 532 |
+
"solve_id": self.agent_solve_counter,
|
| 533 |
+
"attempts": attempts,
|
| 534 |
+
"error": error_msg,
|
| 535 |
+
}
|
| 536 |
+
|
| 537 |
+
def solve_urdf(self, payload, last_only=False):
|
| 538 |
+
if time.time() < self.circuit_open_until:
|
| 539 |
+
return {"status":"circuit_open","error":"urdf circuit open","frames":len(self.animation_frames_urdf)}
|
| 540 |
+
mand, opt, sub = self._build_urdf_objectives(payload)
|
| 541 |
+
lr = self._safe_float(payload.get("learning_rate", self.args.learning_rate), self.args.learning_rate, 1e-5, self.max_learning_rate)
|
| 542 |
+
attempts=0
|
| 543 |
+
best_angles=None; obj_val=float('inf'); steps=0; error_msg=None; recovered=False
|
| 544 |
+
start=time.time()
|
| 545 |
+
while attempts < self.max_fail_retries:
|
| 546 |
+
attempts += 1
|
| 547 |
+
try:
|
| 548 |
+
best_angles, obj_val, steps = self._solve_core(self.urdf_solver, self.urdf_initial_rotations, mand, opt, sub, lr)
|
| 549 |
+
break
|
| 550 |
+
except Exception as e:
|
| 551 |
+
self.urdf_fail_count += 1
|
| 552 |
+
error_msg = str(e)
|
| 553 |
+
self.last_urdf_error = error_msg
|
| 554 |
+
logger.warning(f"URDF solve attempt {attempts} failed: {e}")
|
| 555 |
+
if attempts < self.max_fail_retries:
|
| 556 |
+
if attempts == 1:
|
| 557 |
+
self._rebuild_solver_safe(True, force_defaults=False)
|
| 558 |
+
else:
|
| 559 |
+
recovered = self._attempt_solver_recovery(True)
|
| 560 |
+
else:
|
| 561 |
+
break
|
| 562 |
+
if best_angles is None:
|
| 563 |
+
frame_angles = [self.urdf_initial_rotations]
|
| 564 |
+
if recovered:
|
| 565 |
+
frame_angles = [self.urdf_initial_rotations]
|
| 566 |
+
else:
|
| 567 |
+
self.urdf_best_angles = best_angles[-1].copy()
|
| 568 |
+
self.urdf_initial_rotations = self.urdf_best_angles.copy()
|
| 569 |
+
frame_angles = [best_angles[-1]] if last_only else best_angles
|
| 570 |
+
self.animation_frames_urdf = self._frames_from_angles(frame_angles, True)
|
| 571 |
+
self.urdf_solve_counter += 1
|
| 572 |
+
if best_angles is None and self.urdf_fail_count >= self.circuit_breaker_threshold:
|
| 573 |
+
self.circuit_open_until = time.time() + self.circuit_backoff_seconds
|
| 574 |
+
status = "ok" if best_angles is not None else ("recovered" if recovered else "failed")
|
| 575 |
+
return {
|
| 576 |
+
"status":status,
|
| 577 |
+
"solve_time": time.time()-start,
|
| 578 |
+
"iterations": steps,
|
| 579 |
+
"objective": obj_val,
|
| 580 |
+
"frames": len(self.animation_frames_urdf),
|
| 581 |
+
"solve_id": self.urdf_solve_counter,
|
| 582 |
+
"attempts": attempts,
|
| 583 |
+
"error": error_msg,
|
| 584 |
+
}
|
| 585 |
+
|
| 586 |
+
# ---------- Housekeeping ----------
|
| 587 |
+
def _cleanup(self):
|
| 588 |
+
now = time.time()
|
| 589 |
+
if now - self.last_cleanup_time < self.cleanup_interval:
|
| 590 |
+
return
|
| 591 |
+
try:
|
| 592 |
+
gc.collect()
|
| 593 |
+
# Removed cache invalidation logic (no caches anymore)
|
| 594 |
+
except Exception:
|
| 595 |
+
pass
|
| 596 |
+
self.last_cleanup_time = now
|
| 597 |
+
|
| 598 |
+
# ---------- API ----------
|
| 599 |
+
def _register_routes(self):
|
| 600 |
+
@self.app.get("/")
|
| 601 |
+
def index():
|
| 602 |
+
return FileResponse("static/index.html")
|
| 603 |
+
|
| 604 |
+
@self.app.get("/threejs_viewer")
|
| 605 |
+
def legacy():
|
| 606 |
+
return FileResponse("static/index.html")
|
| 607 |
+
|
| 608 |
+
@self.app.get("/animation")
|
| 609 |
+
def animation(request: Request):
|
| 610 |
+
model = request.query_params.get("model","agent").lower()
|
| 611 |
+
data = self.animation_frames_urdf if model == "pepper" else self.animation_frames_agent
|
| 612 |
+
return Response(content=json.dumps(data), media_type="application/json")
|
| 613 |
+
|
| 614 |
+
@self.app.get("/config")
|
| 615 |
+
def cfg(model: str = "agent"):
|
| 616 |
+
if model.lower() == "pepper":
|
| 617 |
+
return {
|
| 618 |
+
"model":"pepper",
|
| 619 |
+
"available_bones": self.urdf_available_bones,
|
| 620 |
+
"selectable_bones": self.urdf_selectable_bones,
|
| 621 |
+
"default_controlled_bones": self.urdf_current_controlled_bones,
|
| 622 |
+
"default_end_effector": self.urdf_current_end_effector,
|
| 623 |
+
"end_effector_choices": self.urdf_available_bones,
|
| 624 |
+
"hand_shapes": [],
|
| 625 |
+
"hand_positions": [],
|
| 626 |
+
"max_subpoints": 20,
|
| 627 |
+
"default_num_steps": self.urdf_current_num_steps,
|
| 628 |
+
"collision_default_center": getattr(self, 'urdf_collision_default_center', [0.2,0.0,0.35]),
|
| 629 |
+
"collision_default_radius": getattr(self, 'urdf_collision_default_radius', 0.1),
|
| 630 |
+
"collision_default_min_clearance": getattr(self, 'urdf_collision_default_min_clearance', 0.0),
|
| 631 |
+
}
|
| 632 |
+
return {
|
| 633 |
+
"model":"agent",
|
| 634 |
+
"available_bones": self.available_bones,
|
| 635 |
+
"selectable_bones": self.selectable_bones,
|
| 636 |
+
"default_controlled_bones": self.current_controlled_bones,
|
| 637 |
+
"default_end_effector": self.current_end_effector,
|
| 638 |
+
"end_effector_choices": self.available_bones,
|
| 639 |
+
"hand_shapes":["None","Pointing","Shaping","Flat"],
|
| 640 |
+
"hand_positions":[
|
| 641 |
+
"None","Look Forward","Look 45° Up","Look 45° Down","Look Up","Look Down",
|
| 642 |
+
"Look 45° X Downwards","Look 45° X Upwards","Look X Inward","Look to Body",
|
| 643 |
+
"Arm Down","Arm 45° Down","Arm Flat"
|
| 644 |
+
],
|
| 645 |
+
"max_subpoints": 20,
|
| 646 |
+
"default_num_steps": self.current_num_steps,
|
| 647 |
+
"collision_default_center": getattr(self, 'collision_default_center', [0.1,0.0,0.35]),
|
| 648 |
+
"collision_default_radius": getattr(self, 'collision_default_radius', 0.1),
|
| 649 |
+
"collision_default_min_clearance": getattr(self, 'collision_default_min_clearance', 0.0),
|
| 650 |
+
}
|
| 651 |
+
|
| 652 |
+
@self.app.post("/configure")
|
| 653 |
+
async def configure(request: Request):
|
| 654 |
+
payload = await request.json()
|
| 655 |
+
model = payload.get("model","agent").lower()
|
| 656 |
+
num_steps = self._sanitize_num_steps(payload.get("num_steps", self.args.num_steps))
|
| 657 |
+
try:
|
| 658 |
+
if model == "pepper":
|
| 659 |
+
cfg = self.configure_urdf(payload.get("controlled_bones", []), payload.get("end_effector"), num_steps=num_steps)
|
| 660 |
+
else:
|
| 661 |
+
cfg = self.configure_agent(payload.get("controlled_bones", []), payload.get("end_effector"), num_steps=num_steps)
|
| 662 |
+
return JSONResponse({"status":"ok","config":cfg})
|
| 663 |
+
except Exception as e:
|
| 664 |
+
return JSONResponse({"status":"error","message":str(e)}, status_code=500)
|
| 665 |
+
|
| 666 |
+
@self.app.post("/solve")
|
| 667 |
+
async def solve(request: Request):
|
| 668 |
+
payload = await request.json()
|
| 669 |
+
model = payload.get("model","agent").lower()
|
| 670 |
+
return_mode = payload.get("frames_mode", "auto")
|
| 671 |
+
num_steps = self._sanitize_num_steps(payload.get("num_steps", self.args.num_steps))
|
| 672 |
+
subpoints = self._safe_int(payload.get("subpoints",1),1,1,100)
|
| 673 |
+
last_only = (return_mode != 'all' and subpoints == 1)
|
| 674 |
+
self._cleanup()
|
| 675 |
+
with self.solve_lock:
|
| 676 |
+
try:
|
| 677 |
+
if model == "pepper":
|
| 678 |
+
self.configure_urdf(payload.get("controlled_bones", []), payload.get("end_effector", self.urdf_current_end_effector), num_steps=num_steps)
|
| 679 |
+
result = self.solve_urdf(payload, last_only=last_only); result["model"]="pepper"; result["num_steps"] = num_steps
|
| 680 |
+
if last_only:
|
| 681 |
+
frames = list(self.animation_frames_urdf)
|
| 682 |
+
elif return_mode == "all" or (return_mode == "auto" and subpoints > 1):
|
| 683 |
+
frames = list(self.animation_frames_urdf)
|
| 684 |
+
else:
|
| 685 |
+
frames = [self.animation_frames_urdf[-1]]
|
| 686 |
+
result["frames_data"] = frames
|
| 687 |
+
else:
|
| 688 |
+
self.configure_agent(payload.get("controlled_bones", []), payload.get("end_effector", self.current_end_effector), num_steps=num_steps)
|
| 689 |
+
result = self.solve_agent(payload, last_only=last_only); result["model"]="agent"; result["num_steps"] = num_steps
|
| 690 |
+
if last_only:
|
| 691 |
+
frames = list(self.animation_frames_agent)
|
| 692 |
+
elif return_mode == "all" or (return_mode == "auto" and subpoints > 1):
|
| 693 |
+
frames = list(self.animation_frames_agent)
|
| 694 |
+
else:
|
| 695 |
+
frames = [self.animation_frames_agent[-1]]
|
| 696 |
+
result["frames_data"] = frames
|
| 697 |
+
status = result.get("status","ok")
|
| 698 |
+
top_status = "ok" if status in ("ok","recovered") else status
|
| 699 |
+
return JSONResponse({"status":top_status,"result":result})
|
| 700 |
+
except Exception as e:
|
| 701 |
+
logger.exception("Solve failed unrecoverably")
|
| 702 |
+
return JSONResponse({"status":"error","message":str(e)}, status_code=500)
|
| 703 |
+
|
| 704 |
+
@self.app.post("/reset")
|
| 705 |
+
def reset():
|
| 706 |
+
with self.solve_lock:
|
| 707 |
+
self._attempt_solver_recovery(False)
|
| 708 |
+
self._attempt_solver_recovery(True)
|
| 709 |
+
return {"status":"ok","message":"solvers reset"}
|
| 710 |
+
|
| 711 |
+
@self.app.get("/health")
|
| 712 |
+
def health():
|
| 713 |
+
rss = self.process.memory_info().rss if self.process else 0
|
| 714 |
+
return {
|
| 715 |
+
"status":"ok",
|
| 716 |
+
"agent_frames": len(self.animation_frames_agent),
|
| 717 |
+
"urdf_frames": len(self.animation_frames_urdf),
|
| 718 |
+
"agent_fail_count": self.agent_fail_count,
|
| 719 |
+
"urdf_fail_count": self.urdf_fail_count,
|
| 720 |
+
"last_agent_error": self.last_agent_error,
|
| 721 |
+
"last_urdf_error": self.last_urdf_error,
|
| 722 |
+
"circuit_open_for": max(0, int(self.circuit_open_until - time.time())),
|
| 723 |
+
"memory_rss_mb": round(rss/1024/1024,1),
|
| 724 |
+
}
|
| 725 |
+
|
| 726 |
+
@self.app.get("/favicon.ico")
|
| 727 |
+
def favicon():
|
| 728 |
+
return Response(status_code=204)
|
| 729 |
+
|
| 730 |
+
# ---------- Main ----------
|
| 731 |
+
def main():
|
| 732 |
+
parser = configargparse.ArgumentParser(description="Inverse Kinematics Solver - Three.js Web UI", default_config_files=["config.ini"])
|
| 733 |
+
parser.add_argument("--gltf_file", type=str, default="files/smplx.glb")
|
| 734 |
+
parser.add_argument("--hand", type=str, choices=["left","right"], default="left")
|
| 735 |
+
parser.add_argument("--threshold", type=float, default=0.005)
|
| 736 |
+
parser.add_argument("--num_steps", type=int, default=100)
|
| 737 |
+
parser.add_argument("--learning_rate", type=float, default=0.2)
|
| 738 |
+
parser.add_argument("--subpoints", type=int, default=1)
|
| 739 |
+
parser.add_argument("--api_port", type=int, default=17861)
|
| 740 |
+
parser.add_argument("--warmup", action='store_true', default=True, help="Enable background JIT warmup")
|
| 741 |
+
args = parser.parse_args()
|
| 742 |
+
|
| 743 |
+
download_and_setup_files()
|
| 744 |
+
srv = IKServer(args)
|
| 745 |
+
import uvicorn
|
| 746 |
+
uvicorn.run(srv.app, host="0.0.0.0", port=args.api_port)
|
| 747 |
+
|
| 748 |
+
if __name__ == "__main__":
|
| 749 |
+
main()
|
collision_objectives.py
ADDED
|
@@ -0,0 +1,83 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
import jax
|
| 2 |
+
import jax.numpy as jnp
|
| 3 |
+
import numpy as np
|
| 4 |
+
from jax.tree_util import register_pytree_node_class
|
| 5 |
+
from jax_ik.objectives import ObjectiveFunction
|
| 6 |
+
|
| 7 |
+
@register_pytree_node_class
|
| 8 |
+
class FastSphereCollisionPenaltyObjTraj(ObjectiveFunction):
|
| 9 |
+
"""Vectorized sphere collision penalty over bone segments.
|
| 10 |
+
|
| 11 |
+
Weight stored as Python float (static aux) to avoid tracer-to-Python
|
| 12 |
+
concretization when objective always present with varying weight.
|
| 13 |
+
"""
|
| 14 |
+
def __init__(self, sphere_collider: dict, weight: float = 1.0, min_clearance: float = 0.05, segment_radius: float = 0.02):
|
| 15 |
+
self.center = jnp.asarray(sphere_collider["center"], jnp.float32)
|
| 16 |
+
self.radius = jnp.asarray(sphere_collider["radius"], jnp.float32)
|
| 17 |
+
self.min_clearance = jnp.asarray(min_clearance, jnp.float32)
|
| 18 |
+
self.segment_radius = jnp.asarray(segment_radius, jnp.float32)
|
| 19 |
+
self.weight = float(weight)
|
| 20 |
+
|
| 21 |
+
# pytree impl ------------------------------------------------------------
|
| 22 |
+
def tree_flatten(self):
|
| 23 |
+
# weight treated as static (aux) so changing it may retrace but avoids concretization errors
|
| 24 |
+
return (self.center, self.radius, self.min_clearance, self.segment_radius), (self.weight,)
|
| 25 |
+
|
| 26 |
+
@classmethod
|
| 27 |
+
def tree_unflatten(cls, aux, leaves):
|
| 28 |
+
(weight,) = aux
|
| 29 |
+
c, r, mc, sr = leaves
|
| 30 |
+
return cls(dict(center=c, radius=r), weight, mc, sr)
|
| 31 |
+
|
| 32 |
+
# API --------------------------------------------------------------------
|
| 33 |
+
def update_params(self, p: dict) -> None:
|
| 34 |
+
if "sphere_collider" in p:
|
| 35 |
+
collider = p["sphere_collider"]
|
| 36 |
+
if "center" in collider:
|
| 37 |
+
self.center = jnp.asarray(collider["center"], jnp.float32)
|
| 38 |
+
if "radius" in collider:
|
| 39 |
+
self.radius = jnp.asarray(collider["radius"], jnp.float32)
|
| 40 |
+
if "center" in p:
|
| 41 |
+
self.center = jnp.asarray(p["center"], jnp.float32)
|
| 42 |
+
if "radius" in p:
|
| 43 |
+
self.radius = jnp.asarray(p["radius"], jnp.float32)
|
| 44 |
+
if "min_clearance" in p:
|
| 45 |
+
self.min_clearance = jnp.asarray(p["min_clearance"], jnp.float32)
|
| 46 |
+
if "segment_radius" in p:
|
| 47 |
+
self.segment_radius = jnp.asarray(p["segment_radius"], jnp.float32)
|
| 48 |
+
if "weight" in p:
|
| 49 |
+
self.weight = float(p["weight"])
|
| 50 |
+
|
| 51 |
+
def get_params(self) -> dict:
|
| 52 |
+
return dict(
|
| 53 |
+
sphere_collider=dict(center=np.asarray(self.center).tolist(), radius=float(self.radius)),
|
| 54 |
+
min_clearance=float(self.min_clearance),
|
| 55 |
+
segment_radius=float(self.segment_radius),
|
| 56 |
+
weight=float(self.weight),
|
| 57 |
+
)
|
| 58 |
+
|
| 59 |
+
# core -------------------------------------------------------------------
|
| 60 |
+
def _penalty_single(self, cfg, fk_solver) -> jnp.ndarray:
|
| 61 |
+
fk = fk_solver.compute_fk_from_angles(cfg) # (N,4,4)
|
| 62 |
+
heads = fk[:, :3, 3] # (N,3)
|
| 63 |
+
parents = jnp.asarray(fk_solver.parent_list, jnp.int32) # (N,)
|
| 64 |
+
seg_mask = (parents >= 0).astype(jnp.float32) # (N,)
|
| 65 |
+
safe_parent_indices = jnp.where(parents >= 0, parents, 0)
|
| 66 |
+
p_head = heads[safe_parent_indices]
|
| 67 |
+
c_head = heads
|
| 68 |
+
v = c_head - p_head
|
| 69 |
+
dot_vv = jnp.sum(v * v, axis=1) + 1e-6
|
| 70 |
+
eff_rad = self.radius + self.min_clearance + self.segment_radius
|
| 71 |
+
vc = self.center - p_head
|
| 72 |
+
t = jnp.clip(jnp.sum(vc * v, axis=1) / dot_vv, 0.0, 1.0)
|
| 73 |
+
closest = p_head + t[:, None] * v
|
| 74 |
+
dist = jnp.linalg.norm(self.center - closest, axis=1)
|
| 75 |
+
penetration = jnp.maximum(0.0, eff_rad - dist)
|
| 76 |
+
return jnp.sum((penetration ** 2) * seg_mask)
|
| 77 |
+
|
| 78 |
+
def __call__(self, X: jnp.ndarray, fk_solver) -> jnp.ndarray:
|
| 79 |
+
if X.ndim == 1:
|
| 80 |
+
loss = self._penalty_single(X, fk_solver)
|
| 81 |
+
else:
|
| 82 |
+
loss = jnp.mean(jax.vmap(lambda c: self._penalty_single(c, fk_solver))(X))
|
| 83 |
+
return loss * jnp.float32(self.weight)
|
packages.txt
ADDED
|
@@ -0,0 +1,2 @@
|
|
|
|
|
|
|
|
|
|
| 1 |
+
xvfb
|
| 2 |
+
libgl1-mesa-glx
|
requirements.txt
ADDED
|
@@ -0,0 +1,8 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
jax-ik==0.1.6
|
| 2 |
+
wandb
|
| 3 |
+
pillow
|
| 4 |
+
scipy
|
| 5 |
+
configargparse
|
| 6 |
+
requests
|
| 7 |
+
uvicorn
|
| 8 |
+
fastapi
|
static/index.html
ADDED
|
@@ -0,0 +1,473 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<!DOCTYPE html>
|
| 2 |
+
<html lang="en">
|
| 3 |
+
<head>
|
| 4 |
+
<meta charset="UTF-8">
|
| 5 |
+
<title>JAX-IK Three.js IK Demo</title>
|
| 6 |
+
<style>
|
| 7 |
+
body { margin:0; font-family:Arial, sans-serif; background:#1e1e1e; color:#ddd; }
|
| 8 |
+
header { padding:10px 16px; background:#111; border-bottom:1px solid #333; }
|
| 9 |
+
h1 { margin:0; font-size:18px; }
|
| 10 |
+
#tabs { display:flex; background:#222; }
|
| 11 |
+
.tab-btn { padding:10px 16px; cursor:pointer; border:none; background:#222; color:#ccc; font-size:13px; }
|
| 12 |
+
.tab-btn.active { background:#333; color:#fff; }
|
| 13 |
+
#content { display:flex; height:calc(100vh - 82px); }
|
| 14 |
+
#viewerPane { flex: 1 1 auto; position:relative; }
|
| 15 |
+
#uiPane { width:360px; overflow-y:auto; background:#181818; border-left:1px solid #333; padding:10px 12px; box-sizing:border-box; }
|
| 16 |
+
fieldset { border:1px solid #444; margin:8px 0 14px 0; padding:8px 10px; }
|
| 17 |
+
legend { padding:0 6px; font-size:12px; color:#9ad; }
|
| 18 |
+
label { display:block; font-size:12px; margin:4px 0; }
|
| 19 |
+
input[type=number], select { width:100%; box-sizing:border-box; background:#222; border:1px solid #444; color:#ddd; padding:4px; }
|
| 20 |
+
input[type=text] { width:100%; box-sizing:border-box; background:#222; border:1px solid #444; color:#ddd; padding:4px; }
|
| 21 |
+
button.primary { background:#2d6be3; color:#fff; border:none; padding:8px 12px; cursor:pointer; font-size:12px; border-radius:3px; }
|
| 22 |
+
button.secondary { background:#444; color:#eee; border:none; padding:6px 10px; cursor:pointer; font-size:12px; border-radius:3px; margin-left:4px; }
|
| 23 |
+
.flex-row { display:flex; gap:6px; }
|
| 24 |
+
.inline { display:inline-block; }
|
| 25 |
+
#statusBar { font-size:11px; background:#111; padding:6px 10px; border-top:1px solid #333; position:fixed; bottom:0; left:0; right:0; color:#aaa; }
|
| 26 |
+
.bone-grid { columns:2 140px; column-gap:12px; }
|
| 27 |
+
.bone-grid label { break-inside:avoid; }
|
| 28 |
+
.viewer-canvas { position:absolute; top:0; left:0; width:100%; height:100%; }
|
| 29 |
+
#log { position:absolute; right:8px; top:8px; max-width:260px; max-height:50%; overflow:auto; font:11px monospace; background:rgba(0,0,0,0.55); padding:6px; border:1px solid #444; border-radius:4px; }
|
| 30 |
+
.badge { font-size:10px; background:#444; color:#ccc; padding:2px 5px; border-radius:3px; margin-left:4px; }
|
| 31 |
+
#toastContainer { position:fixed; /* moved from top-left to bottom-left */ bottom:56px; left:10px; z-index:9999; display:flex; flex-direction:column; gap:8px; pointer-events:none; }
|
| 32 |
+
.toast { min-width:220px; max-width:300px; background:rgba(30,30,30,0.95); color:#eee; font:12px/1.4 Arial, sans-serif;
|
| 33 |
+
border:1px solid #444; border-radius:4px; padding:8px 10px; box-shadow:0 4px 12px rgba(0,0,0,0.4);
|
| 34 |
+
opacity:0; transform:translateY(6px); transition:opacity .18s ease, transform .18s ease; pointer-events:auto; }
|
| 35 |
+
.toast.show { opacity:1; transform:translateY(0); }
|
| 36 |
+
.toast.success { border-color:#2e8b57; }
|
| 37 |
+
.toast.error { border-color:#b33939; }
|
| 38 |
+
.toast .toast-close { float:right; cursor:pointer; color:#888; margin-left:6px; }
|
| 39 |
+
.toast .toast-close:hover { color:#fff; }
|
| 40 |
+
.axis-pair { margin:4px 0; }
|
| 41 |
+
.axis-pair .flex-row { align-items:center; }
|
| 42 |
+
.axis-pair span { width:14px; display:inline-block; font-size:11px; color:#aaa; }
|
| 43 |
+
</style>
|
| 44 |
+
<!-- Added import map to resolve bare specifier 'three' -->
|
| 45 |
+
<script type="importmap">
|
| 46 |
+
{
|
| 47 |
+
"imports": {
|
| 48 |
+
"three": "https://unpkg.com/three@0.160.0/build/three.module.js"
|
| 49 |
+
}
|
| 50 |
+
}
|
| 51 |
+
</script>
|
| 52 |
+
</head>
|
| 53 |
+
<body>
|
| 54 |
+
<header>
|
| 55 |
+
<h1>
|
| 56 |
+
<a href="https://github.com/hvoss-techfak/TF-JAX-IK" target="_blank" rel="noopener noreferrer" style="color:#fff; text-decoration:none;">
|
| 57 |
+
JAX IK Demo - Please visit our Github Page for more information
|
| 58 |
+
</a>
|
| 59 |
+
<span class="badge" id="modelBadge">Agent</span>
|
| 60 |
+
</h1>
|
| 61 |
+
</header>
|
| 62 |
+
<div id="tabs">
|
| 63 |
+
<button class="tab-btn active" data-model="agent">Virtual Agent</button>
|
| 64 |
+
<button class="tab-btn" data-model="pepper">URDF Robot</button>
|
| 65 |
+
</div>
|
| 66 |
+
<div id="content">
|
| 67 |
+
<div id="viewerPane">
|
| 68 |
+
<div id="log"></div>
|
| 69 |
+
<!-- Canvas inserted by three.js -->
|
| 70 |
+
</div>
|
| 71 |
+
<div id="uiPane">
|
| 72 |
+
<fieldset>
|
| 73 |
+
<legend>Target Position</legend>
|
| 74 |
+
<label>X
|
| 75 |
+
<div class="flex-row">
|
| 76 |
+
<input id="target_x" type="number" value="0.0" step="0.01" data-auto-solve="change">
|
| 77 |
+
<input id="target_x_slider" type="range" min="-1" max="1" step="0.01" value="0.0">
|
| 78 |
+
</div>
|
| 79 |
+
</label>
|
| 80 |
+
<label>Y
|
| 81 |
+
<div class="flex-row">
|
| 82 |
+
<input id="target_y" type="number" value="0.2" step="0.01" data-auto-solve="change">
|
| 83 |
+
<input id="target_y_slider" type="range" min="-1" max="1" step="0.01" value="0.2">
|
| 84 |
+
</div>
|
| 85 |
+
</label>
|
| 86 |
+
<label>Z <input id="target_z" type="number" value="0.35" step="0.01" data-auto-solve="change"></label>
|
| 87 |
+
<label>Trajectory Points
|
| 88 |
+
<!-- changed: removed '(static only)', removed disabled, max updated dynamically -->
|
| 89 |
+
<input id="subpoints" type="number" value="1" min="1" max="20" step="1" data-auto-solve="change">
|
| 90 |
+
</label>
|
| 91 |
+
</fieldset>
|
| 92 |
+
<fieldset>
|
| 93 |
+
<legend>Primary Objectives</legend>
|
| 94 |
+
<label><input id="distance_enabled" type="checkbox" checked> Distance Objective</label>
|
| 95 |
+
<label>Distance Weight <input id="distance_weight" type="number" value="1.0" step="0.1"></label>
|
| 96 |
+
</fieldset>
|
| 97 |
+
<fieldset id="collisionFieldset">
|
| 98 |
+
<legend>Collision Sphere</legend>
|
| 99 |
+
<label><input id="collision_enabled" type="checkbox"> Enable Collision Sphere</label>
|
| 100 |
+
<div class="axis-pair">X
|
| 101 |
+
<div class="flex-row">
|
| 102 |
+
<input id="collision_cx" type="number" value="0.1" step="0.01">
|
| 103 |
+
<input id="collision_cx_slider" type="range" min="-1" max="1" step="0.01" value="0.1">
|
| 104 |
+
</div>
|
| 105 |
+
</div>
|
| 106 |
+
<div class="axis-pair">Y
|
| 107 |
+
<div class="flex-row">
|
| 108 |
+
<input id="collision_cy" type="number" value="0.0" step="0.01">
|
| 109 |
+
<input id="collision_cy_slider" type="range" min="-1" max="1" step="0.01" value="0.0">
|
| 110 |
+
</div>
|
| 111 |
+
</div>
|
| 112 |
+
<div class="axis-pair">Z
|
| 113 |
+
<div class="flex-row">
|
| 114 |
+
<input id="collision_cz" type="number" value="0.35" step="0.01">
|
| 115 |
+
<input id="collision_cz_slider" type="range" min="-1" max="1" step="0.01" value="0.35">
|
| 116 |
+
</div>
|
| 117 |
+
</div>
|
| 118 |
+
<label>Collision Weight <input id="collision_weight" type="number" value="1.0" step="0.1"></label>
|
| 119 |
+
<label>Sphere Radius <input id="collision_radius" type="number" value="0.1" step="0.01" min="0.01" max="1.0"></label>
|
| 120 |
+
<label>Min Clearance
|
| 121 |
+
<div class="flex-row">
|
| 122 |
+
<input id="collision_min_clearance" type="number" value="0.0" step="0.005" min="0" max="0.5">
|
| 123 |
+
<input id="collision_min_clearance_slider" type="range" min="0" max="0.5" step="0.005" value="0.0">
|
| 124 |
+
</div>
|
| 125 |
+
</label>
|
| 126 |
+
</fieldset>
|
| 127 |
+
<fieldset>
|
| 128 |
+
<legend>Regularization</legend>
|
| 129 |
+
<label><input id="bone_zero_enabled" type="checkbox" checked> Bone Zero Rotation</label>
|
| 130 |
+
<label>Bone Zero Weight <input id="bone_zero_weight" type="number" value="0.1" step="0.01"></label>
|
| 131 |
+
<label><input id="derivative_enabled" type="checkbox" checked> Trajectory Smoothing</label>
|
| 132 |
+
<label>Derivative Weight <input id="derivative_weight" type="number" value="0.05" step="0.01"></label>
|
| 133 |
+
</fieldset>
|
| 134 |
+
<fieldset id="handFieldset">
|
| 135 |
+
<legend>Hand (Agent Only)</legend>
|
| 136 |
+
<label>Hand Shape
|
| 137 |
+
<select id="hand_shape"></select>
|
| 138 |
+
</label>
|
| 139 |
+
<label>Hand Position
|
| 140 |
+
<select id="hand_position"></select>
|
| 141 |
+
</label>
|
| 142 |
+
</fieldset>
|
| 143 |
+
<fieldset>
|
| 144 |
+
<legend>Configuration</legend>
|
| 145 |
+
<label>End Effector
|
| 146 |
+
<select id="end_effector"></select>
|
| 147 |
+
</label>
|
| 148 |
+
<div style="margin-top:6px; font-size:12px;">Controlled Bones:</div>
|
| 149 |
+
<div id="bonesContainer" class="bone-grid"></div>
|
| 150 |
+
</fieldset>
|
| 151 |
+
<fieldset>
|
| 152 |
+
<legend>Model / Animation</legend>
|
| 153 |
+
<!-- CHANGED: added explicit style to ensure invisibility -->
|
| 154 |
+
<label hidden style="display:none;">GLTF URL <input id="gltf_url" type="text" value="/files/smplx.glb"></label>
|
| 155 |
+
<div class="flex-row" style="margin-top:6px;">
|
| 156 |
+
<button id="reset_cam" class="secondary" type="button">Reset Camera</button>
|
| 157 |
+
</div>
|
| 158 |
+
<label style="margin-top:8px;"><input id="wireframe" type="checkbox"> Wireframe</label>
|
| 159 |
+
<label style="margin-top:4px;"><input id="show_gltf" type="checkbox" checked> Show GLTF Reference</label>
|
| 160 |
+
<label style="margin-top:4px;"><input id="show_ikmesh" type="checkbox" checked> Show IK Mesh</label>
|
| 161 |
+
<label>Playback FPS <input id="play_fps" type="number" value="24" min="1" max="120"></label>
|
| 162 |
+
</fieldset>
|
| 163 |
+
<fieldset>
|
| 164 |
+
<legend>Solver</legend>
|
| 165 |
+
<label>Steps <input id="num_steps" type="number" value="50" min="1" max="10000" step="10"></label>
|
| 166 |
+
</fieldset>
|
| 167 |
+
<div style="text-align:right; margin-top:10px;">
|
| 168 |
+
<button id="solve_btn" class="primary" type="button">Solve IK</button>
|
| 169 |
+
</div>
|
| 170 |
+
</div>
|
| 171 |
+
</div>
|
| 172 |
+
<div id="statusBar">Ready.</div>
|
| 173 |
+
<div id="toastContainer"></div>
|
| 174 |
+
<script type="module">
|
| 175 |
+
import * as THREE from 'three';
|
| 176 |
+
import { OrbitControls } from 'https://unpkg.com/three@0.160.0/examples/jsm/controls/OrbitControls.js';
|
| 177 |
+
import { GLTFLoader } from 'https://unpkg.com/three@0.160.0/examples/jsm/loaders/GLTFLoader.js';
|
| 178 |
+
|
| 179 |
+
(function(){
|
| 180 |
+
// ----- Logging -----
|
| 181 |
+
const logEl = document.getElementById('log');
|
| 182 |
+
function log(msg){
|
| 183 |
+
const t = new Date().toISOString().split('T')[1].replace('Z','');
|
| 184 |
+
logEl.textContent = `[${t}] ${msg}\n` + logEl.textContent.slice(0, 8000);
|
| 185 |
+
}
|
| 186 |
+
|
| 187 |
+
// ----- State -----
|
| 188 |
+
let currentModel = 'agent';
|
| 189 |
+
let configData = null;
|
| 190 |
+
let animationFrames = [];
|
| 191 |
+
let frameIndex = 0;
|
| 192 |
+
let ikMesh = null;
|
| 193 |
+
let usingGLTFGeometry = false;
|
| 194 |
+
let gltfRoot = null;
|
| 195 |
+
let gltfPrimaryMaterial = null;
|
| 196 |
+
let gltfPrimaryMesh = null;
|
| 197 |
+
let gltfPrimaryMaterialCaptured = false;
|
| 198 |
+
let fallbackMesh = null;
|
| 199 |
+
let lastTime = performance.now();
|
| 200 |
+
let lastSolveIdAgent = 0;
|
| 201 |
+
let lastSolveIdPepper = 0;
|
| 202 |
+
|
| 203 |
+
// ----- Auto-solve -----
|
| 204 |
+
let solving = false;
|
| 205 |
+
let solveDebounceTimer = null;
|
| 206 |
+
const SOLVE_DEBOUNCE_MS = 25;
|
| 207 |
+
let currentSolveController = null;
|
| 208 |
+
function scheduleSolve(immediate=false){
|
| 209 |
+
if (solving){ if (currentSolveController) currentSolveController.abort(); }
|
| 210 |
+
if (immediate){ triggerSolve(true); return; }
|
| 211 |
+
if (solveDebounceTimer) clearTimeout(solveDebounceTimer);
|
| 212 |
+
solveDebounceTimer = setTimeout(()=> triggerSolve(false), SOLVE_DEBOUNCE_MS);
|
| 213 |
+
}
|
| 214 |
+
async function triggerSolve(){
|
| 215 |
+
if (currentSolveController) currentSolveController.abort();
|
| 216 |
+
currentSolveController = new AbortController();
|
| 217 |
+
const controller = currentSolveController;
|
| 218 |
+
solving = true;
|
| 219 |
+
try { await doSolve(controller.signal); }
|
| 220 |
+
catch(e){ if (e.name !== 'AbortError') {} }
|
| 221 |
+
finally { if (controller === currentSolveController) solving = false; }
|
| 222 |
+
}
|
| 223 |
+
|
| 224 |
+
// Playback state
|
| 225 |
+
let playbackEnabled = false;
|
| 226 |
+
const allowLoopPlayback = false;
|
| 227 |
+
|
| 228 |
+
// Ground alignment state
|
| 229 |
+
let baseOffsetY = 0;
|
| 230 |
+
let groundAligned = false;
|
| 231 |
+
let pendingAlign = false;
|
| 232 |
+
let alignAttemptCount = 0;
|
| 233 |
+
const maxAlignAttempts = 120;
|
| 234 |
+
|
| 235 |
+
// Trajectory / spline state
|
| 236 |
+
let controlFrames = [];
|
| 237 |
+
let splineMode = false;
|
| 238 |
+
let splineU = 0;
|
| 239 |
+
let splineDuration = 2.0;
|
| 240 |
+
let initialCameraFramed = false;
|
| 241 |
+
|
| 242 |
+
function cleanupVisuals(){
|
| 243 |
+
if (fallbackMesh){
|
| 244 |
+
modelGroup.remove(fallbackMesh);
|
| 245 |
+
if (fallbackMesh.geometry) fallbackMesh.geometry.dispose();
|
| 246 |
+
if (fallbackMesh.material) fallbackMesh.material.dispose();
|
| 247 |
+
fallbackMesh = null;
|
| 248 |
+
}
|
| 249 |
+
if (gltfRoot){
|
| 250 |
+
gltfRoot.traverse(o=>{ if (o.isMesh){ if (o.geometry) o.geometry.dispose(); if (o.material){ if (Array.isArray(o.material)) o.material.forEach(m=>m.dispose()); else o.material.dispose(); } } });
|
| 251 |
+
modelGroup.remove(gltfRoot); gltfRoot = null;
|
| 252 |
+
}
|
| 253 |
+
while (modelGroup.children.length) modelGroup.remove(modelGroup.children[0]);
|
| 254 |
+
gltfPrimaryMesh = null; gltfPrimaryMaterial = null; gltfPrimaryMaterialCaptured = false; ikMesh = null; usingGLTFGeometry = false;
|
| 255 |
+
animationFrames = []; frameIndex = 0; baseOffsetY = 0; groundAligned = false; pendingAlign = false; alignAttemptCount = 0;
|
| 256 |
+
log('Visuals cleaned.');
|
| 257 |
+
}
|
| 258 |
+
function scheduleGroundAlign(force=false){ if (force){ groundAligned=false; alignAttemptCount=0; } pendingAlign=true; }
|
| 259 |
+
function performGroundAlign(){
|
| 260 |
+
if (!pendingAlign) return;
|
| 261 |
+
if (!modelGroup.children.length){ if (++alignAttemptCount > maxAlignAttempts) pendingAlign=false; return; }
|
| 262 |
+
const box = new THREE.Box3().setFromObject(modelGroup);
|
| 263 |
+
if (box.isEmpty() || !isFinite(box.min.y)){ if (++alignAttemptCount > maxAlignAttempts) pendingAlign=false; return; }
|
| 264 |
+
const currentMin = box.min.y; const delta = -currentMin;
|
| 265 |
+
if (delta > 0 || Math.abs(delta) < 1e-3){
|
| 266 |
+
modelGroup.position.y += delta; baseOffsetY = modelGroup.position.y; groundAligned = true; updateTargetSphere(); updateCollisionSphere();
|
| 267 |
+
}
|
| 268 |
+
pendingAlign=false;
|
| 269 |
+
}
|
| 270 |
+
function fitCamera(obj){
|
| 271 |
+
const targetObj = modelGroup.children.length ? modelGroup : obj; if (!targetObj) return;
|
| 272 |
+
const box = new THREE.Box3().setFromObject(targetObj); if (box.isEmpty()) return;
|
| 273 |
+
const size = box.getSize(new THREE.Vector3()); const center = box.getCenter(new THREE.Vector3());
|
| 274 |
+
controls.target.copy(center); const maxDim = Math.max(size.x,size.y,size.z);
|
| 275 |
+
const dist = maxDim * 3; const dir = new THREE.Vector3(0.0,0.5,1).normalize();
|
| 276 |
+
camera.position.copy(center).addScaledVector(dir, dist);
|
| 277 |
+
camera.near = maxDim/100; camera.far = maxDim*100; camera.updateProjectionMatrix(); controls.update();
|
| 278 |
+
}
|
| 279 |
+
|
| 280 |
+
// ----- DOM refs -----
|
| 281 |
+
const statusBar = document.getElementById('statusBar');
|
| 282 |
+
const bonesContainer = document.getElementById('bonesContainer');
|
| 283 |
+
const endEffectorSel = document.getElementById('end_effector');
|
| 284 |
+
const handShapeSel = document.getElementById('hand_shape');
|
| 285 |
+
const handPosSel = document.getElementById('hand_position');
|
| 286 |
+
const handFieldset = document.getElementById('handFieldset');
|
| 287 |
+
const modelBadge = document.getElementById('modelBadge');
|
| 288 |
+
const subpointsInput = document.getElementById('subpoints');
|
| 289 |
+
const numStepsInput = document.getElementById('num_steps');
|
| 290 |
+
// Collision inputs
|
| 291 |
+
const collisionEnabledEl = document.getElementById('collision_enabled');
|
| 292 |
+
const collisionWeightEl = document.getElementById('collision_weight');
|
| 293 |
+
const collCx = document.getElementById('collision_cx');
|
| 294 |
+
const collCy = document.getElementById('collision_cy');
|
| 295 |
+
const collCz = document.getElementById('collision_cz');
|
| 296 |
+
const collCxSlider = document.getElementById('collision_cx_slider');
|
| 297 |
+
const collCySlider = document.getElementById('collision_cy_slider');
|
| 298 |
+
const collCzSlider = document.getElementById('collision_cz_slider');
|
| 299 |
+
const collRadiusEl = document.getElementById('collision_radius');
|
| 300 |
+
const collMinClearEl = document.getElementById('collision_min_clearance');
|
| 301 |
+
const collMinClearSlider = document.getElementById('collision_min_clearance_slider');
|
| 302 |
+
|
| 303 |
+
function val(id){ return document.getElementById(id).value; }
|
| 304 |
+
function num(id){ return parseFloat(val(id)); }
|
| 305 |
+
function bool(id){ return document.getElementById(id).checked; }
|
| 306 |
+
|
| 307 |
+
// ----- Three.js scene -----
|
| 308 |
+
const renderer = new THREE.WebGLRenderer({ antialias:true });
|
| 309 |
+
renderer.setPixelRatio(window.devicePixelRatio);
|
| 310 |
+
renderer.setSize(document.getElementById('viewerPane').clientWidth, document.getElementById('viewerPane').clientHeight);
|
| 311 |
+
renderer.domElement.className = 'viewer-canvas';
|
| 312 |
+
document.getElementById('viewerPane').appendChild(renderer.domElement);
|
| 313 |
+
const scene = new THREE.Scene(); scene.background = new THREE.Color(0x222222);
|
| 314 |
+
const camera = new THREE.PerspectiveCamera(45, renderer.domElement.clientWidth / renderer.domElement.clientHeight, 0.01, 1000);
|
| 315 |
+
camera.position.set(0,1,3);
|
| 316 |
+
const controls = new OrbitControls(camera, renderer.domElement); controls.target.set(0,0.8,0);
|
| 317 |
+
scene.add(new THREE.HemisphereLight(0xffffff,0x444444,1.0));
|
| 318 |
+
const d = new THREE.DirectionalLight(0xffffff,0.8); d.position.set(3,10,10); scene.add(d);
|
| 319 |
+
const ground = new THREE.Mesh(new THREE.CircleGeometry(5,48), new THREE.MeshStandardMaterial({color:0x303030, metalness:0.1, roughness:0.9}));
|
| 320 |
+
ground.rotation.x = -Math.PI/2; ground.receiveShadow = true; scene.add(ground); ground.visible = false;
|
| 321 |
+
const modelGroup = new THREE.Group(); scene.add(modelGroup);
|
| 322 |
+
|
| 323 |
+
// Target sphere
|
| 324 |
+
const targetSphereGeom = new THREE.SphereGeometry(0.01, 24, 24);
|
| 325 |
+
const targetSphereMat = new THREE.MeshStandardMaterial({color:0x00ff55, emissive:0x008833});
|
| 326 |
+
const targetSphere = new THREE.Mesh(targetSphereGeom, targetSphereMat); scene.add(targetSphere);
|
| 327 |
+
// Collision sphere (unit scaled later)
|
| 328 |
+
const collisionSphereGeom = new THREE.SphereGeometry(1, 32, 32);
|
| 329 |
+
const collisionSphereMat = new THREE.MeshStandardMaterial({color:0xff4444, emissive:0x660000, transparent:true, opacity:0.18, wireframe:false});
|
| 330 |
+
const collisionSphere = new THREE.Mesh(collisionSphereGeom, collisionSphereMat); scene.add(collisionSphere); collisionSphere.visible = false;
|
| 331 |
+
|
| 332 |
+
function updateTargetSphere(){
|
| 333 |
+
const xRaw = parseFloat(document.getElementById('target_x').value) || 0;
|
| 334 |
+
const yRaw = parseFloat(document.getElementById('target_y').value) || 0;
|
| 335 |
+
const zRaw = parseFloat(document.getElementById('target_z').value) || 0;
|
| 336 |
+
const sx = modelGroup?.scale?.x ?? 1; const sy = modelGroup?.scale?.y ?? 1; const sz = modelGroup?.scale?.z ?? 1;
|
| 337 |
+
const tx = modelGroup?.position?.x ?? 0; const ty = modelGroup?.position?.y ?? 0; const tz = modelGroup?.position?.z ?? 0;
|
| 338 |
+
targetSphere.position.set(xRaw * sx + tx, yRaw * sy + ty, zRaw * sz + tz);
|
| 339 |
+
}
|
| 340 |
+
function updateCollisionSphere(){
|
| 341 |
+
const cx = parseFloat(collCx.value) || 0; const cy = parseFloat(collCy.value) || 0; const cz = parseFloat(collCz.value) || 0;
|
| 342 |
+
const r = parseFloat(collRadiusEl.value) || 0.1; const mc = parseFloat(collMinClearEl.value) || 0.0;
|
| 343 |
+
const sx = modelGroup?.scale?.x ?? 1; const sy = modelGroup?.scale?.y ?? 1; const sz = modelGroup?.scale?.z ?? 1; const tx = modelGroup?.position?.x ?? 0; const ty = modelGroup?.position?.y ?? 0; const tz = modelGroup?.position?.z ?? 0;
|
| 344 |
+
collisionSphere.position.set(cx * sx + tx, cy * sy + ty, cz * sz + tz);
|
| 345 |
+
const uniform = (sx+sy+sz)/3; const effective = r + mc; // visualize base radius + clearance
|
| 346 |
+
collisionSphere.scale.set(effective*uniform, effective*uniform, effective*uniform);
|
| 347 |
+
collisionSphere.visible = collisionEnabledEl.checked;
|
| 348 |
+
}
|
| 349 |
+
['target_x','target_y','target_z'].forEach(id=>{ document.getElementById(id).addEventListener('input', updateTargetSphere); document.getElementById(id).addEventListener('change', updateTargetSphere); });
|
| 350 |
+
updateTargetSphere(); updateCollisionSphere();
|
| 351 |
+
|
| 352 |
+
window.addEventListener('resize', () => { renderer.setSize(document.getElementById('viewerPane').clientWidth, document.getElementById('viewerPane').clientHeight); camera.aspect = renderer.domElement.clientWidth / renderer.domElement.clientHeight; camera.updateProjectionMatrix(); });
|
| 353 |
+
function resetCamera(){ camera.position.set(0,1,3); controls.target.set(0,0.8,0); controls.update(); }
|
| 354 |
+
|
| 355 |
+
// ----- Config fetch -----
|
| 356 |
+
async function loadConfig(){ const res = await fetch(`/config?model=${currentModel}`); configData = await res.json(); populateUIFromConfig(); log(`Config loaded for ${currentModel}`); }
|
| 357 |
+
|
| 358 |
+
function populateUIFromConfig(){
|
| 359 |
+
endEffectorSel.innerHTML = ""; configData.end_effector_choices.forEach(b=>{ const opt=document.createElement('option'); opt.value=b; opt.textContent=b; if (b===configData.default_end_effector) opt.selected=true; endEffectorSel.appendChild(opt); });
|
| 360 |
+
bonesContainer.innerHTML = ""; configData.selectable_bones.forEach(b=>{ const id=`bone_${b}`; const label=document.createElement('label'); label.innerHTML = `<input type="checkbox" id="${id}" ${configData.default_controlled_bones.includes(b)?'checked':''}> ${b}`; bonesContainer.appendChild(label); setTimeout(()=>{ const cb=document.getElementById(id); if (cb) cb.addEventListener('change', ()=> scheduleSolve()); },0); });
|
| 361 |
+
if (currentModel === 'agent'){ handFieldset.style.display=''; handShapeSel.innerHTML=""; configData.hand_shapes.forEach(s=>{ const o=document.createElement('option'); o.value=s; o.textContent=s; handShapeSel.appendChild(o); }); handPosSel.innerHTML=""; configData.hand_positions.forEach(s=>{ const o=document.createElement('option'); o.value=s; o.textContent=s; handPosSel.appendChild(o); }); } else { handFieldset.style.display='none'; }
|
| 362 |
+
if (configData && typeof configData.max_subpoints !== 'undefined') subpointsInput.max = configData.max_subpoints;
|
| 363 |
+
if (configData && typeof configData.default_num_steps !== 'undefined') numStepsInput.value = configData.default_num_steps;
|
| 364 |
+
if (configData && configData.collision_default_center){ const c=configData.collision_default_center; collCx.value=c[0]; collCy.value=c[1]; collCz.value=c[2]; collCxSlider.value=c[0]; collCySlider.value=c[1]; collCzSlider.value=c[2]; }
|
| 365 |
+
if (configData && typeof configData.collision_default_radius !== 'undefined'){ collRadiusEl.value = configData.collision_default_radius; }
|
| 366 |
+
if (configData && typeof configData.collision_default_min_clearance !== 'undefined'){ collMinClearEl.value = configData.collision_default_min_clearance; collMinClearSlider.value = configData.collision_default_min_clearance; }
|
| 367 |
+
updateTargetSphere(); updateCollisionSphere();
|
| 368 |
+
}
|
| 369 |
+
|
| 370 |
+
subpointsInput.addEventListener('change', ()=>{ const v=parseInt(subpointsInput.value,10); if (v<=1){ document.getElementById('derivative_enabled').checked=false; } scheduleSolve(); });
|
| 371 |
+
|
| 372 |
+
function applyModelSpecificGLTFPolicy(){ const urlInput=document.getElementById('gltf_url'); const showGltfChk=document.getElementById('show_gltf'); if (currentModel==='pepper'){ showGltfChk.disabled=true; if (gltfRoot) gltfRoot.visible=false; } else { if (!urlInput.value) urlInput.value="/files/smplx.glb"; showGltfChk.disabled=false; } }
|
| 373 |
+
|
| 374 |
+
const gltfLoader = new GLTFLoader();
|
| 375 |
+
function loadGLTF(url){ if (!url){ log('No GLTF URL (possibly Pepper) - skipping load.'); return; } const u=url.startsWith('http')?url:url; statusBar.textContent=`Loading GLTF: ${u}`; log(`Loading GLTF ${u}`); gltfLoader.load(u, gltf=>{ if (gltfRoot) modelGroup.remove(gltfRoot); gltfRoot=gltf.scene; gltfPrimaryMaterial=null; gltfPrimaryMesh=null; gltfPrimaryMaterialCaptured=false; gltfRoot.traverse(o=>{ if (o.isMesh && o.geometry?.attributes?.position){ if (!gltfPrimaryMesh || o.geometry.attributes.position.count > gltfPrimaryMesh.geometry.attributes.position.count){ gltfPrimaryMesh=o; } } }); if (gltfPrimaryMesh){ if (Array.isArray(gltfPrimaryMesh.material)){ const mm=gltfPrimaryMesh.material.find(m=>m.map) || gltfPrimaryMesh.material[0]; gltfPrimaryMaterial=mm.clone(); } else { gltfPrimaryMaterial=gltfPrimaryMesh.material.clone(); } gltfPrimaryMaterialCaptured=true; log(`Captured GLTF primary mesh (verts=${gltfPrimaryMesh.geometry.attributes.position.count})`); } else { log('No primary mesh found in GLTF.'); }
|
| 376 |
+
modelGroup.add(gltfRoot); gltfRoot.visible=document.getElementById('show_gltf').checked; if (animationFrames.length){ ensureActiveMeshBound(animationFrames[0]); applyFrame(animationFrames[Math.min(frameIndex, animationFrames.length-1)]); } fitCamera(gltfRoot); statusBar.textContent='GLTF loaded.'; }, undefined, err=>{ statusBar.textContent='GLTF error: '+err.message; log('GLTF error: '+err.message); }); }
|
| 377 |
+
|
| 378 |
+
document.getElementById('solve_btn').onclick = ()=> triggerSolve(true);
|
| 379 |
+
function collectBones(){ const bones=[]; if (!configData) return bones; configData.selectable_bones.forEach(b=>{ const cb=document.getElementById(`bone_${b}`); if (cb && cb.checked) bones.push(b); }); return bones; }
|
| 380 |
+
|
| 381 |
+
async function doSolve(abortSignal){
|
| 382 |
+
statusBar.textContent='Solving...'; log('Solve request started');
|
| 383 |
+
const subpointsVal=parseInt(val('subpoints'),10);
|
| 384 |
+
const payload={
|
| 385 |
+
model: currentModel,
|
| 386 |
+
target: [num('target_x'), num('target_y'), num('target_z')],
|
| 387 |
+
subpoints: subpointsVal,
|
| 388 |
+
num_steps: parseInt(numStepsInput.value,10) || 100,
|
| 389 |
+
distance_enabled: bool('distance_enabled'),
|
| 390 |
+
distance_weight: num('distance_weight'),
|
| 391 |
+
collision_enabled: collisionEnabledEl.checked,
|
| 392 |
+
collision_weight: parseFloat(collisionWeightEl.value)||1.0,
|
| 393 |
+
collision_center: [parseFloat(collCx.value)||0, parseFloat(collCy.value)||0, parseFloat(collCz.value)||0],
|
| 394 |
+
collision_radius: parseFloat(collRadiusEl.value)||0.1,
|
| 395 |
+
bone_zero_enabled: bool('bone_zero_enabled'),
|
| 396 |
+
bone_zero_weight: num('bone_zero_weight'),
|
| 397 |
+
derivative_enabled: bool('derivative_enabled'),
|
| 398 |
+
derivative_weight: num('derivative_weight'),
|
| 399 |
+
controlled_bones: collectBones(),
|
| 400 |
+
end_effector: endEffectorSel.value,
|
| 401 |
+
hand_shape: currentModel==='agent'? handShapeSel.value : 'None',
|
| 402 |
+
hand_position: currentModel==='agent'? handPosSel.value : 'None',
|
| 403 |
+
frames_mode: subpointsVal > 1 ? 'auto' : 'last',
|
| 404 |
+
collision_min_clearance: parseFloat(collMinClearEl.value)||0.0,
|
| 405 |
+
};
|
| 406 |
+
try { const t0=performance.now(); const res=await fetch('/solve',{method:'POST', headers:{'Content-Type':'application/json'}, body:JSON.stringify(payload), signal:abortSignal}); if (!res.ok) throw new Error(res.status+' '+res.statusText); const json=await res.json(); if (json.status!=='ok') throw new Error(json.message || 'Solve failed'); const sid=json.result.solve_id||0; if (payload.model==='agent'){ if (sid <= lastSolveIdAgent){ log(`Stale agent solve ignored (sid=${sid} <= ${lastSolveIdAgent})`); return; } lastSolveIdAgent=sid; } else { if (sid <= lastSolveIdPepper){ log(`Stale pepper solve ignored (sid=${sid} <= ${lastSolveIdPepper})`); return; } lastSolveIdPepper=sid; }
|
| 407 |
+
const server=json.result.solve_time; const total=(performance.now()-t0)/1000; statusBar.textContent=`Solved: server=${server.toFixed(2)}s total=${total.toFixed(2)}s it=${json.result.iterations} obj=${json.result.objective.toFixed(6)} frames=${json.result.frames}`; log(`Solve completed (frames received=${json.result.frames})`); if (json.result.frames_data && json.result.frames_data.length){ animationFrames=json.result.frames_data; ensureActiveMeshBound(animationFrames[0]); controlFrames=[]; splineMode=false; playbackEnabled=false; if (animationFrames.length>1 && subpointsVal>1){ setupSplinePlayback(animationFrames); applyFrame(animationFrames[0]); } else { frameIndex=animationFrames.length-1; applyFrame(animationFrames[frameIndex]); } scheduleGroundAlign(); }
|
| 408 |
+
updateTargetSphere(); updateCollisionSphere(); showToast(`Solve OK • it=${json.result.iterations} • t=${json.result.solve_time.toFixed(2)}s • err=${json.result.objective.toExponential(2)}`,'success',4000); }
|
| 409 |
+
catch(e){ if (e.name==='AbortError'){ log('Solve aborted (superseded)'); return; } statusBar.textContent='Solve error: '+e.message; log('Solve error: '+e.message); showToast(`Solve ERROR: ${e.message}`,'error',6000); }
|
| 410 |
+
}
|
| 411 |
+
|
| 412 |
+
const toastContainer=document.getElementById('toastContainer');
|
| 413 |
+
function showToast(message, type='success', ttl=4000){ const el=document.createElement('div'); el.className=`toast ${type}`; const close=document.createElement('span'); close.className='toast-close'; close.textContent='✕'; close.onclick=e=>{ e.stopPropagation(); remove(); }; const content=document.createElement('div'); content.textContent=message; el.appendChild(close); el.appendChild(content); toastContainer.appendChild(el); requestAnimationFrame(()=> el.classList.add('show')); function remove(){ el.classList.remove('show'); setTimeout(()=> el.remove(), 180); } setTimeout(remove, ttl); }
|
| 414 |
+
|
| 415 |
+
const xNum=document.getElementById('target_x'); const yNum=document.getElementById('target_y'); const zNum=document.getElementById('target_z'); const xSlider=document.getElementById('target_x_slider'); const ySlider=document.getElementById('target_y_slider');
|
| 416 |
+
function syncSliderToNum(axis){ if (axis==='x') xSlider.value=xNum.value; else if (axis==='y') ySlider.value=yNum.value; }
|
| 417 |
+
function syncNumToSlider(axis){ if (axis==='x') xNum.value=xSlider.value; else if (axis==='y') yNum.value=ySlider.value; }
|
| 418 |
+
xSlider.addEventListener('input', ()=>{ syncNumToSlider('x'); updateTargetSphere(); }); ySlider.addEventListener('input', ()=>{ syncNumToSlider('y'); updateTargetSphere(); });
|
| 419 |
+
xSlider.addEventListener('change', ()=>{ syncNumToSlider('x'); updateTargetSphere(); scheduleSolve(); }); ySlider.addEventListener('change', ()=>{ syncNumToSlider('y'); updateTargetSphere(); scheduleSolve(); });
|
| 420 |
+
xNum.addEventListener('change', ()=>{ syncSliderToNum('x'); updateTargetSphere(); scheduleSolve(); }); yNum.addEventListener('change', ()=>{ syncSliderToNum('y'); updateTargetSphere(); scheduleSolve(); }); zNum.addEventListener('change', ()=>{ updateTargetSphere(); scheduleSolve(); });
|
| 421 |
+
|
| 422 |
+
// Collision sliders
|
| 423 |
+
function syncCollSliderToNum(axis){ if (axis==='x') collCxSlider.value=collCx.value; else if (axis==='y') collCySlider.value=collCy.value; else if (axis==='z') collCzSlider.value=collCz.value; else if (axis==='mc') collMinClearSlider.value=collMinClearEl.value; }
|
| 424 |
+
function syncCollNumToSlider(axis){ if (axis==='x') collCx.value=collCxSlider.value; else if (axis==='y') collCy.value=collCySlider.value; else if (axis==='z') collCz.value=collCzSlider.value; else if (axis==='mc') collMinClearEl.value=collMinClearSlider.value; }
|
| 425 |
+
['x','y','z'].forEach(a=>{ const slider = a==='x'?collCxSlider: a==='y'?collCySlider:collCzSlider; slider.addEventListener('input', ()=>{ syncCollNumToSlider(a); updateCollisionSphere(); }); slider.addEventListener('change', ()=>{ syncCollNumToSlider(a); updateCollisionSphere(); scheduleSolve(); }); });
|
| 426 |
+
[collCx, collCy, collCz].forEach((el,i)=> el.addEventListener('change', ()=>{ syncCollSliderToNum(i===0?'x':i===1?'y':'z'); updateCollisionSphere(); scheduleSolve(); }));
|
| 427 |
+
collRadiusEl.addEventListener('change', ()=>{ updateCollisionSphere(); scheduleSolve(); });
|
| 428 |
+
collisionEnabledEl.addEventListener('change', ()=>{ updateCollisionSphere(); scheduleSolve(); });
|
| 429 |
+
collMinClearSlider.addEventListener('input', ()=>{ syncCollNumToSlider('mc'); updateCollisionSphere(); });
|
| 430 |
+
collMinClearSlider.addEventListener('change', ()=>{ syncCollNumToSlider('mc'); updateCollisionSphere(); scheduleSolve(); });
|
| 431 |
+
collMinClearEl.addEventListener('change', ()=>{ syncCollSliderToNum('mc'); updateCollisionSphere(); scheduleSolve(); });
|
| 432 |
+
|
| 433 |
+
const autoSolveSelectors=[
|
| 434 |
+
'#distance_enabled','#distance_weight',
|
| 435 |
+
'#collision_enabled','#collision_weight', '#collision_radius', '#collision_cx', '#collision_cy', '#collision_cz', '#collision_min_clearance',
|
| 436 |
+
'#bone_zero_enabled','#bone_zero_weight',
|
| 437 |
+
'#derivative_enabled','#derivative_weight',
|
| 438 |
+
'#hand_shape','#hand_position',
|
| 439 |
+
'#end_effector','#wireframe','#show_gltf','#show_ikmesh',
|
| 440 |
+
'#play_fps','#num_steps'
|
| 441 |
+
];
|
| 442 |
+
autoSolveSelectors.forEach(sel=>{ const el=document.querySelector(sel); if (el){ const evt=(el.type==='checkbox'||el.tagName==='SELECT')?'change':'input'; el.addEventListener(evt, ()=> scheduleSolve()); }});
|
| 443 |
+
|
| 444 |
+
document.getElementById('wireframe').addEventListener('change', ()=>{ if (ikMesh && ikMesh.material){ ikMesh.material.wireframe=document.getElementById('wireframe').checked; ikMesh.material.needsUpdate=true; } if (gltfPrimaryMesh && gltfPrimaryMesh.material){ if (Array.isArray(gltfPrimaryMesh.material)) gltfPrimaryMesh.material.forEach(m=>{m.wireframe=document.getElementById('wireframe').checked; m.needsUpdate=true;}); else { gltfPrimaryMesh.material.wireframe=document.getElementById('wireframe').checked; gltfPrimaryMesh.material.needsUpdate=true; } } });
|
| 445 |
+
document.getElementById('show_gltf').addEventListener('change', ()=>{ if (gltfRoot) gltfRoot.visible=document.getElementById('show_gltf').checked; });
|
| 446 |
+
document.getElementById('show_ikmesh').addEventListener('change', ()=>{ if (ikMesh) ikMesh.visible=document.getElementById('show_ikmesh').checked; });
|
| 447 |
+
|
| 448 |
+
function ensureActiveMeshBound(firstFrame){ if (!firstFrame) return; const verts=firstFrame.vertices; let bound=false; if (gltfPrimaryMesh && gltfPrimaryMesh.geometry?.attributes?.position && gltfPrimaryMesh.geometry.attributes.position.count === verts.length){ if (fallbackMesh){ modelGroup.remove(fallbackMesh); if (fallbackMesh.geometry) fallbackMesh.geometry.dispose(); if (fallbackMesh.material && !Array.isArray(fallbackMesh.material)) fallbackMesh.material.dispose(); fallbackMesh=null; } ikMesh=gltfPrimaryMesh; usingGLTFGeometry=true; if (gltfPrimaryMaterial) ikMesh.material=gltfPrimaryMaterial; bound=true; log('ensureActiveMeshBound: using GLTF primary mesh'); }
|
| 449 |
+
if (!bound){ if (!fallbackMesh || !fallbackMesh.geometry?.getAttribute('position') || fallbackMesh.geometry.getAttribute('position').count !== verts.length){ if (fallbackMesh){ modelGroup.remove(fallbackMesh); if (fallbackMesh.geometry) fallbackMesh.geometry.dispose(); if (fallbackMesh.material && !Array.isArray(fallbackMesh.material)) fallbackMesh.material.dispose(); }
|
| 450 |
+
const geom=new THREE.BufferGeometry(); const posArr=new Float32Array(verts.length*3); for (let i=0;i<verts.length;i++){ const v=verts[i]; posArr[i*3]=v[0]; posArr[i*3+1]=v[1]; posArr[i*3+2]=v[2]; } geom.setAttribute('position', new THREE.BufferAttribute(posArr,3)); geom.getAttribute('position').setUsage(THREE.DynamicDrawUsage); const faces=firstFrame.faces; const idx=new Uint32Array(faces.length*3); for (let i=0;i<faces.length;i++){ const f=faces[i]; idx[i*3]=f[0]; idx[i*3+1]=f[1]; idx[i*3+2]=f[2]; } geom.setIndex(new THREE.BufferAttribute(idx,1)); geom.computeVertexNormals(); const mat=gltfPrimaryMaterial?gltfPrimaryMaterial.clone(): new THREE.MeshStandardMaterial({color:0x6699ff, metalness:0.2, roughness:0.6}); fallbackMesh=new THREE.Mesh(geom, mat); fallbackMesh.visible=document.getElementById('show_ikmesh').checked; modelGroup.add(fallbackMesh); ikMesh=fallbackMesh; usingGLTFGeometry=false; log('ensureActiveMeshBound: created fallback mesh'); } else { ikMesh=fallbackMesh; usingGLTFGeometry=false; log('ensureActiveMeshBound: reused fallback mesh'); } }
|
| 451 |
+
if (currentModel==='pepper' && ikMesh){ const box=new THREE.Box3().setFromObject(modelGroup); const h=box.max.y - box.min.y; const targetH=1.2; if (h>0 && (h<0.6 || h>2.0)){ const s=targetH / h; modelGroup.scale.set(s,s,s); log(`Pepper scaled: origH=${h.toFixed(3)} scale=${s.toFixed(3)}`); scheduleGroundAlign(true); } }
|
| 452 |
+
if (gltfRoot) gltfRoot.visible=document.getElementById('show_gltf').checked; if (ikMesh) ikMesh.visible=document.getElementById('show_ikmesh').checked; updateTargetSphere(); updateCollisionSphere(); }
|
| 453 |
+
|
| 454 |
+
function applyFrame(frame){ if (!ikMesh || !frame) return; const posAttr=ikMesh.geometry.getAttribute('position'); if (!posAttr || posAttr.count !== frame.vertices.length){ log('applyFrame: vertex count mismatch'); return; } const arr=posAttr.array; const verts=frame.vertices; for (let i=0;i<verts.length;i++){ const v=verts[i]; arr[i*3]=v[0]; arr[i*3+1]=v[1]; arr[i*3+2]=v[2]; } posAttr.needsUpdate=true; if (!groundAligned) scheduleGroundAlign(); }
|
| 455 |
+
function bsplineBasis(t){ const t2=t*t, t3=t2*t; return [(1 - 3*t + 3*t2 - t3)/6,(4 - 6*t2 + 3*t3)/6,(1 + 3*t + 3*t2 - 3*t3)/6,t3/6]; }
|
| 456 |
+
function getControlFrame(i){ if (i<0) return controlFrames[0]; if (i>=controlFrames.length) return controlFrames[controlFrames.length-1]; return controlFrames[i]; }
|
| 457 |
+
function evalSplineVertices(u){ if (!ikMesh || controlFrames.length<2) return; const n=controlFrames.length; const seg=Math.min(Math.floor(u), n-2); const t=u - seg; const [w0,w1,w2,w3]=bsplineBasis(t); const f0=getControlFrame(seg-1); const f1=getControlFrame(seg); const f2=getControlFrame(seg+1); const f3=getControlFrame(seg+2); const posAttr=ikMesh.geometry.getAttribute('position'); if (!posAttr) return; const arr=posAttr.array; const v0=f0.vertices, v1=f1.vertices, v2=f2.vertices, v3=f3.vertices; const count=posAttr.count; for (let i=0;i<count;i++){ const a0=v0[i], a1=v1[i], a2=v2[i], a3=v3[i]; arr[i*3]=w0*a0[0]+w1*a1[0]+w2*a2[0]+w3*a3[0]; arr[i*3+1]=w0*a0[1]+w1*a1[1]+w2*a2[1]+w3*a3[1]; arr[i*3+2]=w0*a0[2]+w1*a1[2]+w2*a2[2]+w3*a3[2]; } posAttr.needsUpdate=true; if (!groundAligned) scheduleGroundAlign(); }
|
| 458 |
+
function setupSplinePlayback(frames){ controlFrames=frames; splineMode=true; splineU=0; const segments=frames.length - 1; splineDuration=Math.min(segments * 0.6, 8.0); playbackEnabled=true; }
|
| 459 |
+
function updateFramePlayback(){ if (!animationFrames.length) return; const idx=Math.min(Math.floor(frameIndex), animationFrames.length - 1); applyFrame(animationFrames[idx]); }
|
| 460 |
+
|
| 461 |
+
document.querySelectorAll('.tab-btn').forEach(btn=>{ btn.onclick=()=>{ if (btn.classList.contains('active')) return; document.querySelectorAll('.tab-btn').forEach(b=>b.classList.remove('active')); btn.classList.add('active'); currentModel=btn.getAttribute('data-model'); modelBadge.textContent=currentModel==='pepper'? 'Pepper Robot':'Agent'; cleanupVisuals(); initialCameraFramed=false; applyModelSpecificGLTFPolicy(); loadConfig().then(()=>{ if (currentModel==='agent'){ const url=document.getElementById('gltf_url').value; if (url) loadGLTF(url); } scheduleSolve(true); updateTargetSphere(); updateCollisionSphere(); }); }; });
|
| 462 |
+
|
| 463 |
+
function animate(now){ requestAnimationFrame(animate); const dt=(now - lastTime)/1000; lastTime=now; if (splineMode && playbackEnabled){ const n=controlFrames.length; if (n>1){ splineU += (dt / splineDuration) * (n - 1); if (splineU >= (n - 1)){ splineU = n - 1; playbackEnabled=false; } evalSplineVertices(splineU); } } else if (animationFrames.length>1 && playbackEnabled){ const fps=parseInt(document.getElementById('play_fps').value,10) || 24; frameIndex += dt * fps; if (frameIndex >= animationFrames.length){ if (allowLoopPlayback){ frameIndex=0; } else { frameIndex=animationFrames.length - 1; playbackEnabled=false; } } updateFramePlayback(); } if (pendingAlign) performGroundAlign(); if (!initialCameraFramed && modelGroup.children.length){ fitCamera(modelGroup); initialCameraFramed=true; } renderer.render(scene, camera); }
|
| 464 |
+
requestAnimationFrame(animate);
|
| 465 |
+
|
| 466 |
+
document.getElementById('reset_cam').addEventListener('click', ()=>{ fitCamera(modelGroup); });
|
| 467 |
+
|
| 468 |
+
applyModelSpecificGLTFPolicy();
|
| 469 |
+
loadConfig().then(()=>{ const url=document.getElementById('gltf_url').value; if (url) loadGLTF(url); scheduleGroundAlign(true); scheduleSolve(true); updateTargetSphere(); updateCollisionSphere(); });
|
| 470 |
+
})();
|
| 471 |
+
</script>
|
| 472 |
+
</body>
|
| 473 |
+
</html>
|