forked from tonyzhaozh/act
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
0 parents
commit c09015d
Showing
46 changed files
with
5,149 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,90 @@ | ||
# ACT: Action Chunking with Transformers | ||
|
||
### Project Website: https://tonyzhaozh.github.io/aloha/ | ||
|
||
This repo contains the implementation of ACT, together with 2 simulated environments: | ||
Transfer Cube and Bimanual Insertion. You can train and evaluate ACT in sim (tested) or real (ongoing). | ||
|
||
|
||
### Repo Structure | ||
- ``imitate_episodes.py`` Train and Evaluate ACT | ||
- ``policy.py`` An adaptor for ACT policy | ||
- ``detr`` Model definitions of ACT, modified from DETR | ||
- ``sim_env.py`` Mujoco + DM_Control environments with joint space control | ||
- ``ee_sim_env.py`` Mujoco + DM_Control environments with EE space control | ||
- ``scripted_policy.py`` Scripted policies for sim environments | ||
- ``constants.py`` Constants shared across files | ||
- ``utils.py`` Utils such as data loading and helper functions | ||
- ``visualize_episodes.py`` Save videos from a .hdf5 dataset | ||
|
||
|
||
### Installation | ||
|
||
conda create -n aloha python=3.8 | ||
conda activate aloha | ||
pip install torchvision | ||
pip install torch | ||
pip install pyquaternion | ||
pip install pyyaml | ||
pip install rospkg | ||
pip install pexpect | ||
pip install mujoco | ||
pip install dm_control | ||
pip install opencv-python | ||
pip install matplotlib | ||
pip install einops | ||
pip install packaging | ||
pip install h5py | ||
pip install h5py_cache | ||
cd act/detr && pip install -e . | ||
|
||
### Example Usages | ||
|
||
To set up a new terminal, run: | ||
|
||
conda activate aloha | ||
cd <path to act repo> | ||
|
||
### Simulated experiments | ||
|
||
We use ``transfer_cube`` task in the examples below. Another option is ``insertion``. | ||
To generated 50 episodes of scripted data, run: | ||
|
||
python3 record_sim_episodes.py \ | ||
--task_name transfer_cube \ | ||
--dataset_dir <data save dir> \ | ||
--num_episodes 50 | ||
|
||
To can add the flag ``--onscreen_render`` to see real-time rendering. | ||
To visualize the episode after it is collected, run | ||
|
||
python3 visualize_episodes.py --dataset_dir <data save dir> --episode_idx 0 | ||
|
||
To train ACT: | ||
|
||
# Transfer Cube task | ||
python3 imitate_episodes.py \ | ||
--dataset_dir <data save dir> \ | ||
--ckpt_dir <ckpt dir> \ | ||
--policy_class ACT --kl_weight 10 --chunk_size 100 --hidden_dim 256 --batch_size 8 --dim_feedforward 2048 \ | ||
--task_name transfer_cube --seed 0 \ | ||
--temporal_agg \ | ||
--num_epochs 1000 --lr 1e-4 | ||
|
||
# Bimanual Insertion task | ||
python3 imitate_episodes.py \ | ||
--dataset_dir <data save dir> \ | ||
--ckpt_dir <ckpt dir> \ | ||
--policy_class ACT --kl_weight 10 --chunk_size 100 --hidden_dim 256 --batch_size 8 --dim_feedforward 2048 \ | ||
--task_name insertion --seed 0 \ | ||
--temporal_agg \ | ||
--num_epochs 2000 --lr 1e-5 | ||
|
||
To evaluate the policy, run the same command but add ``--eval``. The success rate | ||
should be around 85% for transfer cube, and around 50% for insertion. | ||
Videos will be saved to ``<ckpt_dir>`` for each rollout. | ||
You can also add ``--onscreen_render`` to see real-time rendering during evaluation. | ||
|
||
|
||
|
||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,59 @@ | ||
<mujoco> | ||
<include file="scene.xml"/> | ||
<include file="vx300s_dependencies.xml"/> | ||
|
||
<equality> | ||
<weld body1="mocap_left" body2="vx300s_left/gripper_link" solref="0.01 1" solimp=".25 .25 0.001" /> | ||
<weld body1="mocap_right" body2="vx300s_right/gripper_link" solref="0.01 1" solimp=".25 .25 0.001" /> | ||
</equality> | ||
|
||
|
||
<worldbody> | ||
<include file="vx300s_left.xml" /> | ||
<include file="vx300s_right.xml" /> | ||
|
||
<body mocap="true" name="mocap_left" pos="0.095 0.50 0.425"> | ||
<site pos="0 0 0" size="0.003 0.003 0.03" type="box" name="mocap_left_site1" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.003 0.03 0.003" type="box" name="mocap_left_site2" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.03 0.003 0.003" type="box" name="mocap_left_site3" rgba="1 0 0 1"/> | ||
</body> | ||
<body mocap="true" name="mocap_right" pos="-0.095 0.50 0.425"> | ||
<site pos="0 0 0" size="0.003 0.003 0.03" type="box" name="mocap_right_site1" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.003 0.03 0.003" type="box" name="mocap_right_site2" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.03 0.003 0.003" type="box" name="mocap_right_site3" rgba="1 0 0 1"/> | ||
</body> | ||
|
||
<body name="peg" pos="0.2 0.5 0.05"> | ||
<joint name="red_peg_joint" type="free" frictionloss="0.01" /> | ||
<inertial pos="0 0 0" mass="0.05" diaginertia="0.002 0.002 0.002" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.06 0.01 0.01" type="box" name="red_peg" rgba="1 0 0 1" /> | ||
</body> | ||
|
||
<body name="socket" pos="-0.2 0.5 0.05"> | ||
<joint name="blue_socket_joint" type="free" frictionloss="0.01" /> | ||
<inertial pos="0 0 0" mass="0.05" diaginertia="0.002 0.002 0.002" /> | ||
<!-- <geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.06 0.01 0.01" type="box" name="red_peg_ref" rgba="1 0 0 1" />--> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 0 -0.02" size="0.06 0.018 0.002" type="box" name="socket-1" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 0 0.02" size="0.06 0.018 0.002" type="box" name="socket-2" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 0.02 0" size="0.06 0.002 0.018" type="box" name="socket-3" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 -0.02 0" size="0.06 0.002 0.018" type="box" name="socket-4" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.04 0.01 0.01" type="box" name="pin" rgba="1 0 0 1" /> | ||
</body> | ||
|
||
</worldbody> | ||
|
||
<actuator> | ||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_left/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_left/right_finger" kp="200" user="1"/> | ||
|
||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_right/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_right/right_finger" kp="200" user="1"/> | ||
|
||
</actuator> | ||
|
||
<keyframe> | ||
<key qpos="0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0.2 0.5 0.05 1 0 0 0 -0.2 0.5 0.05 1 0 0 0"/> | ||
</keyframe> | ||
|
||
|
||
</mujoco> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,48 @@ | ||
<mujoco> | ||
<include file="scene.xml"/> | ||
<include file="vx300s_dependencies.xml"/> | ||
|
||
<equality> | ||
<weld body1="mocap_left" body2="vx300s_left/gripper_link" solref="0.01 1" solimp=".25 .25 0.001" /> | ||
<weld body1="mocap_right" body2="vx300s_right/gripper_link" solref="0.01 1" solimp=".25 .25 0.001" /> | ||
</equality> | ||
|
||
|
||
<worldbody> | ||
<include file="vx300s_left.xml" /> | ||
<include file="vx300s_right.xml" /> | ||
|
||
<body mocap="true" name="mocap_left" pos="0.095 0.50 0.425"> | ||
<site pos="0 0 0" size="0.003 0.003 0.03" type="box" name="mocap_left_site1" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.003 0.03 0.003" type="box" name="mocap_left_site2" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.03 0.003 0.003" type="box" name="mocap_left_site3" rgba="1 0 0 1"/> | ||
</body> | ||
<body mocap="true" name="mocap_right" pos="-0.095 0.50 0.425"> | ||
<site pos="0 0 0" size="0.003 0.003 0.03" type="box" name="mocap_right_site1" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.003 0.03 0.003" type="box" name="mocap_right_site2" rgba="1 0 0 1"/> | ||
<site pos="0 0 0" size="0.03 0.003 0.003" type="box" name="mocap_right_site3" rgba="1 0 0 1"/> | ||
</body> | ||
|
||
<body name="box" pos="0.2 0.5 0.05"> | ||
<joint name="red_box_joint" type="free" frictionloss="0.01" /> | ||
<inertial pos="0 0 0" mass="0.05" diaginertia="0.002 0.002 0.002" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.02 0.02 0.02" type="box" name="red_box" rgba="1 0 0 1" /> | ||
</body> | ||
|
||
</worldbody> | ||
|
||
<actuator> | ||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_left/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_left/right_finger" kp="200" user="1"/> | ||
|
||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_right/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_right/right_finger" kp="200" user="1"/> | ||
|
||
</actuator> | ||
|
||
<keyframe> | ||
<key qpos="0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0.2 0.5 0.05 1 0 0 0"/> | ||
</keyframe> | ||
|
||
|
||
</mujoco> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,53 @@ | ||
<mujoco> | ||
<include file="scene.xml"/> | ||
<include file="vx300s_dependencies.xml"/> | ||
<worldbody> | ||
<include file="vx300s_left.xml" /> | ||
<include file="vx300s_right.xml" /> | ||
|
||
<body name="peg" pos="0.2 0.5 0.05"> | ||
<joint name="red_peg_joint" type="free" frictionloss="0.01" /> | ||
<inertial pos="0 0 0" mass="0.05" diaginertia="0.002 0.002 0.002" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.06 0.01 0.01" type="box" name="red_peg" rgba="1 0 0 1" /> | ||
</body> | ||
|
||
<body name="socket" pos="-0.2 0.5 0.05"> | ||
<joint name="blue_socket_joint" type="free" frictionloss="0.01" /> | ||
<inertial pos="0 0 0" mass="0.05" diaginertia="0.002 0.002 0.002" /> | ||
<!-- <geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.06 0.01 0.01" type="box" name="red_peg_ref" rgba="1 0 0 1" />--> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 0 -0.02" size="0.06 0.018 0.002" type="box" name="socket-1" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 0 0.02" size="0.06 0.018 0.002" type="box" name="socket-2" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 0.02 0" size="0.06 0.002 0.018" type="box" name="socket-3" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.05 0.001" pos="0 -0.02 0" size="0.06 0.002 0.018" type="box" name="socket-4" rgba="0 0 1 1" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.04 0.01 0.01" type="box" name="pin" rgba="1 0 0 1" /> | ||
</body> | ||
|
||
</worldbody> | ||
|
||
<actuator> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_left/waist" kp="800" user="1" forcelimited="true" forcerange="-150 150"/> | ||
<position ctrllimited="true" ctrlrange="-1.85005 1.25664" joint="vx300s_left/shoulder" kp="1600" user="1" forcelimited="true" forcerange="-300 300"/> | ||
<position ctrllimited="true" ctrlrange="-1.76278 1.6057" joint="vx300s_left/elbow" kp="800" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_left/forearm_roll" kp="10" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-1.8675 2.23402" joint="vx300s_left/wrist_angle" kp="50" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_left/wrist_rotate" kp="20" user="1"/> | ||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_left/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_left/right_finger" kp="200" user="1"/> | ||
|
||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_right/waist" kp="800" user="1" forcelimited="true" forcerange="-150 150"/> | ||
<position ctrllimited="true" ctrlrange="-1.85005 1.25664" joint="vx300s_right/shoulder" kp="1600" user="1" forcelimited="true" forcerange="-300 300"/> | ||
<position ctrllimited="true" ctrlrange="-1.76278 1.6057" joint="vx300s_right/elbow" kp="800" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_right/forearm_roll" kp="10" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-1.8675 2.23402" joint="vx300s_right/wrist_angle" kp="50" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_right/wrist_rotate" kp="20" user="1"/> | ||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_right/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_right/right_finger" kp="200" user="1"/> | ||
|
||
</actuator> | ||
|
||
<keyframe> | ||
<key qpos="0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0.2 0.5 0.05 1 0 0 0 -0.2 0.5 0.05 1 0 0 0"/> | ||
</keyframe> | ||
|
||
|
||
</mujoco> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,42 @@ | ||
<mujoco> | ||
<include file="scene.xml"/> | ||
<include file="vx300s_dependencies.xml"/> | ||
<worldbody> | ||
<include file="vx300s_left.xml" /> | ||
<include file="vx300s_right.xml" /> | ||
|
||
<body name="box" pos="0.2 0.5 0.05"> | ||
<joint name="red_box_joint" type="free" frictionloss="0.01" /> | ||
<inertial pos="0 0 0" mass="0.05" diaginertia="0.002 0.002 0.002" /> | ||
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0 0 0" size="0.02 0.02 0.02" type="box" name="red_box" rgba="1 0 0 1" /> | ||
</body> | ||
|
||
</worldbody> | ||
|
||
<actuator> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_left/waist" kp="800" user="1" forcelimited="true" forcerange="-150 150"/> | ||
<position ctrllimited="true" ctrlrange="-1.85005 1.25664" joint="vx300s_left/shoulder" kp="1600" user="1" forcelimited="true" forcerange="-300 300"/> | ||
<position ctrllimited="true" ctrlrange="-1.76278 1.6057" joint="vx300s_left/elbow" kp="800" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_left/forearm_roll" kp="10" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-1.8675 2.23402" joint="vx300s_left/wrist_angle" kp="50" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_left/wrist_rotate" kp="20" user="1"/> | ||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_left/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_left/right_finger" kp="200" user="1"/> | ||
|
||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_right/waist" kp="800" user="1" forcelimited="true" forcerange="-150 150"/> | ||
<position ctrllimited="true" ctrlrange="-1.85005 1.25664" joint="vx300s_right/shoulder" kp="1600" user="1" forcelimited="true" forcerange="-300 300"/> | ||
<position ctrllimited="true" ctrlrange="-1.76278 1.6057" joint="vx300s_right/elbow" kp="800" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_right/forearm_roll" kp="10" user="1" forcelimited="true" forcerange="-100 100"/> | ||
<position ctrllimited="true" ctrlrange="-1.8675 2.23402" joint="vx300s_right/wrist_angle" kp="50" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-3.14158 3.14158" joint="vx300s_right/wrist_rotate" kp="20" user="1"/> | ||
<position ctrllimited="true" ctrlrange="0.021 0.057" joint="vx300s_right/left_finger" kp="200" user="1"/> | ||
<position ctrllimited="true" ctrlrange="-0.057 -0.021" joint="vx300s_right/right_finger" kp="200" user="1"/> | ||
|
||
</actuator> | ||
|
||
<keyframe> | ||
<key qpos="0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0 -0.96 1.16 0 -0.3 0 0.024 -0.024 0.2 0.5 0.05 1 0 0 0"/> | ||
</keyframe> | ||
|
||
|
||
</mujoco> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,39 @@ | ||
<mujocoinclude> | ||
<!-- <option timestep='0.0025' iterations="50" tolerance="1e-10" solver="Newton" jacobian="dense" cone="elliptic"/>--> | ||
|
||
<asset> | ||
<mesh file="tabletop.stl" name="tabletop" scale="0.001 0.001 0.001"/> | ||
</asset> | ||
|
||
<visual> | ||
<map fogstart="1.5" fogend="5" force="0.1" znear="0.1"/> | ||
<quality shadowsize="4096" offsamples="4"/> | ||
<headlight ambient="0.4 0.4 0.4"/> | ||
</visual> | ||
|
||
<worldbody> | ||
<light castshadow="false" directional='true' diffuse='.3 .3 .3' specular='0.3 0.3 0.3' pos='-1 -1 1' | ||
dir='1 1 -1'/> | ||
<light directional='true' diffuse='.3 .3 .3' specular='0.3 0.3 0.3' pos='1 -1 1' dir='-1 1 -1'/> | ||
<light castshadow="false" directional='true' diffuse='.3 .3 .3' specular='0.3 0.3 0.3' pos='0 1 1' | ||
dir='0 -1 -1'/> | ||
|
||
<body name="table" pos="0 .6 0"> | ||
<geom group="1" mesh="tabletop" pos="0 0 0" type="mesh" conaffinity="1" contype="1" name="table" rgba="0.2 0.2 0.2 1" /> | ||
</body> | ||
<body name="midair" pos="0 .6 0.2"> | ||
<site pos="0 0 0" size="0.01" type="sphere" name="midair" rgba="1 0 0 0"/> | ||
</body> | ||
|
||
<camera name="left_pillar" pos="-0.5 0.2 0.6" fovy="78" mode="targetbody" target="table"/> | ||
<camera name="right_pillar" pos="0.5 0.2 0.6" fovy="78" mode="targetbody" target="table"/> | ||
<camera name="main" pos="0 -0.2 0.4" fovy="78" mode="targetbody" target="midair"/> | ||
<camera name="top" pos="0 0.6 0.8" fovy="78" mode="targetbody" target="table"/> | ||
<camera name="angle" pos="0 0 0.6" fovy="78" mode="targetbody" target="table"/> | ||
<camera name="front_close" pos="0 0.2 0.4" fovy="78" mode="targetbody" target="vx300s_left/camera_focus"/> | ||
|
||
</worldbody> | ||
|
||
|
||
|
||
</mujocoinclude> |
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,17 @@ | ||
<mujocoinclude> | ||
<compiler angle="radian" inertiafromgeom="auto" inertiagrouprange="4 5"/> | ||
<asset> | ||
<mesh name="vx300s_1_base" file="vx300s_1_base.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_2_shoulder" file="vx300s_2_shoulder.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_3_upper_arm" file="vx300s_3_upper_arm.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_4_upper_forearm" file="vx300s_4_upper_forearm.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_5_lower_forearm" file="vx300s_5_lower_forearm.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_6_wrist" file="vx300s_6_wrist.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_7_gripper" file="vx300s_7_gripper.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_8_gripper_prop" file="vx300s_8_gripper_prop.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_9_gripper_bar" file="vx300s_9_gripper_bar.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_10_gripper_finger_left" file="vx300s_10_custom_finger_left.stl" scale="0.001 0.001 0.001" /> | ||
<mesh name="vx300s_10_gripper_finger_right" file="vx300s_10_custom_finger_right.stl" scale="0.001 0.001 0.001" /> | ||
</asset> | ||
|
||
</mujocoinclude> |
Oops, something went wrong.