Showing preview only (1,057K chars total). Download the full file or copy to clipboard to get everything.
Repository: facebookresearch/ScaDiver
Branch: main
Commit: 96001537f9ab
Files: 43
Total size: 1.0 MB
Directory structure:
gitextract_e3i9npyq/
├── .gitignore
├── CHANGELOG.md
├── CODE_OF_CONDUCT.md
├── CONTRIBUTING.md
├── LICENSE
├── README.md
├── amass_char_info.py
├── bullet/
│ ├── __init__.py
│ ├── bullet_client.py
│ ├── bullet_render.py
│ └── bullet_utils.py
├── data/
│ ├── character/
│ │ └── amass.urdf
│ ├── motion/
│ │ ├── amass_hierarchy.bvh
│ │ ├── cmu/
│ │ │ ├── expert0/
│ │ │ │ └── test.bvh
│ │ │ ├── expert1/
│ │ │ │ └── test.bvh
│ │ │ ├── expert2/
│ │ │ │ └── test.bvh
│ │ │ ├── expert3/
│ │ │ │ └── test.bvh
│ │ │ ├── expert4/
│ │ │ │ └── test.bvh
│ │ │ ├── expert5/
│ │ │ │ └── test.bvh
│ │ │ ├── expert6/
│ │ │ │ └── test.bvh
│ │ │ ├── expert7/
│ │ │ │ └── test.bvh
│ │ │ └── moe/
│ │ │ └── test.bvh
│ │ └── test.bvh
│ └── spec/
│ ├── spec_env_humanoid_imitation_expert0.yaml
│ ├── spec_env_humanoid_imitation_expert1.yaml
│ ├── spec_env_humanoid_imitation_expert2.yaml
│ ├── spec_env_humanoid_imitation_expert3.yaml
│ ├── spec_env_humanoid_imitation_expert4.yaml
│ ├── spec_env_humanoid_imitation_expert5.yaml
│ ├── spec_env_humanoid_imitation_expert6.yaml
│ ├── spec_env_humanoid_imitation_expert7.yaml
│ ├── spec_env_humanoid_imitation_moe.yaml
│ └── test_env_humanoid_imitation.yaml
├── env_humanoid_base.py
├── env_humanoid_imitation.py
├── env_humanoid_tracking.py
├── env_renderer.py
├── render_module.py
├── rllib_driver.py
├── rllib_env_imitation.py
├── rllib_model_custom_torch.py
├── sim_agent.py
└── sim_obstacle.py
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
# Byte-compiled / optimized / DLL files
__pycache__/
*.py[cod]
*$py.class
# C extensions
*.so
# Distribution / packaging
.Python
env/
build/
develop-eggs/
dist/
downloads/
eggs/
.eggs/
lib/
lib64/
parts/
sdist/
var/
*.egg-info/
.installed.cfg
*.egg
# PyInstaller
# Usually these files are written by a python script from a template
# before PyInstaller builds the exe, so as to inject date/other infos into it.
*.manifest
*.spec
# Installer logs
pip-log.txt
pip-delete-this-directory.txt
# Unit test / coverage reports
htmlcov/
.tox/
.coverage
.coverage.*
.cache
nosetests.xml
coverage.xml
*,cover
.hypothesis/
# Translations
*.mo
*.pot
# Django stuff:
*.log
# Sphinx documentation
docs/_build/
# PyBuilder
target/
#Ipython Notebook
.ipynb_checkpoints
venv/
data/learning
data/temp
data/screenshot
================================================
FILE: CHANGELOG.md
================================================
Initial commit
================================================
FILE: CODE_OF_CONDUCT.md
================================================
# Open Source Code of Conduct
## Our Pledge
In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to make participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, sex characteristics, gender identity and expression, level of experience, education, socio-economic status, nationality, personal appearance, race, religion, or sexual identity and orientation.
## Our Standards
Examples of behavior that contributes to creating a positive environment include:
Using welcoming and inclusive language
Being respectful of differing viewpoints and experiences
Gracefully accepting constructive criticism
Focusing on what is best for the community
Showing empathy towards other community members
Examples of unacceptable behavior by participants include:
The use of sexualized language or imagery and unwelcome sexual attention or advances
Trolling, insulting/derogatory comments, and personal or political attacks
Public or private harassment
Publishing others’ private information, such as a physical or electronic address, without explicit permission
Other conduct which could reasonably be considered inappropriate in a professional setting
## Our Responsibilities
Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior.
Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful.
## Scope
This Code of Conduct applies within all project spaces, and it also applies when an individual is representing the project or its community in public spaces. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers.
## Enforcement
Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at opensource-conduct@fb.com. All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately.
Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project’s leadership.
## Attribution
This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4,
available at https://www.contributor-covenant.org/version/1/4/code-of-conduct.html
[homepage]: https://www.contributor-covenant.org
================================================
FILE: CONTRIBUTING.md
================================================
# Contributing to ScaDiver
We want to make contributing to this project as easy and transparent as
possible.
## Pull Requests
We actively welcome your pull requests.
1. Fork the repo and create your branch from `master`.
2. If you've added code that should be tested, add tests.
3. If you've changed APIs, update the documentation.
4. Ensure the test suite passes.
5. Make sure your code lints.
6. If you haven't already, complete the Contributor License Agreement ("CLA").
## Contributor License Agreement ("CLA")
In order to accept your pull request, we need you to submit a CLA. You only need
to do this once to work on any of Facebook's open source projects.
Complete your CLA here: <https://code.facebook.com/cla>
## Issues
We use GitHub issues to track public bugs. Please ensure your description is
clear and has sufficient instructions to be able to reproduce the issue.
Facebook has a [bounty program](https://www.facebook.com/whitehat/) for the safe
disclosure of security bugs. In those cases, please go through the process
outlined on that page and do not file a public issue.
## Coding Style
* 2 spaces for indentation rather than tabs
* 80 character line length
## License
By contributing to ScaDiver, you agree that your contributions will be licensed
under the LICENSE file in the root directory of this source tree.
================================================
FILE: LICENSE
================================================
BSD License
For ScaDiver software
Copyright (c) Facebook, Inc. and its affiliates. All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the name Facebook nor the names of its contributors may be used to
endorse or promote products derived from this software without specific
prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
================================================
FILE: README.md
================================================
# ScaDiver
## Introduction
[](https://www.youtube.com/watch?v=QnIwwAKX5H4&t)
This repository provides executable codes for the paper *A Scalable Approach to Control Diverse Behaviors for Physically Simulated Characters*, which was published in SIGGRAPH 2020. Click [here](https://research.fb.com/publications/a-scalable-approach-to-control-diverse-behaviors-for-physically-simulated-characters/) to see the paper. The name of the project originates from the two keywords in the name of the paper, which are **SCA**lable and **DIVER**se.
Please note that we are not able to guarantee that the codes will work if it is run with settings that we did not intend when we developed for the project. We would appreciate it if users could report the problems when they find it.
## Citation
```
@article{
ScaDiver,
author = {Won, Jungdam and Gopinath, Deepak and Hodgins, Jessica},
title = {A Scalable Approach to Control Diverse Behaviors for Physically Simulated Characters},
year = {2020},
issue_date = {July 2020},
volume = {39},
number = {4},
url = {https://doi.org/10.1145/3386569.3392381},
journal = {ACM Trans. Graph.},
articleno = {33},
}
```
## Getting Started
### Installation
Although we only confirmed that the codes work correctly in Ubuntu (18.04) environment, probably it will work in other environments without much troubles if it is installed in a fresh Python virtual environment, which we recommend users to use to prevent from mixing different pakage versions.
#### ScaDiver
```
git clone https://github.com/fairinternal/ScaDiver
```
#### fairmotion
[fairmotion](https://github.com/fairinternal/fairmotion) provides functionalities to process motion capture data and, to compute kinematics, to visualize simulated characters and environments.
```
pip install fairmotion
```
#### others
We use [PyBullet](https://pybullet.org/wordpress/) for physics simulation and [rllib](https://docs.ray.io/en/latest/rllib.html) for reinforcement learning.
```
pip install pybullet==2.7.3 ray[rllib]==0.8.7 pandas requests
```
### Examples
#### Test Tracking Environment
In this example, a humanoid character will be loaded into space where only the ground plane exists, and it will be simulated without any control. Please press **a** to simulate and press **r** to reset.
```
python env_humanoid_tracking.py
```
#### Test Imitation Environment
In this example, a humanoid character will be loaded into space where only the ground plane exists, and its initial states will be set by some motion capture data specified in the specification file (test_env_humanoid_imiation.yaml). Please note that the character will fall immediately because the current controller is the one not trained at all.
```
python rllib_driver.py --mode load --spec data/spec/test_env_humanoid_imitation.yaml --project_dir ./
```
#### Learning Experts and Mixture of Experts Controllers
To learn expert controllers for a set of heterogeneous motion capture data, we first need to cluster the data according to some motion features. For this, please refer to an example in [fairmotion](https://github.com/fairinternal/fairmotion) about *motion clustering*. After clustering the data, each expert controller can be learned by using only data involved in each cluster.
```
python rllib_driver.py --mode train --spec data/spec/spec_env_humanoid_imitation_expert0.yaml --project_dir ./ --local_dir ./data/learning/experts/
python rllib_driver.py --mode train --spec data/spec/spec_env_humanoid_imitation_expert1.yaml --project_dir ./ --local_dir ./data/learning/experts/
...
python rllib_driver.py --mode train --spec data/spec/spec_env_humanoid_imitation_expert7.yaml --project_dir ./ --local_dir ./data/learning/experts/
```
After expert controllers are learned, they can be combined as a single *mixture-of-experts* controller. In our framework, this can be simply achieved by setting the type of policy model as *moe* as below.
```
python rllib_driver.py --mode train --spec data/spec/spec_env_humanoid_imitation_moe.yaml --project_dir ./ --local_dir ./data/learning/moe/
```
When the training process is performed, it will automatically create logs by using Tensorboard in the *local_dir/project_name*. The status can be checked by the script below.
```
tensorboard --logdir="directory_where_tensorboard_log_exists"
```
According to the iteration number specified in the specification file, it will automatically save intermediate results in the *local_dir/project_name/checkpoint/*. Testing the controllers can be done as below.
```
python rllib_driver.py --mode load --spec "some_specification_file" --project_dir ./ --checkpoint "some_saved_checkpoint_file"
```
### Specification File
Every experiment requires a unique specification file (yaml) that includes all the settings about individual experiments. Most of the elements are easy to understand by its name and it is based on **rllib**'s configuration file. We will explain only our environment-specific settings below, please refer to the documentation of **rllib** for other settings.
#### Reward
Because the optimality of learned policy is defined by the definition of reward function in reinforcement learning, changing the function is the only way for users to design the policy so that it has desirable properties/behaviors. As a result, testing many reward functions by combining various terms with different combinations is a critical process in many researches including ours. We implemented a flexible way to test various functions by simply modifying a specification file.
Our reward function is defined in a tree-like manner, where each node could be a *operation* among child nodes or a *leaf* that defines a term. For example, the function below is a multiplicative reward function composed of the five terms (pose_pos, pose_vel, ee, root, and com), where each term has its own kernel function. Currently, we only support *gaussian* and *none* kernel functions. By simply changing the operation of the root node from *mul* into *add*, we can test an additive reward function. If we want to change weight values for the terms, we can simply change *weight* in the leaf nodes.
We can also define multiple reward functions in the same specification files (please note that their names should be unique), then choose one of them according to experiments by setting the name which we want to test in *fn_map*.
```
reward:
fn_def:
default:
name: total
op: mul
child_nodes:
- name: pose_pos
op: leaf
weight: 1.0
kernel:
type: gaussian
scale: 40.0
- name: pose_vel
op: leaf
weight: 1.0
kernel:
type: gaussian
scale: 1.0
- name: ee
op: leaf
weight: 1.0
kernel:
type: gaussian
scale: 5.0
- name: root
op: leaf
weight: 1.0
kernel:
type: gaussian
scale: 2.5
- name: com
op: leaf
weight: 1.0
kernel:
type: gaussian
scale: 2.5
fn_map:
- default
```
#### Early Termination
We can use various early termination strategies. For example, we can terminate the current episode when the character falls down, or the average reward for 1s is below a specific threshold as used in our paper.
```
early_term:
choices: # 'sim_div', 'sim_window', task_end', 'falldown', 'low_reward'
- task_end
- low_reward
low_reward_thres: 0.1
eoe_margin: 0.5
```
#### Characters
The character fields include character-specific information.
```
character:
name:
- humanoid
char_info_module:
- amass_char_info.py
sim_char_file:
- data/character/amass.urdf
ref_motion_scale:
- 1.0
base_motion_file:
- data/motion/amass_hierarchy.bvh
ref_motion_db:
-
data:
file:
- data/motion/test.bvh
actuation:
- spd
self_collision:
- true
environment_file: []
```
#### Others
If true, the environment will be fully created when *reset* is called. This is useful when the creation of the environment is expensive. Please search with the keyword *Expensive Environments* [here](https://docs.ray.io/en/latest/rllib-env.html#:~:text=Expensive%20Environments,-Some%20environments%20may&text=RLlib%20will%20create%20num_workers%20%2B%201,until%20reset()%20is%20called.) for more details.
```
lazy_creation: false
```
When the codes run, we assume that the current working directory (cwd) is the root directory where the project is originally saved. However, there exist some cases when the cwd could be changed by other external libraries such as *rllib*, so specifying *project_dir* is necessary to keep the root directory of the project.
```
project_dir: /home/jungdam/Research/opensource/ScaDiver/
```
Time steps for physics simulation
```
fps_sim: 480
```
Time steps for control policies
```
fps_con: 30
```
If true, small noise will be added to th the initial state of the character
```
add_noise: false
```
If true, some additional information will be printed. Please use this only for testing environments.
```
verbose: false
```
This defines which information will be added to the state of the character. 'body' will include the physical state of the simulated character such as joint angles and joint angular velocities, 'task' will include the difference between the simulated character and the currently playing reference motion.
```
state:
choices: ['body', 'task'] # 'body', 'imitation', 'interaction', 'task'
```
This includes information on the action space for our environment. Basically, the action space is a target posture that includes a set of target joint angles except for the root joint. 'range_min/range_max' defines the range of joint angles in radian for which we will use, and 'range_min_pol/range_max_pol' defines the range of output values of the policy (controller). In other words, there exists a linear mapping from (range_min_pol, range_max_pol) to (range_min, range_max). For example in the setting below, the full range of motion of our simulated character is between -3.0 radian and 3.0 radians from its base posture (t-pose), and if the policy outputs 3.0 for a specific joint, the environment will interpret the value as 3.0 radians. This feature is especially useful when we want to restrict the range of motion of the simulated character (range_min/range_max will be useful), or the policy has special output layers such as *tanh* (range_min_pol/range_max_pol will be useful).
```
action:
type: "absolute" # 'absolute', 'relative'
range_min: -3.0
range_max: 3.0
range_min_pol: -3.0
range_max_pol: 3.0
```
## Using Clusters
Because our framework is based on *rllib*, it can run not only on a single machine with multiple cores but also on clusters such as AWS, Azure, or customized one managed by Slurm. Please refer to [this](https://docs.ray.io/en/latest/cluster/index.html) for more detail.
## Pretrained Model
To be updated.
## License
ScaDiver is released under the [BSD-3-Clause License](https://github.com/fairinternal/ScaDiver/blob/master/LICENSE).
================================================
FILE: amass_char_info.py
================================================
# Copyright (c) Facebook, Inc. and its affiliates.
import collections
import numpy as np
'''
The up direction of the character w.r.t. its root joint.
The up direction in the world frame can be computed by dot(R_root, v_up),
where R_root is the orientation of the root.
'''
v_up = np.array([0.0, 1.0, 0.0])
'''
The facing direction of the character w.r.t. its root joint.
The facing direction in the world frame can be computed by dot(R_root, v_face),
where R_root is the orientation of the root.
'''
v_face = np.array([0.0, 0.0, 1.0])
'''
The up direction of the world frame, when the character holds its defalult posture (e.g. t-pose).
This information is useful/necessary when comparing a relationship between the character and its environment.
'''
v_up_env = np.array([0.0, 0.0, 1.0])
'''
Definition of Link/Joint (In our character definition, one joint can only have one link)
'''
root = -1
lhip = 0
lknee = 1
lankle = 2
rhip = 3
rknee = 4
rankle = 5
lowerback = 6
upperback = 7
chest = 8
lowerneck = 9
upperneck = 10
lclavicle = 11
lshoulder = 12
lelbow = 13
lwrist = 14
rclavicle = 15
rshoulder = 16
relbow = 17
rwrist = 18
'''
Definition of the root (base) joint
'''
ROOT = root
'''
Definition of end effectors
'''
end_effector_indices = [
lwrist, rwrist, lankle, rankle,
]
'''
Mapping from joint indicies to names
'''
joint_name = collections.OrderedDict()
joint_name[root] = "root"
joint_name[lhip] = "lhip"
joint_name[lknee] = "lknee"
joint_name[lankle] = "lankle"
joint_name[rhip] = "rhip"
joint_name[rknee] = "rknee"
joint_name[rankle] = "rankle"
joint_name[lowerback] = "lowerback"
joint_name[upperback] = "upperback"
joint_name[chest] = "chest"
joint_name[lowerneck] = "lowerneck"
joint_name[upperneck] = "upperneck"
joint_name[lclavicle] = "lclavicle"
joint_name[lshoulder] = "lshoulder"
joint_name[lelbow] = "lelbow"
joint_name[lwrist] = "lwrist"
joint_name[rclavicle] = "rclavicle"
joint_name[rshoulder] = "rshoulder"
joint_name[relbow] = "relbow"
joint_name[rwrist] = "rwrist"
'''
Mapping from joint names to indicies
'''
joint_idx = collections.OrderedDict()
joint_idx["root"] = root
joint_idx["lhip"] = lhip
joint_idx["lknee"] = lknee
joint_idx["lankle"] = lankle
joint_idx["rhip"] = rhip
joint_idx["rknee"] = rknee
joint_idx["rankle"] = rankle
joint_idx["lowerback"] = lowerback
joint_idx["upperback"] = upperback
joint_idx["chest"] = chest
joint_idx["lowerneck"] = lowerneck
joint_idx["upperneck"] = upperneck
joint_idx["lclavicle"] = lclavicle
joint_idx["lshoulder"] = lshoulder
joint_idx["lelbow"] = lelbow
joint_idx["lwrist"] = lwrist
joint_idx["rclavicle"] = rclavicle
joint_idx["rshoulder"] = rshoulder
joint_idx["relbow"] = relbow
joint_idx["rwrist"] = rwrist
'''
Mapping from character's joint indicies to bvh's joint names.
Some entry could have no mapping (by assigning None).
'''
bvh_map = collections.OrderedDict()
bvh_map[root] = "root"
bvh_map[lhip] = "lhip"
bvh_map[lknee] = "lknee"
bvh_map[lankle] = "lankle"
bvh_map[rhip] = "rhip"
bvh_map[rknee] = "rknee"
bvh_map[rankle] = "rankle"
bvh_map[lowerback] = "lowerback"
bvh_map[upperback] = "upperback"
bvh_map[chest] = "chest"
bvh_map[lowerneck] = "lowerneck"
bvh_map[upperneck] = "upperneck"
bvh_map[lclavicle] = "lclavicle"
bvh_map[lshoulder] = "lshoulder"
bvh_map[lelbow] = "lelbow"
bvh_map[lwrist] = "lwrist"
bvh_map[rclavicle] = "rclavicle"
bvh_map[rshoulder] = "rshoulder"
bvh_map[relbow] = "relbow"
bvh_map[rwrist] = "rwrist"
'''
Mapping from bvh's joint names to character's joint indicies.
Some entry could have no mapping (by assigning None).
'''
bvh_map_inv = collections.OrderedDict()
bvh_map_inv["root"] = root
bvh_map_inv["lhip"] = lhip
bvh_map_inv["lknee"] = lknee
bvh_map_inv["lankle"] = lankle
bvh_map_inv["ltoe"] = None
bvh_map_inv["rhip"] = rhip
bvh_map_inv["rknee"] = rknee
bvh_map_inv["rankle"] = rankle
bvh_map_inv["rtoe"] = None
bvh_map_inv["lowerback"] = lowerback
bvh_map_inv["upperback"] = upperback
bvh_map_inv["chest"] = chest
bvh_map_inv["lowerneck"] = lowerneck
bvh_map_inv["upperneck"] = upperneck
bvh_map_inv["lclavicle"] = lclavicle
bvh_map_inv["lshoulder"] = lshoulder
bvh_map_inv["lelbow"] = lelbow
bvh_map_inv["lwrist"] = lwrist
bvh_map_inv["rclavicle"] = rclavicle
bvh_map_inv["rshoulder"] = rshoulder
bvh_map_inv["relbow"] = relbow
bvh_map_inv["rwrist"] = rwrist
'''
Definition of PD gains (tuned for Stable PD Controller)
'''
kp = {
root : 0,
lhip : 500,
lknee : 400,
lankle : 300,
rhip : 500,
rknee : 400,
rankle : 300,
lowerback : 500,
upperback : 500,
chest : 500,
lowerneck : 200,
upperneck : 200,
lclavicle : 400,
lshoulder : 400,
lelbow : 300,
lwrist : 0,
rclavicle : 400,
rshoulder : 400,
relbow : 300,
rwrist : 0,
}
kd = {}
for k, v in kp.items():
kd[k] = 0.1 * v
kd[root] = 0
'''
Definition of PD gains (tuned for Contrained PD Controller).
"cpd_ratio * kp" and "cpd_ratio * kd" will be used respectively.
'''
cpd_ratio = 0.0002
max_force = {
root : 0,
lhip : 300,
lknee : 200,
lankle : 100,
rhip : 300,
rknee : 200,
rankle : 100,
lowerback : 300,
upperback : 300,
chest : 300,
lowerneck : 100,
upperneck : 100,
lclavicle : 200,
lshoulder : 200,
lelbow : 150,
lwrist : 0,
rclavicle : 200,
rshoulder : 200,
relbow : 150,
rwrist : 0 ,
}
'''
Maximum forces that character can generate when PD controller is used.
'''
contact_allow_map = {
root : False,
lhip : False,
lknee : False,
lankle : False,
rhip : False,
rknee : False,
rankle : False,
lowerback : False,
upperback : False,
chest : False,
lowerneck : False,
upperneck : False,
lclavicle : False,
lshoulder : False,
lelbow : False,
lwrist : False,
rclavicle : False,
rshoulder : False,
relbow : False,
rwrist : False,
}
joint_weight = {
root : 1.0,
lhip : 0.5,
lknee : 0.3,
lankle : 0.2,
rhip : 0.5,
rknee : 0.3,
rankle : 0.2,
lowerback : 0.4,
upperback : 0.4,
chest : 0.3,
lowerneck : 0.3,
upperneck : 0.3,
lclavicle : 0.3,
lshoulder : 0.3,
lelbow : 0.2,
lwrist : 0.0,
rclavicle : 0.3,
rshoulder : 0.3,
relbow : 0.2,
rwrist : 0.0,
}
''' mu, sigma, lower, upper '''
noise_pose = {
root : (0.0, 0.1, -0.5, 0.5),
lhip : (0.0, 0.1, -0.5, 0.5),
lknee : (0.0, 0.1, -0.5, 0.5),
lankle : (0.0, 0.1, -0.5, 0.5),
rhip : (0.0, 0.1, -0.5, 0.5),
rknee : (0.0, 0.1, -0.5, 0.5),
rankle : (0.0, 0.1, -0.5, 0.5),
lowerback : (0.0, 0.1, -0.5, 0.5),
upperback : (0.0, 0.1, -0.5, 0.5),
chest : (0.0, 0.1, -0.5, 0.5),
lowerneck : (0.0, 0.1, -0.5, 0.5),
upperneck : (0.0, 0.1, -0.5, 0.5),
lclavicle : (0.0, 0.1, -0.5, 0.5),
lshoulder : (0.0, 0.1, -0.5, 0.5),
lelbow : (0.0, 0.1, -0.5, 0.5),
lwrist : (0.0, 0.1, -0.5, 0.5),
rclavicle : (0.0, 0.1, -0.5, 0.5),
rshoulder : (0.0, 0.1, -0.5, 0.5),
relbow : (0.0, 0.1, -0.5, 0.5),
rwrist : (0.0, 0.1, -0.5, 0.5),
}
''' mu, sigma, lower, upper '''
noise_vel = {
root : (0.0, 0.1, -0.5, 0.5),
lhip : (0.0, 0.1, -0.5, 0.5),
lknee : (0.0, 0.1, -0.5, 0.5),
lankle : (0.0, 0.1, -0.5, 0.5),
rhip : (0.0, 0.1, -0.5, 0.5),
rknee : (0.0, 0.1, -0.5, 0.5),
rankle : (0.0, 0.1, -0.5, 0.5),
lowerback : (0.0, 0.1, -0.5, 0.5),
upperback : (0.0, 0.1, -0.5, 0.5),
chest : (0.0, 0.1, -0.5, 0.5),
lowerneck : (0.0, 0.1, -0.5, 0.5),
upperneck : (0.0, 0.1, -0.5, 0.5),
lclavicle : (0.0, 0.1, -0.5, 0.5),
lshoulder : (0.0, 0.1, -0.5, 0.5),
lelbow : (0.0, 0.1, -0.5, 0.5),
lwrist : (0.0, 0.1, -0.5, 0.5),
rclavicle : (0.0, 0.1, -0.5, 0.5),
rshoulder : (0.0, 0.1, -0.5, 0.5),
relbow : (0.0, 0.1, -0.5, 0.5),
rwrist : (0.0, 0.1, -0.5, 0.5),
}
collison_ignore_pairs = [
]
friction_lateral = 0.8
friction_spinning = 0.3
restitution = 0.0
sum_joint_weight = 0.0
for key, val in joint_weight.items():
sum_joint_weight += val
for key, val in joint_weight.items():
joint_weight[key] /= sum_joint_weight
================================================
FILE: bullet/__init__.py
================================================
# Copyright (c) Facebook, Inc. and its affiliates.
================================================
FILE: bullet/bullet_client.py
================================================
# Copyright (c) Facebook, Inc. and its affiliates.
'''
This class was slightly edited from the code existing in one of examples in PyBullet.
'''
import functools
import inspect
import pybullet
class BulletClient(object):
"""A wrapper for pybullet to manage different clients."""
def __init__(self, connection_mode=pybullet.DIRECT, options=""):
"""Create a simulation and connect to it."""
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
if (self._client < 0):
self._client = pybullet.connect(connection_mode, options=options)
self._shapes = {}
def __del__(self):
"""Clean up connection if not already done."""
try:
pybullet.disconnect(physicsClientId=self._client)
except pybullet.error:
pass
def __getattr__(self, name):
"""Inject the client id into Bullet functions."""
attribute = getattr(pybullet, name)
if inspect.isbuiltin(attribute):
attribute = functools.partial(attribute, physicsClientId=self._client)
return attribute
================================================
FILE: bullet/bullet_render.py
================================================
# Copyright (c) Facebook, Inc. and its affiliates.
from OpenGL.GL import *
from OpenGL.GLUT import *
from OpenGL.GLU import *
import numpy as np
import pybullet
from fairmotion.viz import gl_render
from fairmotion.ops import conversions
from fairmotion.utils import constants
def glTransform(quaternion):
glMultMatrixd(T.transpose().ravel())
class RenderOptionBody():
def __init__(self):
self.render = True
self.render_edge = True
self.render_face = True
self.color_edge = [0.0, 0.0, 0.0, 1.0]
self.color_face = [0.5, 0.5, 1.0, 0.5]
self.line_width = 1.0
self.scale = 1.0
self.lighting = False
class RenderOptionJoint():
def __init__(self):
self.render = False
self.render_pos = True
self.render_ori = True
self.color_pos = [0, 0, 0, 1.0]
self.color_ori = [[1, 0, 0], [0, 1, 0], [0, 0, 1]]
self.line_width = 1.0
self.scale = 1.0
self.lighting = False
class RenderOption():
def __init__(self):
self.body = RenderOptionBody()
self.joint = RenderOptionJoint()
def render_joint(joint, option):
glPushAttrib(GL_LIGHTING)
if option.lighting:
glEnable(GL_LIGHTING)
else:
glDisable(GL_LIGHTING)
j_type = joint.type()
T0 = joint.child_bodynode.transform()
T1 = joint.transform_from_child_body_node()
T = T0.dot(T1)
R, p = conversions.T2Rp(T)
scale = option.scale
if option.render_pos:
gl_render.render_point(p,
color=option.color_pos,
scale=scale,
radius=0.1)
if option.render_ori:
if j_type == "WeldJoint":
pass
elif j_type == "RevoluteJoint":
axis1 = joint.axis_in_world_frame()
gl_render.render_line(p,
p + scale * axis1,
color=option.color_ori[0])
elif j_type == "UniversalJoint":
axis1 = joint.axis1_in_world_frame()
axis2 = joint.axis2_in_world_frame()
gl_render.render_line(p,
p + scale * axis1,
color=option.color_ori[0])
gl_render.render_line(p,
p + scale * axis2,
color=option.color_ori[1])
elif j_type == "EulerJoint":
gl_render.render_transform(T,
scale=scale,
color_pos=option.color_pos,
color_ori=option.color_ori)
elif j_type == "BallJoint":
gl_render.render_transform(T,
scale=scale,
color_pos=option.color_pos,
color_ori=option.color_ori)
elif j_type == "TranslationalJoint":
gl_render.render_transform(T,
scale=scale,
color_pos=option.color_pos,
color_ori=option.color_ori)
elif j_type == "FreeJoint":
gl_render.render_transform(T,
scale=scale,
color_pos=option.color_pos,
color_ori=option.color_ori)
else:
raise NotImplementedError("Not Implemented")
glPopAttrib(GL_LIGHTING)
def get_wing_info(world, bid1, bid2, ntype):
body1 = world.skel.body(bid1)
body2 = world.skel.body(bid2)
joint1 = body1.parent_joint
joint2 = body2.parent_joint
p1 = joint1.position_in_world_frame()
c1 = body1.com()
p1_end = p1 + 2 * (c1 - p1)
p2 = joint2.position_in_world_frame()
c2 = body2.com()
p2_end = p2 + 2 * (c2 - p2)
if ntype == 0:
v1 = p1_end
v2 = p2_end
v3 = 0.5 * (p1 + p2)
elif ntype == 1:
v1 = p2_end
v2 = p1_end
v3 = 0.5 * (p1 + p2)
elif ntype == 2:
v1 = p2_end
v2 = p1
v3 = 0.5 * (p1_end + p2)
elif ntype == 3:
v1 = p1
v2 = p2_end
v3 = 0.5 * (p1_end + p2)
else:
raise NotImplementedError("Not Implemented")
c = 0.333333 * (v1 + v2 + v3)
n = np.cross(v1 - v3, v2 - v3)
n = n / np.linalg.norm(n)
return v1, v2, v3, c, n
def render_wing_force_one_segment(wing_info, force, option):
v1, v2, v3, c, n = wing_info
if option.wing.render_force:
gl_render.render_line(c,
c + 0.01 * force,
color=option.wing.color_force)
def render_wing_one_segment(wing_info, option):
v1, v2, v3, c, n = wing_info
if option.wing.render_face:
gl_render.render_tri(v3, v1, v2, color=option.wing.color_face)
if option.wing.render_normal:
gl_render.render_line(c, c + n, color=option.wing.color_normal)
def render_wing(world, option):
glPushAttrib(GL_LIGHTING)
if option.wing.lighting:
glEnable(GL_LIGHTING)
else:
glDisable(GL_LIGHTING)
for bid1, bid2, ntype in world.aero_flesh:
wing_info = get_wing_info(world, bid1, bid2, ntype)
render_wing_one_segment(wing_info, option)
for bid1, bid2, ntype, f in world.render_temp:
wing_info = get_wing_info(world, bid1, bid2, ntype)
render_wing_force_one_segment(wing_info, f, option)
glPopAttrib(GL_LIGHTING)
def get_visual_aspects(skel):
vas = []
for body in skel.bodynodes:
for shape in body.shapenodes:
vas.append(shape.visual_aspect_rgba())
return vas
def set_visual_aspect(skel, vas):
cnt = 0
for body in skel.bodynodes:
for shape in body.shapenodes:
c = vas[cnt]
shape.set_visual_aspect_rgba(c)
cnt += 1
def get_visual_aspects_body(body):
vas = []
for shape in body.shapenodes:
vas.append(shape.visual_aspect_rgba())
return vas
def set_visual_aspect_body(body, vas):
cnt = 0
for shape in body.shapenodes:
c = vas[cnt]
shape.set_visual_aspect_rgba(c)
cnt += 1
def render_body(body, option, global_coord=True):
T = body.parent_bodynode.T if body.parent_bodynode else constants.eye_T()
glPushAttrib(GL_LIGHTING)
if option.lighting:
glEnable(GL_LIGHTING)
else:
glDisable(GL_LIGHTING)
if option.render_face:
s = option.scale
glPushMatrix()
if global_coord:
gl_render.glTransform(T)
glScalef(s, s, s)
body.render_with_color(option.color_face)
glPopMatrix()
if option.render_edge:
glLineWidth(option.line_width)
s = option.scale
glPushMatrix()
if global_coord:
gl_render.glTransform(T)
glScalef(s, s, s)
glPolygonMode(GL_FRONT_AND_BACK, GL_LINE)
body.render_with_color(option.color_edge)
glPolygonMode(GL_FRONT_AND_BACK, GL_FILL)
glPopMatrix()
glPopAttrib(GL_LIGHTING)
def render_skeleton(skel, option):
if option is None:
option = RenderOption()
if option.body.render:
# skel.render_with_color(option.body.color_face)
for body in skel.bodynodes:
render_body(body, option.body)
if option.wing.render:
render_wing(world, option)
if option.joint.render:
for joint in skel.joints:
render_joint(joint, option.joint)
def render_world(world, option=None):
if option is None:
option = RenderOption()
for skel in world.skeletons:
render_skeleton(skel, option)
# def render_joint_with_body(joint):
# T0 = joint.child_bodynode.transform()
# T1 = joint.transform_from_child_body_node()
# def render_body(body):
# T0 = body.transform()
# body.shapenodes[0]
# def render_skeleton(skel):
# for joint in skel.joints:
# body = joint.child_bodynode
# T0 = joint.child_bodynode.transform()
# T1 = joint.transform_from_child_body_node()
def render_geom_bounding_box(geom_type, geom_size, color=[0, 0, 0, 1], T=constants.EYE_T):
if geom_type==pybullet.GEOM_SPHERE:
size = [2*geom_size[0], 2*geom_size[0], 2*geom_size[0]]
gl_render.render_cube(T, size=size, color=color, solid=False)
elif geom_type==pybullet.GEOM_BOX:
size = [geom_size[0], geom_size[1], geom_size[2]]
gl_render.render_cube(T, size=size, color=color, solid=False)
elif geom_type==pybullet.GEOM_CAPSULE:
size = [2*geom_size[1], 2*geom_size[1], 2*geom_size[1]+geom_size[0]]
gl_render.render_cube(T, size=size, color=color, solid=False)
else:
raise NotImplementedError()
def render_geom(geom_type, geom_size, color=[0.5, 0.5, 0.5, 1.0], T=constants.EYE_T):
if geom_type==pybullet.GEOM_SPHERE:
gl_render.render_sphere(T, geom_size[0], color=color, slice1=16, slice2=16)
elif geom_type==pybullet.GEOM_BOX:
gl_render.render_cube(T, size=[geom_size[0], geom_size[1], geom_size[2]], color=color)
elif geom_type==pybullet.GEOM_CAPSULE:
gl_render.render_capsule(T, geom_size[0], geom_size[1], color=color, slice=16)
elif geom_type==pybullet.GEOM_CYLINDER:
gl_render.render_cylinder(T, geom_size[0], geom_size[1], color=color, slice=16)
# elif geom_type==pybullet.GEOM_PLANE:
# pass
# elif geom_type==pybullet.GEOM_MESH:
# pass
else:
raise NotImplementedError()
def render_geom_info(geom_type, geom_size, scale=1.0, color=[0, 0, 0, 1], T=constants.EYE_T, line_width=1.0):
glPushMatrix()
glScalef(scale, scale, scale)
if geom_type==pybullet.GEOM_SPHERE:
gl_render.render_sphere_info(T, geom_size[0], line_width=line_width, slice=32, color=color)
elif geom_type==pybullet.GEOM_BOX:
gl_render.render_cube(T, size=[geom_size[0], geom_size[1], geom_size[2]], color=color, solid=False, line_width=line_width)
elif geom_type==pybullet.GEOM_CAPSULE:
gl_render.render_capsule_info(T, geom_size[0], geom_size[1], line_width=line_width, slice=32, color=color)
elif geom_type==pybullet.GEOM_CYLINDER:
gl_render.render_cylinder_info(T, geom_size[0], geom_size[1], line_width=line_width, slice=32, color=color)
# elif geom_type==pybullet.GEOM_PLANE:
# pass
# elif geom_type==pybullet.GEOM_MESH:
# pass
else:
raise NotImplementedError()
glPopMatrix()
def render_links(pb_client, model):
for j in range(pb_client.getNumJoints(model)):
link_state = pb_client.getLinkState(model, j)
p, Q = np.array(link_state[0]), np.array(link_state[1])
T = conversions.Qp2T(Q, p)
gl_render.render_point(p, radius=0.01, color=[0, 1, 0, 1])
def render_joints(pb_client, model):
for j in range(pb_client.getNumJoints(model)):
joint_info = pb_client.getJointInfo(model, j)
joint_local_p, joint_local_Q, link_idx = joint_info[14], joint_info[15], joint_info[16]
T_joint_local = conversions.Qp2T(
np.array(joint_local_Q), np.array(joint_local_p))
if link_idx == -1:
link_world_p, link_world_Q = pb_client.getBasePositionAndOrientation(model)
else:
link_info = pb_client.getLinkState(model, link_idx)
link_world_p, link_world_Q = link_info[0], link_info[1]
T_link_world = conversions.Qp2T(
np.array(link_world_Q), np.array(link_world_p))
T_joint_world = np.dot(T_link_world, T_joint_local)
# Render joint position
glPushMatrix()
gl_render.glTransform(T_joint_world)
gl_render.render_point(np.zeros(3), radius=0.02, color=[0, 0, 0, 1])
# Render joint axis depending on joint types
joint_type = joint_info[2]
if joint_type == pb_client.JOINT_FIXED:
pass
elif joint_type == pb_client.JOINT_REVOLUTE:
axis = joint_info[13]
gl_render.render_line(np.zeros(3), axis, color=[1, 0, 0, 1], line_width=1.0)
elif joint_type == pb_client.JOINT_SPHERICAL:
gl_render.render_transform(constants.eye_T(), scale=0.2)
else:
raise NotImplementedError()
glPopMatrix()
def render_joint_geoms(pb_client, model, radius=0.025, color=[0.5, 0.5, 0.5, 1]):
for j in range(pb_client.getNumJoints(model)):
joint_info = pb_client.getJointInfo(model, j)
joint_local_p, joint_local_Q, link_idx = joint_info[14], joint_info[15], joint_info[16]
T_joint_local = conversions.Qp2T(
np.array(joint_local_Q), np.array(joint_local_p))
if link_idx == -1:
link_world_p, link_world_Q = pb_client.getBasePositionAndOrientation(model)
else:
link_info = pb_client.getLinkState(model, link_idx)
link_world_p, link_world_Q = link_info[0], link_info[1]
T_link_world = conversions.Qp2T(
np.array(link_world_Q), np.array(link_world_p))
T_joint_world = np.dot(T_link_world, T_joint_local)
# Render joint position
glPushMatrix()
gl_render.render_sphere(T_joint_world, radius, color=color, slice1=16, slice2=16)
gl_render.render_sphere_info(T_joint_world, radius, line_width=4.0, slice=32)
glPopMatrix()
def render_model(pb_client,
model,
draw_link=True,
draw_link_info=True,
draw_joint=False,
draw_joint_geom=True,
ee_indices=None,
color=None,
link_info_scale=1.0,
link_info_color=[0, 0, 0, 1],
link_info_line_width=1.0,
lighting=True,
):
if draw_link or draw_link_info:
data_visual = pb_client.getVisualShapeData(model)
for d in data_visual:
if lighting:
glEnable(GL_LIGHTING)
else:
glDisable(GL_LIGHTING)
link_id = d[1]
if link_id == -1:
p, Q = pb_client.getBasePositionAndOrientation(model)
else:
link_state = pb_client.getLinkState(model, link_id)
p, Q = link_state[4], link_state[5]
p, Q = np.array(p), np.array(Q)
R = conversions.Q2R(Q)
T_joint = conversions.Rp2T(R, p)
T_visual_from_joint = conversions.Qp2T(np.array(d[6]),np.array(d[5]))
glPushMatrix()
gl_render.glTransform(T_joint)
gl_render.glTransform(T_visual_from_joint)
# if color is None: color = d[7]
# alpha = 0.5 if draw_joint else color[3]
if color is None:
color = [d[7][0], d[7][1], d[7][2], d[7][3]]
if draw_link:
render_geom(geom_type=d[2], geom_size=d[3], color=color)
if draw_link_info:
render_geom_info(geom_type=d[2], geom_size=d[3], color=link_info_color, scale=link_info_scale, line_width=link_info_line_width)
# if ee_indices is not None and link_id in ee_indices:
# render_geom_bounding_box(geom_type=d[2], geom_size=d[3], color=[0, 0, 0, 1])
glPopMatrix()
if draw_joint_geom:
render_joint_geoms(pb_client, model)
glDisable(GL_DEPTH_TEST)
if draw_joint:
render_joints(pb_client, model)
render_links(pb_client, model)
glEnable(GL_DEPTH_TEST)
def render_contacts(pb_client, model, scale_h=0.0005, scale_r=0.01, color=[1.0,0.1,0.0,0.5]):
data = pb_client.getContactPoints(model)
for d in data:
p, n, l = np.array(d[6]), np.array(d[7]), d[9]
p1 = p
p2 = p + n * l * scale_h
gl_render.render_arrow(p1, p2, D=scale_r, color=color)
================================================
FILE: bullet/bullet_utils.py
================================================
# Copyright (c) Facebook, Inc. and its affiliates.
import numpy as np
from fairmotion.ops import quaternion
'''
Bullet uses 'xyzw' order for the quaternion. quat_out_order lets
the bullet_utils interprets the order for the application correctly.
'''
xyzw_in = True
def set_base_pQvw(pb_client, body_id, p, Q, v=None, w=None):
'''
Set positions, orientations, linear and angular velocities of the base link.
'''
if not xyzw_in:
Q = quaternion.Q_op(Q, op=['change_order'], xyzw_in=False)
pb_client.resetBasePositionAndOrientation(body_id, p, Q)
if v is not None and w is not None:
pb_client.resetBaseVelocity(body_id, v, w)
def get_base_pQvw(pb_client, body_id):
'''
Returns position, orientation, linear and angular velocities of the base link.
'''
p, Q = pb_client.getBasePositionAndOrientation(body_id)
p, Q = np.array(p), np.array(Q)
if not xyzw_in:
Q = quaternion.Q_op(Q, op=['change_order'], xyzw_in=True)
v, w = pb_client.getBaseVelocity(body_id)
v, w = np.array(v), np.array(w)
return p, Q, v, w
def get_link_pQvw(pb_client, body_id, indices=None):
'''
Returns positions, orientations, linear and angular velocities given link indices.
Please use get_base_pQvw for the base link.
'''
if indices is None:
indices = range(pb_client.getNumJoints(body_id))
num_indices = len(indices)
assert num_indices > 0
ls = pb_client.getLinkStates(body_id, indices, computeLinkVelocity=True)
ps = [np.array(ls[j][0]) for j in range(num_indices)]
if not xyzw_in:
Qs = [
quaternion.Q_op(np.array(ls[j][1]), op=['change_order'], xyzw_in=True) \
for j in range(num_indices)]
else:
Qs = [np.array(ls[j][1]) for j in range(num_indices)]
vs = [np.array(ls[j][6]) for j in range(num_indices)]
ws = [np.array(ls[j][7]) for j in range(num_indices)]
if num_indices == 1:
return ps[0], Qs[0], vs[0], ws[0]
else:
return ps, Qs, vs, ws
def get_joint_torques(pb_client, body_id, indices=None):
'''
This will return joint torques applied during the previous simulation
'''
if indices is None:
indices = range(pb_client.getNumJoints(body_id))
num_indices = len(indices)
assert num_indices > 0
js = pb_client.getJointStatesMultiDof(body_id, indices)
tqs = [np.array(js[j][3]) for j in range(num_indices)]
if num_indices == 1:
return tqs[0]
else:
return tqs
def set_joint_pv(pb_client, body_id, indices, ps, vs):
'''
Set positions and velocities given joint indices.
Please note that the values are locally repsented w.r.t. its parent joint
'''
ps_processed = ps.copy()
for i in range(len(ps_processed)):
if len(ps_processed[i]) == 4 and not xyzw_in:
ps_processed[i] = \
quaternion.Q_op(ps_processed[i], op=['change_order'], xyzw_in=False)
pb_client.resetJointStatesMultiDof(body_id, indices, ps_processed, vs)
def get_joint_pv(pb_client, body_id, indices=None):
'''
Return positions and velocities given joint indices.
Please note that the values are locally repsented w.r.t. its parent joint
'''
if indices is None:
indices = range(pb_client.getNumJoints(body_id))
num_indices = len(indices)
assert num_indices > 0
js = pb_client.getJointStatesMultiDof(body_id, indices)
ps = []
vs = []
for j in range(num_indices):
p = np.array(js[j][0])
v = np.array(js[j][1])
if len(p) == 4 and not xyzw_in:
p = quaternion.Q_op(p, op=['change_order'], xyzw_in=True)
ps.append(p)
vs.append(v)
if num_indices == 1:
return ps[0], vs[0]
else:
return ps, vs
def get_state_all(pb_client, body_id):
'''
Return all state information of the given body. This includes
pQvw of the base link and p and v for the all joints
'''
p, Q, v, w = get_base_pQvw(pb_client, body_id)
ps, vs = get_joint_pv(pb_client, body_id)
return [p, Q, v, w, ps, vs]
def set_state_all(pb_client, body_id, states):
'''
Set all state information of the given body. States should include
pQvw of the base link and p and v for the all joints
'''
p, Q, v, w, ps, vs = states
assert pb_client.getNumJoints(body_id) == len(ps)
set_base_pQvw(pb_client, body_id, p, Q, v, w)
indices = range(len(ps))
''' Handling fixed joints '''
for i in indices:
if len(ps[i])==0: ps[i] = [0]
if len(vs[i])==0: vs[i] = [0]
set_joint_pv(pb_client, body_id, indices, ps, vs)
def get_mass(pb_client, body_id, indices=None):
'''
Return masses of the links
'''
if indices is None:
indices = range(-1, pb_client.getNumJoints(body_id))
masses = []
for i in indices:
di = pb_client.getDynamicsInfo(body_id, i)
masses.append(di[0])
return masses
def compute_com_and_com_vel(pb_client, body_id, indices=None):
'''
Return the center-of-mass and the center-of-mass velocity
'''
if indices is None:
indices = range(-1, pb_client.getNumJoints(body_id))
total_mass = 0.0
com = np.zeros(3)
com_vel = np.zeros(3)
for i in indices:
di = pb_client.getDynamicsInfo(body_id, i)
mass = di[0]
if i==-1:
p, _, v, _ = get_base_pQvw(pb_client, body_id)
else:
ls = pb_client.getLinkState(body_id, i, computeLinkVelocity=True)
p, v = np.array(ls[0]), np.array(ls[6])
total_mass += mass
com += mass * p
com_vel += mass * v
com /= total_mass
com_vel /= total_mass
return com, com_vel
def _compute_com_and_com_vel(pb_client, body_id, indices=None, masses=None):
if indices is None:
indices = range(-1, pb_client.getNumJoints(body_id))
if masses is None:
masses = get_mass(pb_client, body_id, indices)
assert len(indices)==len(masses)
total_mass = 0.0
com = np.zeros(3)
com_vel = np.zeros(3)
indices_wo_base = []
masses_wo_base = []
for i in range(len(indices)):
if indices[i]<0:
p, _, v, _ = get_base_pQvw(pb_client, body_id)
mass = masses[i]
total_mass += mass
com += mass * p
com_vel = mass * v
else:
indices_wo_base.append(indices[i])
masses_wo_base.append(masses[i])
ls = pb_client.getLinkStates(body_id, indices_wo_base, computeLinkVelocity=True)
for i in range(len(masses_wo_base)):
mass = masses_wo_base[i]
p, v = np.array(ls[i][0]), np.array(ls[i][6])
total_mass += mass
com += mass * p
com_vel = mass * v
com /= total_mass
com_vel /= total_mass
return com, com_vel
def compute_PD_forces(pb_client,
body_id,
joint_indices,
desired_positions,
desired_velocities,
kps,
kds,
max_forces):
'''
Compute PD forces given target values (P and D) and the simulated agent.
This was implented because PD_CONTROL for setJointMotorControlMultiDofArray
in PyBullet does not support spherical joint yet.
'''
forces = []
js = pb_client.getJointStatesMultiDof(body_id, joint_indices)
for i in range(len(joint_indices)):
joint_pos = js[i][0]
joint_vel = js[i][1]
# print(i, desired_positions[i], joint_pos)
if len(joint_pos) == 1:
desired_pos = desired_positions[i]
desired_vel = desired_velocities[i]
qerror = desired_pos - joint_pos[0]
qdoterror = desired_vel - joint_vel[0]
elif len(joint_pos) == 4:
desired_pos = desired_positions[i]
desired_vel = desired_velocities[i]
qerror = np.array(pb_client.getAxisDifferenceQuaternion(desired_pos, joint_pos))
qdoterror = np.array(desired_vel - joint_vel)
else:
raise NotImplementedError
f = kps[i] * qerror + kds[i] * qdoterror
f = np.clip(f, -max_forces[i], max_forces[i])
forces.append(f)
return forces
================================================
FILE: data/character/amass.urdf
================================================
<?xml version="1.0"?>
<!-- Copyright (c) Facebook, Inc. and its affiliates. -->
<robot name="amass_male">
<link name="root">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="5.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_root">
<origin xyz="0.00354 0.065 -0.03107" rpy="0 1.5708 0"/>
<geometry>
<sphere radius="0.05" length="0.115"/>
</geometry>
</collision>
<collision name="collision_1_root">
<origin xyz="-0.05769 -0.02577 -0.0174" rpy="0 0 0"/>
<geometry>
<sphere radius="0.075"/>
</geometry>
</collision>
<collision name="collision_2_root">
<origin xyz="0.06735 -0.02415 -0.0174" rpy="0 0 0"/>
<geometry>
<sphere radius="0.075"/>
</geometry>
</collision>
</link>
<link name="lhip">
<inertial>
<origin xyz="0.02173 -0.19323 0.00402" rpy="0 0 0"/>
<mass value="5.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lhip">
<origin xyz="0.02173 -0.19323 0.00402" rpy="1.55 0.11194 0.10964"/>
<geometry>
<capsule radius="0.05" length="0.3"/>
</geometry>
<!-- <origin xyz="0.02173 -0.19323 0.00402" rpy="0 0 0"/>
<geometry>
<box size="0.08 0.3 0.08"/>
</geometry> -->
</collision>
</link>
<link name="lknee">
<inertial>
<origin xyz="-0.00739 -0.21344 -0.01871" rpy="0 0 0"/>
<mass value="3.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lknee">
<origin xyz="-0.00739 -0.21344 -0.01871" rpy="1.65825 -0.0345 -0.03766"/>
<geometry>
<capsule radius="0.05" length="0.325"/>
</geometry>
<!-- <origin xyz="-0.00739 -0.21344 -0.01871" rpy="0 0 0"/>
<geometry>
<box size="0.08 0.35 0.08"/>
</geometry> -->
</collision>
</link>
<link name="lankle">
<inertial>
<origin xyz="0.01719 -0.06032 0.02617" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lankle">
<origin xyz="0.01719 -0.06032 0.02617" rpy="0 0 0"/>
<geometry>
<box size="0.0875 0.06 0.185"/>
</geometry>
</collision>
</link>
<link name="rhip">
<inertial>
<origin xyz="-0.02163 -0.19184 -0.00242" rpy="0 0 0"/>
<mass value="5.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_rhip">
<origin xyz="-0.02163 -0.19184 -0.00242" rpy="1.58342 -0.11226 -0.11368"/>
<geometry>
<capsule radius="0.05" length="0.3"/>
</geometry>
<!-- <origin xyz="-0.02163 -0.19184 -0.00242" rpy="0 0 0"/>
<geometry>
<box size="0.08 0.3 0.08"/>
</geometry> -->
</collision>
</link>
<link name="rknee">
<inertial>
<origin xyz="0.00953 -0.21002 -0.01728" rpy="0 0 0"/>
<mass value="3.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_rknee">
<origin xyz="0.00953 -0.21002 -0.01728" rpy="1.65289 0.04518 0.04905"/>
<geometry>
<capsule radius="0.05" length="0.325"/>
</geometry>
<!-- <origin xyz="0.00953 -0.21002 -0.01728" rpy="0 0 0"/>
<geometry>
<box size="0.08 0.35 0.08"/>
</geometry> -->
</collision>
</link>
<link name="rankle">
<inertial>
<origin xyz="-0.01742 -0.06202 0.02969" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_rankle">
<origin xyz="-0.01742 -0.06202 0.02969" rpy="0 0 0"/>
<geometry>
<box size="0.0875 0.06 0.185"/>
</geometry>
</collision>
</link>
<link name="lowerback">
<inertial>
<origin xyz="0.0 0.05 0.013" rpy="0 0 0"/>
<mass value="5.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lowerback">
<origin xyz="0.0 0.06 0.013" rpy="0 1.5708 0"/>
<geometry>
<sphere radius="0.065"/>
</geometry>
</collision>
<!-- <collision name="collision_0_lowerback">
<origin xyz="-0.00028 0.0158 0.01" rpy="0 1.5708 0"/>
<geometry>
<sphere radius="0.0375" length="0.1"/>
</geometry>
</collision>
<collision name="collision_1_lowerback">
<origin xyz="-0.00054 0.08624 0.016" rpy="0 1.5708 0"/>
<geometry>
<sphere radius="0.0375" length="0.1"/>
</geometry>
</collision> -->
</link>
<link name="upperback">
<inertial>
<origin xyz="0.0 0.02246 0.00143" rpy="0 0 0"/>
<mass value="5.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_upperback">
<origin xyz="0.0 0.03246 0.00143" rpy="0 1.5708 0"/>
<geometry>
<sphere radius="0.05" length="0.125"/>
</geometry>
</collision>
</link>
<link name="chest">
<inertial>
<origin xyz="0.0 0.057 -0.00687" rpy="0 0 0"/>
<mass value="8.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_chest">
<origin xyz="-0.045 0.057 -0.00687" rpy="0 0 0"/>
<geometry>
<sphere radius="0.07"/>
</geometry>
</collision>
<collision name="collision_1_chest">
<origin xyz="0.045 0.057 -0.00687" rpy="0 0 0"/>
<geometry>
<sphere radius="0.07"/>
</geometry>
</collision>
</link>
<link name="lowerneck">
<inertial>
<origin xyz="0.0 -0.01296 0.01" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lowerneck">
<origin xyz="0.0 -0.01296 0.01" rpy="1.5708 0 0"/>
<geometry>
<capsule radius="0.030" length="0.0273"/>
</geometry>
</collision>
</link>
<link name="upperneck">
<inertial>
<origin xyz="0 0.0020 0" rpy="0 0 0"/>
<mass value="3.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_upperneck">
<origin xyz="0 0.0020 0" rpy="1.5708 0 0"/>
<geometry>
<capsule radius="0.06" length="0.035"/>
</geometry>
</collision>
</link>
<link name="lclavicle">
<inertial>
<origin xyz="0.06146 0.0226 -0.00952" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lclavicle">
<origin xyz="0.06146 0.0226 -0.00952" rpy="1.17204 1.95049 1.5502"/>
<geometry>
<capsule radius="0.04" length="0.05"/>
</geometry>
</collision>
</link>
<link name="lshoulder">
<inertial>
<!-- <origin xyz="0.12767 -0.00782 -0.01147" rpy="0 0 0"/> -->
<origin xyz="0.12767 0.0 0.0" rpy="0.0 0.0 0.0"/>
<mass value="2.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lshoulder">
<!-- <origin xyz="0.12767 -0.00782 -0.01147" rpy="-0.59854 1.67914 -0.66249"/>
<geometry>
<capsule radius="0.032" length="0.2"/>
</geometry> -->
<!-- <origin xyz="0.12767 -0.00782 -0.01147" rpy="0 0 0"/> -->
<origin xyz="0.12767 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry>
<box size="0.25 0.05 0.05"/>
</geometry>
</collision>
</link>
<link name="lelbow">
<inertial>
<!-- <origin xyz="0.12285 0.00635 -0.00369" rpy="0 0 0"/> -->
<origin xyz="0.12285 0.0 0.0" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lelbow">
<!-- <origin xyz="0.12285 0.00635 -0.00369" rpy="1.04461 1.626 1.09303"/>
<geometry>
<capsule radius="0.032" length="0.18"/>
</geometry> -->
<!-- <origin xyz="0.12285 0.00635 -0.00369" rpy="0 0 0"/> -->
<origin xyz="0.12285 0.0 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.22 0.05 0.05"/>
</geometry>
</collision>
</link>
<link name="lwrist">
<inertial>
<origin xyz="0.02228 0 0" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_lwrist">
<origin xyz="0.02228 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.04"/>
</geometry>
</collision>
</link>
<link name="rclavicle">
<inertial>
<origin xyz="-0.05661 0.02343 -0.00424" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_rclavicle">
<origin xyz="-0.05661 0.02343 -0.00424" rpy="-1.74968 -1.17274 1.34362"/>
<geometry>
<capsule radius="0.04" length="0.05"/>
</geometry>
</collision>
</link>
<link name="rshoulder">
<inertial>
<!-- <origin xyz="-0.13006 -0.00718 -0.01563" rpy="0 0 0"/> -->
<origin xyz="-0.13006 0.0 0.0" rpy="0 0 0"/>
<mass value="2.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_rshoulder">
<!-- <origin xyz="-0.13006 -0.00718 -0.01563" rpy="-0.43075 -1.70232 0.48923"/>
<geometry>
<capsule radius="0.032" length="0.2"/>
</geometry> -->
<!-- <origin xyz="-0.13006 -0.00718 -0.01563" rpy="0 0 0"/> -->
<origin xyz="-0.13006 0.0 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.25 0.05 0.05"/>
</geometry>
</collision>
</link>
<link name="relbow">
<inertial>
<!-- <origin xyz="-0.12455 0.0034 -0.00301" rpy="0 0 0"/> -->
<origin xyz="-0.12455 0.0 0.0" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_relbow">
<!-- <origin xyz="-0.12455 0.0034 -0.00301" rpy="0.84515 -1.60453 -0.87067"/>
<geometry>
<capsule radius="0.032" length="0.18"/>
</geometry> -->
<!-- <origin xyz="-0.12455 0.0034 -0.00301" rpy="0 0 0"/> -->
<origin xyz="-0.12455 0.0 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.22 0.05 0.05"/>
</geometry>
</collision>
</link>
<link name="rwrist">
<inertial>
<origin xyz="-0.0239 0 0" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<collision name="collision_0_rwrist">
<origin xyz="-0.0239 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.04"/>
</geometry>
</collision>
</link>
<joint name="lhip" type="spherical">
<origin xyz="0.08858 -0.08228 -0.01766" rpy="0 0 0"/>
<parent link="root"/>
<child link="lhip"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lknee" type="spherical">
<origin xyz="0.04345 -0.38647 0.00804" rpy="0 0 0"/>
<parent link="lhip"/>
<child link="lknee"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lankle" type="spherical">
<origin xyz="-0.01479 -0.42687 -0.03743" rpy="0 0 0"/>
<parent link="lknee"/>
<child link="lankle"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rhip" type="spherical">
<origin xyz="-0.09031 -0.09051 -0.01354" rpy="0 0 0"/>
<parent link="root"/>
<child link="rhip"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rknee" type="spherical">
<origin xyz="-0.04326 -0.38369 -0.00484" rpy="0 0 0"/>
<parent link="rhip"/>
<child link="rknee"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rankle" type="spherical">
<origin xyz="0.01906 -0.42005 -0.03456" rpy="0 0 0"/>
<parent link="rknee"/>
<child link="rankle"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lowerback" type="spherical">
<origin xyz="0.0 0.1244 -0.03" rpy="0 0 0"/>
<parent link="root"/>
<child link="lowerback"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="upperback" type="spherical">
<origin xyz="0.0 0.13796 0.02682" rpy="0 0 0"/>
<parent link="lowerback"/>
<child link="upperback"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="chest" type="spherical">
<origin xyz="0.0 0.05603 0.00285" rpy="0 0 0"/>
<parent link="upperback"/>
<child link="chest"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lowerneck" type="spherical">
<origin xyz="0.0 0.15524 -0.03347" rpy="0 0 0"/>
<parent link="chest"/>
<child link="lowerneck"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="upperneck" type="spherical">
<origin xyz="0.0 0.08894 0.02041" rpy="0 0 0"/>
<parent link="lowerneck"/>
<child link="upperneck"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lclavicle" type="spherical">
<origin xyz="0.0717 0.114 -0.0189" rpy="0 0 0"/>
<parent link="chest"/>
<child link="lclavicle"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lshoulder" type="spherical">
<origin xyz="0.12292 0.04521 -0.01905" rpy="0 0 0"/>
<!-- <origin xyz="0.12292 0.0 0.0" rpy="0 0 0"/> -->
<parent link="lclavicle"/>
<child link="lshoulder"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lelbow" type="spherical">
<!-- <origin xyz="0.25533 -0.01565 -0.02295" rpy="0 0 0"/> -->
<origin xyz="0.25533 0.0 0.0" rpy="0 0 0"/>
<parent link="lshoulder"/>
<child link="lelbow"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="lwrist" type="fixed">
<!-- <origin xyz="0.24571 0.0127 -0.00737" rpy="0 0 0"/> -->
<origin xyz="0.24571 0.0 0.0" rpy="0 0 0"/>
<parent link="lelbow"/>
<child link="lwrist"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rclavicle" type="spherical">
<origin xyz="-0.08295 0.11247 -0.02371" rpy="0 0 0"/>
<parent link="chest"/>
<child link="rclavicle"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rshoulder" type="spherical">
<origin xyz="-0.11323 0.04685 -0.00847" rpy="0 0 0"/>
<parent link="rclavicle"/>
<child link="rshoulder"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="relbow" type="spherical">
<!-- <origin xyz="-0.26013 -0.01437 -0.03127" rpy="0 0 0"/> -->
<origin xyz="-0.26013 0.0 0.0" rpy="0 0 0"/>
<parent link="rshoulder"/>
<child link="relbow"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rwrist" type="fixed">
<!-- <origin xyz="-0.24911 0.00679 -0.00603" rpy="0 0 0"/> -->
<origin xyz="-0.24911 0.0 0.0" rpy="0 0 0"/>
<parent link="relbow"/>
<child link="rwrist"/>
<axis xyz="1 0 0"/>
</joint>
</robot>
================================================
FILE: data/motion/amass_hierarchy.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 5
Frame Time: 0.033333
0.000000 0.000000 1.000000 0.000000 -0.000000 90.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000
0.000000 0.000000 1.000000 0.000000 -0.000000 90.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000
0.000000 0.000000 1.000000 0.000000 -0.000000 90.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000
0.000000 0.000000 1.000000 0.000000 -0.000000 90.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000
0.000000 0.000000 1.000000 0.000000 -0.000000 90.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000 0.000000 -0.000000 0.000000
================================================
FILE: data/motion/cmu/expert0/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/expert1/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/expert2/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/expert3/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/expert4/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/expert5/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/expert6/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/expert7/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/cmu/moe/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 10
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
================================================
FILE: data/motion/test.bvh
================================================
HIERARCHY
ROOT root
{
OFFSET 0.000000 0.000000 0.000000
CHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation Xrotation
JOINT lhip
{
OFFSET 0.058581 -0.082280 -0.017664
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lknee
{
OFFSET 0.043451 -0.386469 0.008037
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lankle
{
OFFSET -0.014790 -0.426874 -0.037428
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT ltoe
{
OFFSET 0.041054 -0.060286 0.122042
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rhip
{
OFFSET -0.060310 -0.090513 -0.013543
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rknee
{
OFFSET -0.043257 -0.383688 -0.004843
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rankle
{
OFFSET 0.019056 -0.420046 -0.034562
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rtoe
{
OFFSET -0.034840 -0.062106 0.130323
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT lowerback
{
OFFSET 0.004439 0.124404 -0.038385
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperback
{
OFFSET 0.004488 0.137956 0.026820
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT chest
{
OFFSET -0.002265 0.056032 0.002855
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lowerneck
{
OFFSET -0.013390 0.211636 -0.033468
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT upperneck
{
OFFSET 0.010113 0.088937 0.050410
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
JOINT lclavicle
{
OFFSET 0.071702 0.114000 -0.018898
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lshoulder
{
OFFSET 0.122921 0.045205 -0.019046
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lelbow
{
OFFSET 0.255332 -0.015649 -0.022946
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT lwrist
{
OFFSET 0.265709 0.012698 -0.007375
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
JOINT rclavicle
{
OFFSET -0.082954 0.112472 -0.023707
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rshoulder
{
OFFSET -0.113228 0.046853 -0.008472
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT relbow
{
OFFSET -0.260127 -0.014369 -0.031269
CHANNELS 3 Zrotation Yrotation Xrotation
JOINT rwrist
{
OFFSET -0.269108 0.006794 -0.006027
CHANNELS 3 Zrotation Yrotation Xrotation
End Site
{
OFFSET 0.000000 0.000000 0.000000
}
}
}
}
}
}
}
}
}
MOTION
Frames: 1058
Frame Time: 0.033333
0.359791 0.157500 0.997414 82.809032 -1.328360 92.038375 3.455343 6.125326 2.341002 -3.117674 2.859707 -2.001316 -0.695214 9.021748 -4.817840 0.000000 -0.000000 0.000000 -7.320280 -4.394152 -3.239532 1.287693 -2.752259 5.033440 5.645506 -0.607566 -6.286681 0.000000 -0.000000 0.000000 -3.083010 2.600816 -8.670147 2.712164 -3.957971 25.792586 -1.212561 0.828071 -11.421098 4.101695 5.119176 14.090366 2.712227 -1.595290 6.607059 -22.512859 -3.111139 -4.082881 -29.300866 -13.340521 12.215706 68.113647 -84.868300 -41.495501 12.506346 -44.258594 32.923647 22.874828 8.014039 4.655263 27.148928 14.498636 5.570891 -73.439562 88.464497 -64.512318 -17.868863 38.938117 9.427635
0.357352 0.157599 0.997219 84.467883 -1.473583 91.828679 3.334637 5.851037 1.740084 -3.010128 1.717090 -1.259012 -0.786118 8.865797 -4.844414 0.000000 -0.000000 0.000000 -7.339365 -4.743995 -3.423832 1.128667 -3.181044 5.995970 5.443164 -1.330705 -6.744501 0.000000 -0.000000 0.000000 -3.156443 2.852926 -7.273137 2.518798 -3.548612 26.065026 -1.239334 0.790788 -11.364130 3.606971 3.941311 13.389005 3.397545 -2.013872 6.057834 -23.319894 -3.111136 -3.460317 -29.968176 -13.681917 12.281171 57.211037 -84.355823 -29.129682 18.456412 -46.204516 31.995838 23.919182 7.285763 5.083580 26.220957 14.401956 3.733749 -49.496781 88.336228 -39.782476 -18.418272 40.142467 8.322680
0.356290 0.157777 0.997014 85.015232 -1.552513 91.785184 3.244886 5.771477 1.517353 -2.979231 1.435120 -1.023404 -0.798205 8.734015 -4.787341 0.000000 -0.000000 0.000000 -7.359236 -4.838234 -3.758668 1.007696 -3.456797 6.697731 5.347687 -1.522442 -6.999852 0.000000 -0.000000 0.000000 -3.214113 2.867809 -6.630895 2.413532 -3.452558 26.179007 -1.236871 0.868872 -11.260248 3.501376 3.773821 13.147860 3.524381 -2.249016 5.502108 -23.395686 -3.201569 -3.414779 -30.198995 -13.693257 12.300341 57.244486 -84.094955 -29.054918 19.264283 -46.477914 31.391147 24.080604 7.299545 5.124624 26.490229 14.149753 3.463439 -64.523354 88.151202 -54.601695 -18.217587 40.591531 8.384093
0.355150 0.158007 0.996755 85.352687 -1.584785 91.739159 3.164317 5.705348 1.350237 -2.894029 1.234912 -0.864629 -0.749290 8.699552 -4.720854 0.000000 -0.000000 0.000000 -7.332664 -4.888962 -4.166560 0.883160 -3.588909 7.449022 5.243328 -1.739674 -7.213130 0.000000 -0.000000 0.000000 -3.240094 2.940980 -5.869128 2.358406 -3.352735 26.203616 -1.233408 0.926570 -11.284949 3.457433 3.727419 12.782968 3.595996 -2.415365 5.186014 -23.384673 -3.258541 -3.313590 -30.232277 -13.773525 12.264702 58.894518 -84.000935 -30.665036 20.426528 -46.419306 30.390787 24.266898 7.283104 5.250874 26.740762 13.940831 3.350339 -82.187024 87.943836 -72.088177 -18.936536 40.580582 7.578998
0.354107 0.158016 0.996579 85.658812 -1.587851 91.889694 3.151933 5.615116 1.011589 -2.864357 1.161671 -0.757431 -0.704566 8.573250 -4.628772 0.000000 -0.000000 0.000000 -7.244375 -4.905611 -4.740218 0.748640 -3.786689 8.148999 5.208929 -1.913761 -7.364999 0.000000 -0.000000 0.000000 -3.282857 2.992659 -5.320851 2.310155 -3.262484 25.959600 -1.214145 0.941893 -11.241755 3.473584 3.883213 12.672781 3.725178 -2.682631 4.818535 -23.240086 -3.357973 -3.338156 -30.122238 -13.757927 12.415975 62.455494 -84.008240 -34.631580 20.558439 -46.091134 29.755059 24.207461 7.455887 5.341269 27.302653 13.508297 3.731445 -96.553321 87.237974 -86.576100 -19.749944 40.461420 7.027911
0.353693 0.158085 0.996328 85.869760 -1.566703 91.988859 3.201274 5.613412 0.865406 -2.882660 1.098000 -0.785177 -0.738519 8.442164 -4.536247 0.000000 -0.000000 0.000000 -7.165460 -4.971876 -5.144652 0.663906 -3.896009 8.685722 5.185478 -1.985371 -7.464504 0.000000 -0.000000 0.000000 -3.478097 3.055199 -4.934412 2.440464 -3.202301 25.873726 -1.101609 0.956452 -11.344846 3.297992 3.841087 12.657414 3.872266 -2.748189 4.568542 -23.069637 -3.414888 -3.229709 -29.989199 -13.949093 12.477741 66.035548 -84.070347 -38.606739 21.247465 -45.608429 28.933868 24.296793 7.445052 5.370906 27.405557 13.192469 3.877710 -105.770625 87.043656 -95.236584 -20.731015 41.499649 7.228717
0.353859 0.157858 0.996146 86.077473 -1.537643 92.132674 3.263559 5.572884 0.796919 -2.902512 0.927494 -1.008698 -0.579786 8.465550 -4.384462 0.000000 -0.000000 0.000000 -6.991539 -5.055447 -5.471203 0.497247 -3.894806 9.035267 5.124499 -2.249588 -7.518726 0.000000 -0.000000 0.000000 -3.789198 3.045338 -4.824954 2.617427 -3.225472 25.638017 -0.968479 0.948323 -11.236639 3.176472 3.820533 12.522887 4.001771 -2.488416 4.609174 -22.772514 -3.347065 -3.284803 -29.674687 -14.347560 12.537658 70.229286 -84.339699 -43.649053 21.342472 -44.065641 27.211556 24.313262 7.087721 5.058543 27.506718 13.485176 3.866925 -123.360219 86.535344 -113.939635 -20.641722 39.210296 5.167936
0.354029 0.157771 0.996139 86.201426 -1.502646 92.186483 3.350980 5.614025 0.850805 -2.962523 0.772338 -1.268276 -0.512064 8.428307 -4.216238 0.000000 -0.000000 0.000000 -6.917030 -5.046310 -5.571751 0.489840 -3.914268 9.122475 5.116424 -2.428662 -7.455487 0.000000 -0.000000 0.000000 -3.988579 3.046282 -4.787072 2.745137 -3.288207 25.383391 -0.907481 1.024098 -11.011983 2.984910 3.806983 12.442354 4.141390 -2.365901 4.657415 -22.320695 -3.322613 -3.456699 -29.550328 -15.071815 12.624360 73.906013 -84.438630 -48.803908 20.470223 -41.966070 24.644399 24.053949 7.015139 4.742291 27.649754 13.730337 4.111536 -131.969067 85.734469 -123.447287 -20.927061 37.933259 3.730767
0.354323 0.157773 0.996289 86.341388 -1.430449 92.200632 3.466129 5.630134 0.968458 -3.003977 0.529864 -1.529451 -0.466676 8.509042 -4.053361 0.000000 -0.000000 0.000000 -6.815033 -5.059712 -5.533655 0.504736 -3.799828 9.083904 5.131329 -2.711135 -7.419216 0.000000 -0.000000 0.000000 -4.108476 3.030527 -4.745613 2.852709 -3.426843 25.024511 -0.852273 1.125735 -10.806600 2.491412 3.500452 12.435080 4.458764 -1.929591 4.803542 -21.717420 -3.513799 -3.391890 -29.345163 -15.717298 12.712185 77.367734 -84.317072 -53.577885 21.841104 -39.455981 20.728945 23.632357 6.959582 4.492893 27.556650 14.079939 4.122770 -141.972942 85.304562 -133.815940 -22.004498 37.122863 2.554463
0.355097 0.157748 0.996282 86.372097 -1.404138 92.115286 3.520552 5.645212 1.217381 -3.023494 0.295799 -1.792634 -0.371281 8.645108 -3.953789 0.000000 -0.000000 0.000000 -6.759764 -5.066536 -5.322574 0.520598 -3.630566 8.893024 5.115930 -2.969957 -7.342545 0.000000 -0.000000 0.000000 -4.245223 3.029543 -4.826672 2.899734 -3.536133 24.866290 -0.854558 1.283432 -10.722280 2.148249 3.247573 12.419926 4.703117 -1.626020 5.003567 -21.078504 -3.787116 -3.413467 -29.071296 -16.629268 12.783380 78.928188 -83.974014 -56.606551 22.206119 -36.448317 17.388064 23.005089 7.163017 4.191519 27.640751 14.514000 4.254256 -143.170492 84.398563 -136.175888 -22.589298 35.206501 0.295548
0.355828 0.157594 0.996283 86.351870 -1.381929 92.014569 3.574782 5.674950 1.438174 -3.051363 0.020410 -1.954496 -0.255108 8.844115 -3.901345 0.000000 -0.000000 0.000000 -6.702544 -5.018588 -5.102650 0.560139 -3.340171 8.693973 5.067077 -3.317400 -7.288374 0.000000 -0.000000 0.000000 -4.367350 3.034161 -4.846158 2.939041 -3.529230 24.383230 -0.836006 1.368352 -10.427506 1.874172 2.969860 12.341321 4.998025 -1.359644 5.266729 -20.342970 -4.180218 -3.500686 -28.657405 -17.651300 12.762692 78.489355 -83.567392 -57.565844 22.879018 -33.838615 14.753977 22.281093 7.367196 3.795711 27.617189 15.096315 4.361435 -144.308902 83.749792 -138.660845 -24.097630 33.094784 -2.403399
0.356418 0.157708 0.996283 86.326371 -1.361890 91.921128 3.606397 5.735852 1.524629 -3.073751 -0.337029 -1.917476 -0.155817 9.130096 -3.898826 0.000000 -0.000000 0.000000 -6.657178 -5.016326 -4.940334 0.606165 -2.907793 8.556907 5.025537 -3.776550 -7.248032 0.000000 -0.000000 0.000000 -4.407359 3.045200 -4.890347 2.963673 -3.572959 23.737630 -0.837552 1.486406 -9.934246 1.413422 2.587761 12.325932 5.389487 -0.927673 5.363866 -19.555521 -4.480315 -3.727437 -28.207819 -18.863425 12.724376 76.566379 -83.392010 -57.366502 24.175214 -30.667025 11.642028 21.307861 7.423808 3.283621 27.526671 15.967281 4.510906 -148.236918 83.359975 -144.413723 -26.862474 29.917949 -5.694914
0.356984 0.157859 0.996418 86.310221 -1.336960 91.774373 3.624313 5.700259 1.627974 -3.073767 -0.498991 -1.824505 0.006758 9.294500 -3.896060 0.000000 -0.000000 0.000000 -6.605846 -5.013791 -4.709303 0.614869 -2.585150 8.395268 5.025223 -4.085637 -7.178258 0.000000 -0.000000 0.000000 -4.419151 3.114622 -4.945594 2.939739 -3.679640 23.347868 -0.853071 1.673563 -9.637379 1.133577 2.322901 12.267972 5.712845 -0.594586 5.501401 -18.608759 -5.101506 -3.801589 -27.803170 -19.956382 12.487507 74.939605 -82.948944 -57.425659 24.171076 -27.679116 8.452600 20.421176 7.864605 3.029070 27.362137 16.773812 4.089696 -145.015255 82.808275 -142.430579 -26.759577 27.513610 -7.382011
0.357602 0.158136 0.996584 86.300457 -1.309749 91.596157 3.639245 5.643562 1.828373 -3.051301 -0.557343 -1.844403 0.132774 9.411861 -3.888662 0.000000 -0.000000 0.000000 -6.573037 -5.006062 -4.422702 0.624160 -2.431768 8.206604 4.992252 -4.267678 -7.125626 0.000000 -0.000000 0.000000 -4.379025 3.191452 -5.098921 2.892432 -3.806403 23.274256 -0.878982 1.859137 -9.547681 0.755664 2.093364 12.465640 6.112606 -0.330246 5.474846 -17.757878 -5.920020 -3.858052 -27.218048 -20.883396 12.109664 73.657488 -82.271112 -58.044109 23.215209 -25.356557 5.049884 19.487509 8.608184 2.627717 27.005681 17.503754 3.350674 -137.029157 82.588522 -135.461761 -24.299869 26.523567 -8.455515
0.358241 0.158423 0.996628 86.252667 -1.308943 91.425655 3.643698 5.694199 2.049032 -3.069378 -0.855473 -1.904678 0.282462 9.658949 -3.865142 0.000000 -0.000000 0.000000 -6.550699 -5.003786 -4.153391 0.633620 -2.035856 8.027635 4.929160 -4.647565 -7.030364 0.000000 -0.000000 0.000000 -4.405838 3.273726 -5.191243 2.907453 -3.875652 22.943320 -0.879104 2.041662 -9.297263 0.361883 1.728123 12.543023 6.461856 0.016682 5.600804 -16.858496 -6.608907 -3.924752 -26.720114 -22.070657 11.733965 71.649326 -81.678517 -58.101880 23.073873 -22.464998 1.443952 18.490490 9.141325 2.324187 26.642546 18.304338 3.002752 -132.732175 82.513183 -132.636457 -24.896522 23.736777 -10.481643
0.358899 0.158744 0.996595 86.186485 -1.307793 91.273446 3.670552 5.774433 2.271756 -3.130671 -1.087035 -2.003563 0.365830 9.882590 -3.818273 0.000000 -0.000000 0.000000 -6.527337 -4.995536 -3.938567 0.621612 -1.646323 7.908971 4.873550 -4.970719 -6.989096 0.000000 -0.000000 0.000000 -4.392812 3.319849 -5.319180 2.884167 -3.950463 22.672536 -0.878877 2.214876 -9.058201 -0.052743 1.394427 12.469915 6.795801 0.360514 5.893615 -16.007525 -7.326189 -4.123605 -26.191590 -23.168310 11.346865 69.606563 -81.012910 -58.282741 22.416424 -19.784589 -1.916024 17.578991 9.837054 1.998522 25.742198 19.429372 2.543302 -124.240265 82.721605 -125.778410 -24.582339 21.539829 -12.405770
0.359400 0.159057 0.996723 86.133983 -1.293341 91.145888 3.675016 5.834670 2.473250 -3.134158 -1.328653 -2.133229 0.402862 10.113099 -3.751196 0.000000 -0.000000 0.000000 -6.484316 -4.955903 -3.755088 0.603467 -1.278415 7.749449 4.844823 -5.305100 -6.873431 0.000000 -0.000000 0.000000 -4.301484 3.338864 -5.427142 2.838848 -4.020867 22.330912 -0.900109 2.452452 -8.749462 -0.429971 1.144095 12.365341 7.084472 0.530140 6.192676 -15.210038 -8.131273 -4.437626 -25.534277 -24.196546 10.823624 66.552535 -80.423366 -57.317637 21.305917 -17.833583 -4.841806 16.887516 10.674723 1.722316 24.531701 20.533734 1.940458 -114.764950 82.721934 -117.861848 -24.112161 18.981227 -13.607428
0.359814 0.159304 0.996835 86.133025 -1.268813 91.057420 3.680930 5.841865 2.563431 -3.120945 -1.472462 -2.163265 0.457770 10.242529 -3.720043 0.000000 -0.000000 0.000000 -6.403330 -4.913137 -3.623496 0.531711 -1.055375 7.642937 4.805642 -5.596638 -6.775633 0.000000 -0.000000 0.000000 -4.293865 3.394849 -5.299572 2.853151 -4.022311 21.622138 -0.818030 2.538534 -8.497552 -0.659642 0.850801 12.592593 7.267583 0.750051 6.158409 -14.349281 -8.716906 -4.713376 -25.200266 -25.341792 10.408016 63.110121 -79.735228 -55.388185 20.055558 -16.196491 -7.342938 15.825977 11.249481 1.347418 24.173887 21.635125 1.454466 -102.408178 82.753780 -106.732840 -22.889498 17.364406 -15.230937
0.360162 0.159548 0.996959 86.125786 -1.255969 90.945189 3.677695 5.870192 2.694606 -3.114967 -1.625471 -2.207040 0.474724 10.390789 -3.662888 0.000000 -0.000000 0.000000 -6.370760 -4.909432 -3.467763 0.512288 -0.823524 7.541512 4.805474 -5.865582 -6.684534 0.000000 -0.000000 0.000000 -4.289237 3.419758 -5.359106 2.819352 -4.073378 21.267063 -0.783162 2.667237 -8.216716 -0.837507 0.631843 12.602929 7.478589 0.819775 6.134861 -13.364143 -9.344008 -4.993077 -24.892970 -26.429387 9.894571 59.848170 -78.971845 -53.703904 19.035766 -14.608972 -9.886140 14.939838 12.020037 1.084536 23.684791 22.802579 0.775320 -87.991958 82.297837 -93.512454 -21.239088 15.758741 -16.867107
0.360417 0.159783 0.997193 86.104486 -1.221821 90.782678 3.731868 5.899491 2.922042 -3.168137 -1.767965 -2.335897 0.627547 10.486145 -3.514244 0.000000 -0.000000 0.000000 -6.324625 -4.901231 -3.273831 0.516925 -0.591917 7.453296 4.809482 -6.126863 -6.599343 0.000000 -0.000000 0.000000 -4.227462 3.451207 -5.285863 2.750414 -4.051234 20.831471 -0.721027 2.790243 -7.951362 -0.862127 0.531800 12.870932 7.563135 0.829878 5.833781 -12.346512 -10.097741 -5.031126 -24.775277 -27.551616 9.339909 56.430145 -77.673688 -51.497243 17.697407 -13.223940 -12.769868 13.642422 12.657633 0.682867 24.817217 24.001954 0.386607 -74.026148 80.631971 -79.495183 -18.046407 14.071636 -18.650782
0.360733 0.160072 0.997257 86.143551 -1.216628 90.663571 3.732409 5.909594 3.038008 -3.191028 -1.966233 -2.353108 0.693157 10.651704 -3.489225 0.000000 -0.000000 0.000000 -6.320728 -4.968135 -3.099018 0.537902 -0.311389 7.348159 4.756148 -6.387260 -6.512458 0.000000 -0.000000 0.000000 -4.175857 3.521412 -5.318757 2.694354 -4.103808 20.615627 -0.674635 2.936262 -7.811163 -1.045438 0.344646 12.905878 7.774942 0.944985 5.874668 -11.582632 -10.910090 -5.278042 -24.348209 -28.644997 8.755863 52.017187 -76.476536 -48.805832 16.610612 -11.910897 -14.937385 12.732266 13.449621 0.438607 24.327685 25.212258 -0.242038 -61.029654 79.013047 -67.527400 -16.618171 12.756667 -19.755592
0.360847 0.160414 0.997256 86.195263 -1.215140 90.595020 3.737756 5.973209 3.053155 -3.227347 -2.156719 -2.314436 0.605740 10.786643 -3.509212 0.000000 -0.000000 0.000000 -6.316303 -4.993992 -2.983023 0.551150 -0.086080 7.250355 4.700092 -6.644064 -6.448098 0.000000 -0.000000 0.000000 -4.118328 3.604922 -5.324117 2.657677 -4.127894 20.362703 -0.616608 3.039054 -7.744394 -1.362869 0.142755 13.001658 8.038697 0.993910 5.919874 -10.905454 -11.805305 -5.493107 -23.884032 -29.608624 8.080918 47.197517 -75.092406 -45.576371 15.650783 -11.078332 -16.667575 11.913108 14.349781 0.293231 23.373984 26.233370 -1.144968 -49.686593 77.299725 -57.858587 -15.826200 11.865543 -20.779367
0.360738 0.160598 0.997405 86.244323 -1.187688 90.477461 3.766466 5.998987 3.138738 -3.230850 -2.408172 -2.317418 0.586713 10.955030 -3.463348 0.000000 -0.000000 0.000000 -6.247430 -4.986848 -2.834458 0.527349 0.187117 7.156348 4.656906 -6.976902 -6.388805 0.000000 -0.000000 0.000000 -4.022750 3.670010 -5.233104 2.561069 -4.127611 20.058471 -0.592044 3.196970 -7.633542 -1.530283 -0.046234 13.111118 8.274883 1.013285 5.882429 -10.227022 -12.724602 -5.548190 -23.476585 -30.676740 7.210970 42.496393 -73.382304 -42.195716 14.348483 -10.174334 -18.673415 11.173755 15.134830 0.114529 23.348868 27.237816 -2.044821 -42.704407 74.920819 -51.331025 -13.623811 10.559454 -21.845146
0.360637 0.160759 0.997542 86.320424 -1.192790 90.388231 3.761523 6.082903 3.206729 -3.242198 -2.660059 -2.348456 0.526596 11.056474 -3.424152 0.000000 -0.000000 0.000000 -6.213107 -5.013558 -2.696055 0.494484 0.402225 7.039476 4.606097 -7.250680 -6.337885 0.000000 -0.000000 0.000000 -3.996961 3.730324 -5.167724 2.506416 -4.128626 19.765423 -0.521800 3.281049 -7.453838 -1.653538 -0.160678 13.111283 8.422001 0.997167 5.878544 -9.561072 -13.492666 -5.827253 -23.378244 -31.723973 6.651915 38.575768 -71.388234 -39.777520 13.059683 -9.377087 -20.068166 10.424791 15.927541 -0.150933 22.902788 28.224858 -2.624664 -36.942590 72.403474 -46.576861 -12.304014 9.405140 -22.941345
0.360511 0.160951 0.997651 86.379947 -1.193463 90.283391 3.732605 6.142401 3.302854 -3.207974 -2.920958 -2.408870 0.511817 11.256097 -3.401380 0.000000 -0.000000 0.000000 -6.193692 -5.045320 -2.549455 0.487028 0.674793 6.935489 4.542092 -7.533714 -6.263624 0.000000 -0.000000 0.000000 -3.892493 3.771169 -5.030189 2.414611 -4.168679 19.479543 -0.468141 3.405421 -7.292019 -1.978406 -0.285548 13.183066 8.549385 1.179580 5.685916 -9.077108 -14.339832 -6.131255 -23.002402 -32.558594 5.946658 34.801976 -69.348043 -37.632930 11.878066 -8.610800 -21.664695 9.626735 16.797943 -0.359343 22.165548 29.133515 -3.196291 -32.069220 69.911711 -42.696279 -11.437128 8.289959 -24.350999
0.360326 0.161102 0.997751 86.465344 -1.197117 90.226236 3.720603 6.159184 3.342003 -3.221083 -3.156446 -2.438692 0.496236 11.409850 -3.385647 0.000000 -0.000000 0.000000 -6.179366 -5.078748 -2.476071 0.493542 0.868619 6.896770 4.501014 -7.819002 -6.253992 0.000000 -0.000000 0.000000 -3.851755 3.850154 -4.970064 2.319283 -4.222354 19.355185 -0.413537 3.504157 -7.275215 -2.149979 -0.463093 13.434430 8.680749 1.277880 5.334370 -8.611297 -15.220107 -6.226168 -22.624191 -33.366885 5.080549 31.611368 -67.266211 -36.009421 10.533161 -7.784191 -23.266030 8.842718 17.658216 -0.463704 21.907369 29.820426 -4.022079 -28.744084 67.412019 -40.102050 -9.938848 7.208380 -25.269187
0.360029 0.161253 0.997884 86.597077 -1.199987 90.125083 3.724804 6.246621 3.384863 -3.251241 -3.504708 -2.443195 0.437085 11.596639 -3.406593 0.000000 -0.000000 0.000000 -6.179524 -5.115377 -2.364748 0.537042 1.115149 6.838494 4.427563 -8.181741 -6.249729 0.000000 -0.000000 0.000000 -3.755343 3.914670 -4.720624 2.206033 -4.264341 19.165408 -0.327297 3.526426 -7.282680 -2.374485 -0.534632 13.377978 8.778150 1.456498 5.308651 -8.388965 -16.178031 -6.526109 -21.903370 -33.931083 4.402791 28.416229 -65.135728 -34.310329 9.209187 -7.614660 -24.033216 8.146040 18.674882 -0.620863 20.616861 30.314720 -4.184147 -25.491169 64.830775 -37.950813 -9.579322 6.384087 -27.254742
0.359731 0.161291 0.998050 86.695270 -1.207935 90.053429 3.724577 6.300009 3.441220 -3.272382 -3.774504 -2.524605 0.423789 11.735944 -3.332682 0.000000 -0.000000 0.000000 -6.164128 -5.166884 -2.290284 0.544606 1.341352 6.776617 4.375801 -8.469891 -6.220243 0.000000 -0.000000 0.000000 -3.706303 3.928852 -4.387465 2.080221 -4.286059 18.735079 -0.281758 3.589518 -7.181692 -2.456121 -0.587522 13.421377 8.927883 1.565729 5.253717 -7.970283 -17.011954 -6.730782 -21.380604 -34.628010 3.704114 25.264216 -62.854693 -32.362640 7.670303 -7.435506 -24.561291 7.493932 19.394232 -0.791359 20.089604 30.963640 -4.679972 -22.784548 62.341027 -35.938221 -8.232864 5.551985 -28.110455
0.359468 0.161293 0.998207 86.811719 -1.200369 90.016791 3.745861 6.320819 3.453121 -3.310471 -4.055534 -2.588899 0.400915 11.935611 -3.286621 0.000000 -0.000000 0.000000 -6.108013 -5.206603 -2.235745 0.523310 1.611657 6.696373 4.303900 -8.818858 -6.152658 0.000000 -0.000000 0.000000 -3.663186 3.973960 -4.122516 2.003897 -4.335346 18.366200 -0.221066 3.564747 -7.078110 -2.654496 -0.758951 13.494008 9.103410 1.757075 5.251755 -7.539191 -17.805120 -6.880432 -20.786681 -35.199302 3.138253 22.428233 -60.685671 -30.959018 6.772265 -6.962176 -25.808643 6.863920 20.028149 -0.909655 19.493082 31.681715 -5.229322 -19.885906 59.874503 -33.739853 -7.436820 4.855522 -28.845826
0.359260 0.161244 0.998377 86.918564 -1.191514 89.986677 3.733447 6.364755 3.455384 -3.272438 -4.285159 -2.654797 0.348846 12.057989 -3.229128 0.000000 -0.000000 0.000000 -6.054838 -5.239095 -2.171677 0.530152 1.807807 6.593155 4.217113 -9.115453 -6.106757 0.000000 -0.000000 0.000000 -3.665382 4.011248 -3.960011 1.932423 -4.390205 18.206611 -0.155512 3.569409 -7.016193 -2.827863 -0.878281 13.620915 9.309869 1.842281 5.114897 -7.117801 -18.520830 -7.027374 -20.410335 -35.855170 2.640017 20.116852 -58.497590 -29.960511 5.907228 -6.512363 -26.633374 6.304017 20.669690 -1.020894 19.100340 32.276648 -5.645092 -17.839980 57.445860 -32.349145 -6.857461 4.216637 -29.871005
0.358939 0.161172 0.998393 87.008333 -1.134909 89.992175 3.775832 6.416203 3.392701 -3.245992 -4.494544 -2.667526 0.297746 12.169195 -3.155564 0.000000 -0.000000 0.000000 -5.951711 -5.248278 -2.138982 0.538321 1.987641 6.466458 4.113816 -9.396719 -6.039834 0.000000 -0.000000 0.000000 -3.628964 4.023364 -3.796753 1.909484 -4.423044 18.139681 -0.113253 3.554941 -7.017271 -2.967522 -0.957689 13.528745 9.422509 1.887619 5.173114 -6.687988 -19.162902 -7.165991 -20.230183 -36.460291 2.244390 18.337149 -56.413467 -29.309747 5.277983 -6.084852 -27.517697 5.731749 21.208545 -1.177145 18.789073 32.833672 -5.957040 -16.174726 55.198739 -31.342479 -6.173514 3.576866 -31.161461
0.358718 0.161264 0.998511 87.087185 -1.100901 89.988540 3.791018 6.425596 3.404325 -3.231386 -4.648616 -2.751544 0.303244 12.269489 -3.069068 0.000000 -0.000000 0.000000 -5.886246 -5.263393 -2.086909 0.529989 2.136911 6.350619 4.066151 -9.660236 -5.972867 0.000000 -0.000000 0.000000 -3.522677 3.995934 -3.564369 1.806568 -4.449998 17.925134 -0.106362 3.630701 -6.913993 -3.080986 -0.993868 13.562155 9.485505 1.885625 5.131145 -6.290883 -19.816095 -7.363913 -20.196062 -36.913373 2.285022 17.064659 -54.460267 -29.250735 4.816669 -5.792034 -28.186355 5.088256 21.917076 -1.266890 18.906347 33.016236 -5.541331 -16.097900 53.076939 -31.578197 -5.789529 3.025961 -32.446309
0.358253 0.161216 0.998597 87.123854 -1.064484 90.054583 3.783751 6.474159 3.327323 -3.180186 -4.806310 -2.821005 0.278019 12.393932 -3.056106 0.000000 -0.000000 0.000000 -5.808494 -5.286359 -2.158467 0.515524 2.238065 6.296435 4.018174 -9.847977 -5.883248 0.000000 -0.000000 0.000000 -3.644642 3.949696 -3.273252 1.867742 -4.501030 17.484349 0.026651 3.632385 -6.688425 -3.338801 -1.111653 13.589228 9.664301 2.166407 5.105369 -5.921565 -20.013908 -7.431673 -20.102665 -37.657306 1.845754 15.172225 -52.815096 -28.179508 4.595622 -5.424882 -29.345620 4.908462 21.890051 -1.358143 18.350808 34.215642 -6.453176 -13.788784 51.071727 -29.858648 -5.208230 2.615237 -33.498640
0.357681 0.161068 0.998753 87.046257 -1.016742 90.098508 3.829629 6.526584 3.285843 -3.186412 -4.860574 -2.879118 0.313567 12.479440 -2.933859 0.000000 -0.000000 0.000000 -5.695507 -5.228029 -2.189585 0.478104 2.380228 6.157572 3.989176 -10.051691 -5.749047 0.000000 -0.000000 0.000000 -3.576934 3.949249 -2.901929 1.813038 -4.461498 17.134906 0.066372 3.702386 -6.567736 -3.436890 -1.060337 13.626354 9.668545 2.137536 4.899677 -5.579270 -20.462735 -7.587321 -19.986396 -37.982877 1.919550 14.393395 -51.427622 -28.345882 3.832394 -5.300233 -30.135582 4.226617 22.494670 -1.462467 18.631694 34.405796 -5.970596 -14.294245 49.449171 -30.459943 -4.968738 1.925006 -34.852723
0.357339 0.160837 0.998926 86.938694 -0.981783 90.186615 3.830347 6.601920 3.176313 -3.180524 -4.865100 -2.894442 0.292794 12.590052 -2.816481 0.000000 -0.000000 0.000000 -5.621555 -5.206095 -2.261748 0.475535 2.495181 5.987361 3.986112 -10.175827 -5.552419 0.000000 -0.000000 0.000000 -3.662476 3.987026 -2.811271 1.902291 -4.489773 17.054627 0.170934 3.671873 -6.526857 -3.654984 -1.091188 13.777493 9.758036 2.425523 4.803542 -5.233834 -20.678874 -7.599189 -19.740025 -38.301742 1.487277 13.260385 -50.353999 -28.118594 3.240093 -5.154573 -31.530381 3.878646 22.577468 -1.521144 18.161847 35.341658 -6.724848 -12.909302 47.995918 -29.854396 -4.868416 1.399101 -35.703924
0.357423 0.160613 0.999167 86.825214 -0.997400 90.228953 3.785130 6.623291 3.162339 -3.178001 -4.673959 -2.934196 0.269971 12.550496 -2.672531 0.000000 -0.000000 0.000000 -5.659013 -5.217830 -2.161088 0.511376 2.508587 5.630020 4.032906 -10.197992 -5.353967 0.000000 -0.000000 0.000000 -3.673915 4.031715 -2.810847 1.876701 -4.518329 17.032503 0.172251 3.686954 -6.431012 -3.706932 -0.997319 14.000851 9.857182 2.430936 4.720860 -4.864434 -20.831759 -7.667367 -19.797150 -38.434770 1.424416 13.010885 -49.557690 -29.128819 2.253748 -5.303010 -32.971749 3.349672 22.719249 -1.552928 18.451375 35.864255 -6.630629 -13.173923 47.013633 -30.529650 -4.868734 1.241615 -36.325808
0.357706 0.160445 0.999406 86.768446 -0.994765 90.314694 3.747399 6.530772 3.052708 -3.186124 -4.332384 -2.872464 0.193375 12.442183 -2.594553 0.000000 -0.000000 0.000000 -5.653106 -5.195987 -2.091564 0.480051 2.369126 5.336422 4.102426 -10.071508 -5.177825 0.000000 -0.000000 0.000000 -3.660569 4.060750 -2.892300 1.862765 -4.528586 16.956181 0.122359 3.644999 -6.390516 -3.579736 -0.936649 14.206589 9.869957 2.250613 4.956959 -4.581448 -20.575256 -7.697871 -20.665895 -38.599375 1.857699 13.818062 -49.172921 -30.219025 1.428625 -5.626614 -33.355078 3.166924 22.527060 -1.480509 18.946408 36.044913 -6.304929 -13.929536 47.042542 -31.497315 -4.644134 1.341843 -36.705990
0.358401 0.160094 0.999619 86.720520 -0.994907 90.502117 3.702851 6.448989 2.956484 -3.174432 -3.886206 -2.933065 0.101404 12.122399 -2.542209 0.000000 -0.000000 0.000000 -5.661798 -5.176179 -2.027480 0.422585 1.980119 4.958301 4.249720 -9.653831 -4.973805 0.000000 -0.000000 0.000000 -3.692657 4.061165 -3.206898 1.912379 -4.495972 16.892872 0.059098 3.537516 -6.358299 -3.305020 -0.677616 14.404451 9.647572 2.067854 5.293698 -4.787816 -19.627503 -7.621496 -22.560680 -38.552159 2.711254 16.381208 -50.050536 -31.873552 0.302227 -6.388127 -33.009285 3.720611 21.765138 -1.112509 19.969794 36.218302 -5.811628 -15.949265 48.241057 -33.802219 -4.012628 1.556739 -36.765347
0.359169 0.160269 0.999581 86.684149 -0.968787 90.708807 3.680427 6.278106 2.829797 -3.184750 -3.096395 -2.924660 -0.025804 11.463495 -2.612568 0.000000 -0.000000 0.000000 -5.745287 -5.042503 -1.931017 0.424826 1.135123 4.601878 4.489876 -8.800401 -4.811294 0.000000 -0.000000 0.000000 -3.623211 3.963404 -3.653597 1.964813 -4.394829 17.151361 -0.102064 3.460521 -6.463101 -2.562237 -0.166554 14.642661 9.126162 1.326581 5.360488 -5.806280 -17.897073 -7.508403 -25.780099 -38.102797 4.227361 21.610462 -52.775722 -33.023268 -1.557033 -8.289789 -29.560714 5.222794 20.309009 -0.840950 22.374081 36.042649 -4.988319 -20.531505 50.982738 -37.543482 -2.340738 2.651280 -34.455937
0.361255 0.160079 0.999365 86.678603 -1.062655 91.066937 3.595917 6.147420 2.630178 -3.232035 -2.228863 -2.905401 -0.082689 10.622569 -2.853449 0.000000 -0.000000 0.000000 -5.936818 -5.116482 -1.981555 0.390167 0.028867 4.387096 4.695631 -7.482693 -4.873356 0.000000 -0.000000 0.000000 -3.848540 4.026437 -4.786863 2.141865 -4.334747 18.401258 -0.372786 3.194507 -7.154713 -1.766466 0.343678 14.799680 8.723045 0.663253 5.574764 -8.380674 -15.680092 -7.298676 -28.321592 -36.367282 5.779549 28.425771 -58.418101 -33.776784 -2.913603 -10.435146 -21.807021 8.523612 18.438972 0.057108 23.644167 34.229285 -3.725943 -26.743209 56.811763 -41.478055 -2.957648 5.612057 -27.141264
0.363314 0.160525 0.998829 86.679946 -1.169088 91.401175 3.486090 5.969266 2.412808 -3.298297 -1.437267 -2.804958 -0.009651 9.937772 -3.224898 0.000000 -0.000000 0.000000 -6.240975 -5.234821 -2.115508 0.458693 -1.053685 4.401201 4.914145 -6.199199 -5.104807 0.000000 -0.000000 0.000000 -4.047294 4.089199 -5.975311 2.400270 -4.283015 19.811672 -0.693546 3.028575 -7.617272 -1.279888 0.506242 14.550603 8.371000 0.072415 5.879859 -11.910588 -13.171084 -6.875402 -29.292956 -33.847110 7.065608 36.925517 -65.767779 -36.271250 -2.311563 -12.191466 -13.234139 12.737565 16.021562 1.037654 24.255998 31.187100 -2.858144 -36.243684 65.084760 -47.828080 -5.852505 9.121912 -16.427468
0.365212 0.160898 0.998262 86.808370 -1.228506 91.603546 3.470913 5.716679 2.289232 -3.381138 -0.767998 -2.739290 0.034478 9.390298 -3.508464 0.000000 -0.000000 0.000000 -6.474716 -5.300136 -2.164115 0.543742 -1.998441 4.476225 5.118205 -5.194773 -5.387863 0.000000 -0.000000 0.000000 -4.303182 4.054889 -6.753516 2.789432 -4.158590 20.684317 -0.883263 2.721215 -7.833962 -0.978986 0.583054 14.183022 7.918932 -0.364358 6.317903 -15.259627 -10.298574 -6.515847 -30.239178 -30.853422 9.106954 49.342765 -72.333294 -43.305054 0.294267 -14.735591 -6.204923 16.872672 13.006185 1.480264 25.538560 28.006808 -0.544140 -51.652263 72.236842 -59.061817 -9.496830 13.332231 -9.523243
0.366983 0.160934 0.997780 86.970376 -1.310325 91.925334 3.339758 5.449475 1.933018 -3.285019 -0.080609 -2.440859 0.084509 8.759236 -3.860280 0.000000 -0.000000 0.000000 -6.672616 -5.293078 -2.392108 0.580140 -2.954504 4.707097 5.172171 -4.251939 -5.610393 0.000000 -0.000000 0.000000 -4.563672 4.059200 -7.225015 3.121475 -4.034741 21.227001 -1.048937 2.273292 -8.333600 -0.550088 0.855608 13.957830 7.244684 -0.827471 6.723785 -17.827401 -6.861131 -6.034368 -31.502765 -27.480517 11.167642 68.605856 -77.608254 -58.747132 2.376604 -17.648621 -0.615460 20.500618 9.547340 1.958182 26.794802 24.796335 1.323908 -74.071474 77.997114 -79.620639 -12.116886 17.577856 -5.004382
0.368784 0.160698 0.997430 86.994012 -1.378107 92.095216 3.266619 5.323845 1.875342 -3.281578 0.399736 -2.275962 0.228915 8.258645 -4.147269 0.000000 -0.000000 0.000000 -6.834211 -5.161401 -2.481215 0.572623 -3.703902 5.001824 5.308611 -3.557188 -5.909072 0.000000 -0.000000 0.000000 -4.875868 3.992864 -7.726841 3.462548 -3.895568 21.942750 -1.142161 1.838090 -8.852562 0.088890 1.453392 13.892743 6.341203 -1.434178 7.070115 -19.837559 -3.482670 -5.610908 -33.049310 -23.909960 13.024078 96.056097 -80.253635 -82.991899 2.259045 -20.318205 4.060945 23.457757 6.558959 2.435442 28.677267 21.377627 4.082660 -103.561442 79.600547 -106.577490 -13.268069 21.193392 -2.922432
0.370510 0.160258 0.996952 86.905151 -1.362027 92.158388 3.320015 5.254173 2.045378 -3.318364 0.708718 -2.277583 0.368979 7.946834 -4.330964 0.000000 -0.000000 0.000000 -6.932003 -5.030504 -2.401317 0.640240 -4.184923 5.158020 5.445383 -3.066008 -6.124804 0.000000 -0.000000 0.000000 -5.159216 3.865674 -8.562969 3.789737 -3.838782 23.016684 -1.231305 1.646401 -9.087101 0.734446 2.049549 13.644879 5.517038 -1.944620 7.501943 -21.355738 -0.372112 -5.305394 -34.988123 -20.761431 14.424061 121.239933 -80.830443 -106.029119 -0.111058 -21.705662 6.984102 25.671438 4.091047 2.918603 30.623414 18.200422 6.513487 -123.723991 79.336616 -125.142772 -13.047376 22.868536 -1.549659
0.371928 0.159807 0.993521 86.708296 -1.367239 91.923760 3.664423 4.853284 1.843315 -3.684995 0.556304 -0.938898 0.681496 7.525619 -5.507758 0.000000 -0.000000 0.000000 -7.091802 -4.695630 -2.764040 0.817739 -4.290894 6.835254 5.436058 -2.454536 -7.518723 0.000000 -0.000000 0.000000 -5.264229 3.621062 -8.426207 4.049507 -3.576581 22.394760 -1.312353 1.465613 -8.694890 1.570442 2.556887 12.615090 4.594714 -2.369409 7.903026 -22.848882 2.900384 -4.694750 -37.814045 -17.420234 15.470111 137.633209 -80.304125 -120.860167 -3.020552 -21.847872 5.456936 27.621303 1.434184 3.006392 34.331271 14.604004 8.563542 -128.714567 79.114133 -128.220291 -8.468691 22.835101 -2.082083
0.373015 0.159412 0.990643 86.586470 -1.343579 91.633262 4.056511 4.560482 1.723363 -4.040923 -0.061956 0.254018 0.949558 7.372164 -6.611088 0.000000 -0.000000 0.000000 -7.173416 -4.447048 -2.922272 1.009195 -4.051762 8.150063 5.309037 -2.249984 -8.816401 0.000000 -0.000000 0.000000 -5.226103 3.390024 -8.142335 4.211677 -3.343984 21.481573 -1.437161 1.350560 -8.170458 2.286711 3.013440 11.535923 3.832196 -2.663737 8.338642 -23.819275 5.409858 -4.023016 -40.378371 -14.452585 16.586527 144.910179 -80.028871 -127.621613 -3.059770 -20.791966 2.826483 28.571572 -0.326180 3.143876 38.164427 10.743501 11.224267 -127.268763 79.392714 -126.206529 -9.950257 21.068599 -4.849205
0.373588 0.159280 0.987813 86.371438 -1.325139 91.393017 4.464938 4.312185 1.611939 -4.452278 -0.622367 1.267724 1.211920 7.306137 -7.655850 0.000000 -0.000000 0.000000 -7.292932 -4.272910 -3.228818 1.297734 -3.669845 9.471959 5.155312 -2.038767 -10.033937 0.000000 -0.000000 0.000000 -5.191778 3.309514 -7.819365 4.360181 -3.038558 20.408072 -1.47061
gitextract_e3i9npyq/ ├── .gitignore ├── CHANGELOG.md ├── CODE_OF_CONDUCT.md ├── CONTRIBUTING.md ├── LICENSE ├── README.md ├── amass_char_info.py ├── bullet/ │ ├── __init__.py │ ├── bullet_client.py │ ├── bullet_render.py │ └── bullet_utils.py ├── data/ │ ├── character/ │ │ └── amass.urdf │ ├── motion/ │ │ ├── amass_hierarchy.bvh │ │ ├── cmu/ │ │ │ ├── expert0/ │ │ │ │ └── test.bvh │ │ │ ├── expert1/ │ │ │ │ └── test.bvh │ │ │ ├── expert2/ │ │ │ │ └── test.bvh │ │ │ ├── expert3/ │ │ │ │ └── test.bvh │ │ │ ├── expert4/ │ │ │ │ └── test.bvh │ │ │ ├── expert5/ │ │ │ │ └── test.bvh │ │ │ ├── expert6/ │ │ │ │ └── test.bvh │ │ │ ├── expert7/ │ │ │ │ └── test.bvh │ │ │ └── moe/ │ │ │ └── test.bvh │ │ └── test.bvh │ └── spec/ │ ├── spec_env_humanoid_imitation_expert0.yaml │ ├── spec_env_humanoid_imitation_expert1.yaml │ ├── spec_env_humanoid_imitation_expert2.yaml │ ├── spec_env_humanoid_imitation_expert3.yaml │ ├── spec_env_humanoid_imitation_expert4.yaml │ ├── spec_env_humanoid_imitation_expert5.yaml │ ├── spec_env_humanoid_imitation_expert6.yaml │ ├── spec_env_humanoid_imitation_expert7.yaml │ ├── spec_env_humanoid_imitation_moe.yaml │ └── test_env_humanoid_imitation.yaml ├── env_humanoid_base.py ├── env_humanoid_imitation.py ├── env_humanoid_tracking.py ├── env_renderer.py ├── render_module.py ├── rllib_driver.py ├── rllib_env_imitation.py ├── rllib_model_custom_torch.py ├── sim_agent.py └── sim_obstacle.py
SYMBOL INDEX (242 symbols across 13 files)
FILE: bullet/bullet_client.py
class BulletClient (line 11) | class BulletClient(object):
method __init__ (line 14) | def __init__(self, connection_mode=pybullet.DIRECT, options=""):
method __del__ (line 21) | def __del__(self):
method __getattr__ (line 28) | def __getattr__(self, name):
FILE: bullet/bullet_render.py
function glTransform (line 13) | def glTransform(quaternion):
class RenderOptionBody (line 17) | class RenderOptionBody():
method __init__ (line 18) | def __init__(self):
class RenderOptionJoint (line 29) | class RenderOptionJoint():
method __init__ (line 30) | def __init__(self):
class RenderOption (line 40) | class RenderOption():
method __init__ (line 41) | def __init__(self):
function render_joint (line 45) | def render_joint(joint, option):
function get_wing_info (line 107) | def get_wing_info(world, bid1, bid2, ntype):
function render_wing_force_one_segment (line 147) | def render_wing_force_one_segment(wing_info, force, option):
function render_wing_one_segment (line 155) | def render_wing_one_segment(wing_info, option):
function render_wing (line 163) | def render_wing(world, option):
function get_visual_aspects (line 179) | def get_visual_aspects(skel):
function set_visual_aspect (line 186) | def set_visual_aspect(skel, vas):
function get_visual_aspects_body (line 194) | def get_visual_aspects_body(body):
function set_visual_aspect_body (line 200) | def set_visual_aspect_body(body, vas):
function render_body (line 207) | def render_body(body, option, global_coord=True):
function render_skeleton (line 236) | def render_skeleton(skel, option):
function render_world (line 250) | def render_world(world, option=None):
function render_geom_bounding_box (line 271) | def render_geom_bounding_box(geom_type, geom_size, color=[0, 0, 0, 1], T...
function render_geom (line 284) | def render_geom(geom_type, geom_size, color=[0.5, 0.5, 0.5, 1.0], T=cons...
function render_geom_info (line 300) | def render_geom_info(geom_type, geom_size, scale=1.0, color=[0, 0, 0, 1]...
function render_links (line 319) | def render_links(pb_client, model):
function render_joints (line 326) | def render_joints(pb_client, model):
function render_joint_geoms (line 357) | def render_joint_geoms(pb_client, model, radius=0.025, color=[0.5, 0.5, ...
function render_model (line 377) | def render_model(pb_client,
function render_contacts (line 429) | def render_contacts(pb_client, model, scale_h=0.0005, scale_r=0.01, colo...
FILE: bullet/bullet_utils.py
function set_base_pQvw (line 12) | def set_base_pQvw(pb_client, body_id, p, Q, v=None, w=None):
function get_base_pQvw (line 22) | def get_base_pQvw(pb_client, body_id):
function get_link_pQvw (line 35) | def get_link_pQvw(pb_client, body_id, indices=None):
function get_joint_torques (line 63) | def get_joint_torques(pb_client, body_id, indices=None):
function set_joint_pv (line 82) | def set_joint_pv(pb_client, body_id, indices, ps, vs):
function get_joint_pv (line 94) | def get_joint_pv(pb_client, body_id, indices=None):
function get_state_all (line 122) | def get_state_all(pb_client, body_id):
function set_state_all (line 131) | def set_state_all(pb_client, body_id, states):
function get_mass (line 148) | def get_mass(pb_client, body_id, indices=None):
function compute_com_and_com_vel (line 160) | def compute_com_and_com_vel(pb_client, body_id, indices=None):
function _compute_com_and_com_vel (line 186) | def _compute_com_and_com_vel(pb_client, body_id, indices=None, masses=No...
function compute_PD_forces (line 223) | def compute_PD_forces(pb_client,
FILE: env_humanoid_base.py
class Env (line 22) | class Env(metaclass=ABCMeta):
class ActionMode (line 23) | class ActionMode(Enum):
method from_string (line 27) | def from_string(cls, string):
class StateChoice (line 31) | class StateChoice(Enum):
method from_string (line 35) | def from_string(cls, string):
class EarlyTermChoice (line 39) | class EarlyTermChoice(Enum):
method from_string (line 51) | def from_string(cls, string):
method __init__ (line 58) | def __init__(self, config):
method action_range (line 202) | def action_range(self, idx):
method dim_action (line 205) | def dim_action(self, idx):
method dim_state (line 208) | def dim_state(self, idx):
method dim_state_body (line 211) | def dim_state_body(self, idx):
method dim_state_task (line 214) | def dim_state_task(self, idx):
method set_learning_info (line 217) | def set_learning_info(self, info):
method update_learning_info (line 220) | def update_learning_info(self, info):
method agent_avg_position (line 223) | def agent_avg_position(self, agents=None):
method agent_ave_facing_position (line 227) | def agent_ave_facing_position(self, agents=None):
method throw_obstacle (line 231) | def throw_obstacle(self):
method split_action (line 236) | def split_action(self, action):
method compute_target_pose (line 246) | def compute_target_pose(self, idx, action):
method compute_init_pose_vel (line 289) | def compute_init_pose_vel(self, add_noise):
method callback_reset_prev (line 306) | def callback_reset_prev(self, info):
method callback_reset_after (line 312) | def callback_reset_after(self, info):
method reset (line 318) | def reset(self, info):
method callback_step_prev (line 348) | def callback_step_prev(self):
method callback_step_after (line 351) | def callback_step_after(self):
method print_log_in_step (line 354) | def print_log_in_step(self):
method step (line 363) | def step(self, action):
method state (line 432) | def state(self, idx):
method state_body (line 443) | def state_body(self, idx):
method _state_body (line 449) | def _state_body(self,
method state_task (line 506) | def state_task(self, idx):
method reward_data (line 513) | def reward_data(self, idx):
method reward_max (line 520) | def reward_max(self):
method reward_min (line 527) | def reward_min(self):
method return_max (line 533) | def return_max(self, gamma):
method return_min (line 540) | def return_min(self, gamma):
method get_task_error (line 548) | def get_task_error(self, idx, data_prev, data_next, action):
method reward (line 555) | def reward(self, idx, data_prev, data_next, action):
method get_reward_names (line 567) | def get_reward_names(self, fn_def):
method pretty_print_rew_info (line 581) | def pretty_print_rew_info(self, rew_info, prefix=str()):
method compute_reward (line 589) | def compute_reward(self, error, fn_def):
method inspect_end_of_episode_task (line 639) | def inspect_end_of_episode_task(self):
method inspect_end_of_episode_per_agent (line 646) | def inspect_end_of_episode_per_agent(self, idx):
method get_ground_height (line 666) | def get_ground_height(self):
method get_elapsed_time (line 672) | def get_elapsed_time(self):
method set_elapsed_time (line 678) | def set_elapsed_time(self, time):
method render (line 681) | def render(self, rm):
FILE: env_humanoid_imitation.py
function load_motions (line 19) | def load_motions(motion_files, skel, char_info, verbose):
class Env (line 59) | class Env(env_humanoid_base.Env):
method __init__ (line 60) | def __init__(self, config):
method create (line 77) | def create(self):
method callback_reset_prev (line 166) | def callback_reset_prev(self, info):
method callback_reset_after (line 181) | def callback_reset_after(self, info):
method callback_step_after (line 186) | def callback_step_after(self):
method print_log_in_step (line 194) | def print_log_in_step(self):
method compute_init_pose_vel (line 204) | def compute_init_pose_vel(self, info):
method state_body (line 224) | def state_body(self, idx):
method state_task (line 234) | def state_task(self, idx):
method state_imitation (line 258) | def state_imitation(self,
method reward_data (line 300) | def reward_data(self, idx):
method reward_max (line 317) | def reward_max(self):
method reward_min (line 320) | def reward_min(self):
method get_task_error (line 323) | def get_task_error(self, idx, data_prev, data_next, action):
method inspect_end_of_episode_task (line 407) | def inspect_end_of_episode_task(self):
method inspect_end_of_episode_per_agent (line 414) | def inspect_end_of_episode_per_agent(self, idx):
method get_ground_height (line 418) | def get_ground_height(self):
method get_current_time (line 421) | def get_current_time(self):
method sample_ref_motion (line 424) | def sample_ref_motion(self):
function arg_parser (line 444) | def arg_parser():
class EnvRenderer (line 449) | class EnvRenderer(er.EnvRenderer):
method __init__ (line 450) | def __init__(self, **kwargs):
method reset (line 454) | def reset(self):
method one_step (line 456) | def one_step(self):
method extra_render_callback (line 459) | def extra_render_callback(self):
method extra_idle_callback (line 464) | def extra_idle_callback(self):
method extra_keyboard_callback (line 469) | def extra_keyboard_callback(self, key):
FILE: env_humanoid_tracking.py
class Env (line 30) | class Env(object):
method __init__ (line 35) | def __init__(self,
method setup_physics_scene (line 105) | def setup_physics_scene(self, sim_char_file, char_info, ref_motion_sca...
method create_ground (line 122) | def create_ground(self):
method check_collision (line 145) | def check_collision(self, body_id1, body_id2, link_id1=None, link_id2=...
method check_falldown (line 166) | def check_falldown(self, agent, plane_id=None):
method is_sim_div (line 179) | def is_sim_div(self, agent):
method step (line 183) | def step(self, target_poses=[]):
method reset (line 201) | def reset(self, time=0.0, poses=None, vels=None, pb_state_id=None):
method add_noise_to_pose_vel (line 226) | def add_noise_to_pose_vel(self, agent, pose, vel=None, return_as_copie...
method render (line 274) | def render(self, rm, ground_height=0.0):
class EnvRenderer (line 341) | class EnvRenderer(er.EnvRenderer):
method __init__ (line 342) | def __init__(self, **kwargs):
method reset (line 346) | def reset(self):
method one_step (line 348) | def one_step(self):
method extra_render_callback (line 351) | def extra_render_callback(self):
method extra_idle_callback (line 353) | def extra_idle_callback(self):
method extra_keyboard_callback (line 358) | def extra_keyboard_callback(self, key):
FILE: env_renderer.py
function axis_to_str (line 9) | def axis_to_str(axis):
class EnvRenderer (line 19) | class EnvRenderer(glut_viewer.Viewer):
method __init__ (line 20) | def __init__(self,
method save_screen (line 28) | def save_screen(self, dir, name):
method render_ground (line 30) | def render_ground(self,
method extra_keyboard_callback (line 48) | def extra_keyboard_callback(self, key):
method extra_render_callback (line 50) | def extra_render_callback(self):
method extra_idle_callback (line 52) | def extra_idle_callback(self):
method extra_overlay_callback (line 54) | def extra_overlay_callback(self):
method keyboard_callback (line 56) | def keyboard_callback(self, key):
method render_callback (line 62) | def render_callback(self):
method idle_callback (line 68) | def idle_callback(self):
method overlay_callback (line 70) | def overlay_callback(self):
method update_target_pos (line 73) | def update_target_pos(self, pos, ignore_x=False, ignore_y=False, ignor...
FILE: render_module.py
function initialize (line 80) | def initialize():
FILE: rllib_driver.py
function arg_parser (line 12) | def arg_parser():
function adjust_config_for_loading (line 134) | def adjust_config_for_loading(config, alg):
function adjust_config (line 142) | def adjust_config(config, alg):
FILE: rllib_env_imitation.py
class HumanoidImitation (line 17) | class HumanoidImitation(gym.Env):
method __init__ (line 18) | def __init__(self, env_config):
method state (line 45) | def state(self):
method reset (line 48) | def reset(self, start_time=None, add_noise=None):
method step (line 57) | def step(self, action):
class EnvRenderer (line 63) | class EnvRenderer(er.EnvRenderer):
method __init__ (line 64) | def __init__(self, trainer, **kwargs):
method one_step (line 70) | def one_step(self):
method extra_render_callback (line 74) | def extra_render_callback(self):
method extra_overlay_callback (line 79) | def extra_overlay_callback(self):
method extra_idle_callback (line 98) | def extra_idle_callback(self):
method extra_keyboard_callback (line 103) | def extra_keyboard_callback(self, key):
function default_cam (line 142) | def default_cam():
function config_override (line 150) | def config_override(spec):
FILE: rllib_model_custom_torch.py
class AppendLogStd (line 22) | class AppendLogStd(nn.Module):
method __init__ (line 26) | def __init__(self, type, init_val, dim):
method forward (line 39) | def forward(self, x):
class FC (line 53) | class FC(nn.Module):
method __init__ (line 57) | def __init__(self, size_in, size_out, hiddens, activations,
method forward (line 81) | def forward(self, x):
class FullyConnectedPolicy (line 84) | class FullyConnectedPolicy(TorchModelV2, nn.Module):
method __init__ (line 99) | def __init__(self, obs_space, action_space, num_outputs, model_config,
method forward (line 166) | def forward(self, input_dict, state, seq_lens):
method value_function (line 176) | def value_function(self):
method save_policy_weights (line 180) | def save_policy_weights(self, file):
class MOEPolicyBase (line 183) | class MOEPolicyBase(TorchModelV2, nn.Module):
method __init__ (line 235) | def __init__(self, obs_space, action_space, num_outputs, model_config,
method forward (line 322) | def forward(self, input_dict, state, seq_lens):
method value_function (line 326) | def value_function(self):
method gate_function (line 330) | def gate_function(self):
method num_experts (line 333) | def num_experts(self):
class MOEPolicyAdditive (line 336) | class MOEPolicyAdditive(MOEPolicyBase):
method __init__ (line 337) | def __init__(self, obs_space, action_space, num_outputs, model_config,
method forward (line 343) | def forward(self, input_dict, state, seq_lens):
class MOEPolicyMultiplicative (line 358) | class MOEPolicyMultiplicative(MOEPolicyBase):
method __init__ (line 359) | def __init__(self, obs_space, action_space, num_outputs, model_config,
method forward (line 365) | def forward(self, input_dict, state, seq_lens):
FILE: sim_agent.py
class SimAgent (line 16) | class SimAgent(object):
class Actuation (line 20) | class Actuation(Enum):
method from_string (line 29) | def from_string(cls, string):
method __init__ (line 39) | def __init__(self,
method get_name (line 137) | def get_name(self):
method split_joint_variables (line 140) | def split_joint_variables(self, states, joint_indices):
method setup_dynamics (line 159) | def setup_dynamics(self):
method setup_kinematics (line 189) | def setup_kinematics(self):
method change_visual_color (line 209) | def change_visual_color(self, color):
method get_num_dofs (line 213) | def get_num_dofs(self):
method get_num_joint (line 216) | def get_num_joint(self):
method get_joint_type (line 219) | def get_joint_type(self, idx):
method get_joint_axis (line 222) | def get_joint_axis(self, idx):
method get_joint_dofs (line 225) | def get_joint_dofs(self, idx):
method get_root_height_from_ground (line 228) | def get_root_height_from_ground(self, ground_height=0.0):
method get_root_state (line 233) | def get_root_state(self):
method get_root_transform (line 236) | def get_root_transform(self):
method set_root_transform (line 240) | def set_root_transform(self, T):
method get_facing_transform (line 244) | def get_facing_transform(self, ground_height=0.0):
method get_facing_position (line 251) | def get_facing_position(self, ground_height=0.0):
method get_facing_direction (line 255) | def get_facing_direction(self):
method get_facing_direction_position (line 259) | def get_facing_direction_position(self, ground_height=0.0):
method project_to_ground (line 278) | def project_to_ground(self, v):
method get_link_states (line 281) | def get_link_states(self, indices=None):
method get_joint_states (line 284) | def get_joint_states(self, indices=None):
method set_pose_by_xform (line 287) | def set_pose_by_xform(self, xform):
method set_pose (line 326) | def set_pose(self, pose, vel=None):
method get_pose (line 381) | def get_pose(self, skel):
method array_to_pose_data (line 403) | def array_to_pose_data(self, skel, data, T_root_ref=None):
method arrary_to_pose (line 429) | def arrary_to_pose(self, skel, data, T_root_ref=None):
method save_states (line 433) | def save_states(self):
method restore_states (line 436) | def restore_states(self, states):
method get_com_and_com_vel (line 439) | def get_com_and_com_vel(self):
method get_joint_torques (line 442) | def get_joint_torques(self):
method get_joint_weights (line 445) | def get_joint_weights(self, skel):
method interaction_mesh_samples (line 457) | def interaction_mesh_samples(self):
method inverse_kinematics (line 477) | def inverse_kinematics(self, indices, positions):
method actuate (line 494) | def actuate(self, pose=None, vel=None, torque=None):
FILE: sim_obstacle.py
function filter_list_by_index (line 17) | def filter_list_by_index(old_list, pos, positive=True):
class Shape (line 23) | class Shape(Enum):
class Obstacle (line 27) | class Obstacle(object):
method __init__ (line 28) | def __init__(self, name, duration, shape, mass, size, p, Q, v, w):
class ObstacleManager (line 47) | class ObstacleManager(object):
method __init__ (line 48) | def __init__(self, pb_client, dt, v_up_env, visualization=False):
method clear (line 58) | def clear(self):
method launch (line 62) | def launch(self, obstacle):
method throw (line 88) | def throw(self, pos_target, num=1, duration=2.0, shape=Shape.BOX, vel=...
method update (line 110) | def update(self):
method render (line 122) | def render(self):
Condensed preview — 43 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (1,068K chars).
[
{
"path": ".gitignore",
"chars": 811,
"preview": "# Byte-compiled / optimized / DLL files\n__pycache__/\n*.py[cod]\n*$py.class\n\n# C extensions\n*.so\n\n# Distribution / packagi"
},
{
"path": "CHANGELOG.md",
"chars": 14,
"preview": "Initial commit"
},
{
"path": "CODE_OF_CONDUCT.md",
"chars": 3231,
"preview": "# Open Source Code of Conduct\n\n## Our Pledge\n\nIn the interest of fostering an open and welcoming environment, we as cont"
},
{
"path": "CONTRIBUTING.md",
"chars": 1342,
"preview": "# Contributing to ScaDiver\nWe want to make contributing to this project as easy and transparent as\npossible.\n\n## Pull Re"
},
{
"path": "LICENSE",
"chars": 1534,
"preview": "BSD License\n\nFor ScaDiver software\n\nCopyright (c) Facebook, Inc. and its affiliates. All rights reserved.\n\nRedistributio"
},
{
"path": "README.md",
"chars": 11613,
"preview": "# ScaDiver\n\n## Introduction\n\n[](https://www.youtube.com/watch?v=QnIwwAKX5H4&"
},
{
"path": "amass_char_info.py",
"chars": 8237,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport collections\nimport numpy as np\n\n''' \nThe up direction of the "
},
{
"path": "bullet/__init__.py",
"chars": 50,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates."
},
{
"path": "bullet/bullet_client.py",
"chars": 1096,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates. \n\n'''\nThis class was slightly edited from the code existing in one of"
},
{
"path": "bullet/bullet_render.py",
"chars": 15946,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates. \n\nfrom OpenGL.GL import *\nfrom OpenGL.GLUT import *\nfrom OpenGL.GLU i"
},
{
"path": "bullet/bullet_utils.py",
"chars": 8349,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport numpy as np\nfrom fairmotion.ops import quaternion\n\n'''\nBullet"
},
{
"path": "data/character/amass.urdf",
"chars": 16079,
"preview": "<?xml version=\"1.0\"?>\n <!-- Copyright (c) Facebook, Inc. and its affiliates. --> \n <robot name=\"amass_male\">\n\n <li"
},
{
"path": "data/motion/amass_hierarchy.bvh",
"chars": 6179,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert0/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert1/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert2/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert3/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert4/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert5/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert6/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/expert7/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/cmu/moe/test.bvh",
"chars": 9714,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/motion/test.bvh",
"chars": 719294,
"preview": "HIERARCHY\nROOT root\n{\n\tOFFSET 0.000000 0.000000 0.000000\n\tCHANNELS 6 Xposition Yposition Zposition Zrotation Yrotation X"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert0.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert0\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert1.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert1\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert2.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert2\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert3.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert3\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert4.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert4\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert5.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert5\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert6.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert6\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_expert7.yaml",
"chars": 3512,
"preview": "run: PPO\nname: expert7\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/experts/\ncheckpoint_freq:"
},
{
"path": "data/spec/spec_env_humanoid_imitation_moe.yaml",
"chars": 5328,
"preview": "run: PPO\nname: moe\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/cmu/moe/\ncheckpoint_freq: 100\nche"
},
{
"path": "data/spec/test_env_humanoid_imitation.yaml",
"chars": 3423,
"preview": "run: PPO\nname: test\nlocal_dir: /home/jungdam/Research/opensource/ScaDiver/data/learning/test/\ncheckpoint_freq: 100\ncheck"
},
{
"path": "env_humanoid_base.py",
"chars": 28397,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport os\n\nimport numpy as np\nimport copy\nfrom enum import Enum\nfrom"
},
{
"path": "env_humanoid_imitation.py",
"chars": 20145,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport os\n\nimport numpy as np\nimport pickle\nimport gzip\nimport re\nim"
},
{
"path": "env_humanoid_tracking.py",
"chars": 15822,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport os\n\n''' \nThis forces the environment to use only 1 cpu when r"
},
{
"path": "env_renderer.py",
"chars": 2710,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport numpy as np\nimport render_module as rm\nfrom fairmotion.viz im"
},
{
"path": "render_module.py",
"chars": 2354,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport numpy as np\n\nviewer = None\ncamera = None\ngl_render = None\nbul"
},
{
"path": "rllib_driver.py",
"chars": 6369,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport argparse\nimport os\nimport yaml\n\nimport ray\n\nfrom ray import t"
},
{
"path": "rllib_env_imitation.py",
"chars": 5908,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport copy\nimport numpy as np\nimport argparse\nimport random\n\nimport"
},
{
"path": "rllib_model_custom_torch.py",
"chars": 13669,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nimport numpy as np\nimport os\n\nfrom ray.rllib.models.m"
},
{
"path": "sim_agent.py",
"chars": 29817,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport numpy as np\nfrom enum import Enum\n\nfrom bullet import bullet_"
},
{
"path": "sim_obstacle.py",
"chars": 5370,
"preview": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom enum import Enum\nimport numpy as np\n\nfrom fairmotion.ops import"
}
]
About this extraction
This page contains the full source code of the facebookresearch/ScaDiver GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 43 files (1.0 MB), approximately 469.1k tokens, and a symbol index with 242 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.