Skip to content

Commit

Permalink
Update Aloha cameras with specs from Omnivision OV9782.
Browse files Browse the repository at this point in the history
Data from https://www.ovt.com/products/ov09782-ga4a/

Note that the camera positions in MuJoCo correspond to the location of the sensor so `pos` should be updated in the XML if the camera positions do not reflect the locations of the real camera sensors.

The resulting vertical FOV is 65 degrees as per https://www.intelrealsense.com/wp-content/uploads/2022/03/Intel-RealSense-D400-Series-Datasheet-March-2022.pdf (table on page 42)

PiperOrigin-RevId: 654045392
Change-Id: I2c5430d59e9908d0382f08b0596c0d957e46cb68
  • Loading branch information
quagla authored and copybara-github committed Jul 19, 2024
1 parent bf50a5b commit 3d593a3
Show file tree
Hide file tree
Showing 4 changed files with 27 additions and 23 deletions.
6 changes: 4 additions & 2 deletions aloha/aloha.xml
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,8 @@
<geom class="collision" pos="0 -0.03525 -0.0227" quat="0 -1 0 -1" type="mesh" mesh="vx300s_7_gripper_wrist_mount"/>
<geom class="visual" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<geom class="collision" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<camera name="wrist_cam_left" pos="0 -0.0824748 -0.0095955" fovy="58" mode="fixed" euler="2.70525955359 0 0"/>
<camera name="wrist_cam_left" pos="0 -0.0824748 -0.0095955" mode="fixed" euler="2.70525955359 0 0"
focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"/>
<body name="left/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
<inertial pos="0.0143478 -0.0284791 0.0122897" quat="0.535486 0.458766 -0.450407 0.547651"
mass="0.0862937" diaginertia="5.86848e-05 4.46887e-05 1.8397e-05"/>
Expand Down Expand Up @@ -236,7 +237,8 @@
<geom class="collision" pos="0 -0.03525 -0.0227" quat="0 -0.707107 0 -0.707107" type="mesh" mesh="vx300s_7_gripper_wrist_mount"/>
<geom class="visual" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<geom class="collision" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<camera name="wrist_cam_right" pos="0 -0.0824748 -0.0095955" fovy="58" mode="fixed" euler="2.70525955359 0 0"/>
<camera name="wrist_cam_right" pos="0 -0.0824748 -0.0095955" mode="fixed" euler="2.70525955359 0 0"
focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"/>
<body name="right/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
<inertial pos="0.0143478 -0.0284791 0.0122897" quat="0.535486 0.458766 -0.450407 0.547651"
mass="0.0862937" diaginertia="5.86848e-05 4.46887e-05 1.8397e-05"/>
Expand Down
28 changes: 14 additions & 14 deletions aloha/mjx_aloha.patch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
--- aloha.xml 2024-04-29 19:01:00.000000000 +0100
+++ mjx_aloha.xml 2024-04-29 18:58:32.000000000 +0100
--- aloha.xml 2024-07-18 11:14:18.000000000 +0100
+++ mjx_aloha.xml 2024-07-18 13:16:54.000000000 +0100
@@ -1,7 +1,7 @@
<mujoco model="aloha">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
Expand Down Expand Up @@ -73,10 +73,10 @@
<geom class="visual" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<geom class="collision" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
+ <geom class="primitive_collision" type="capsule" fromto="0.055 0 0.015 -0.055 0 0.015" size="0.03" />
<camera name="wrist_cam_left" pos="0 -0.0824748 -0.0095955" fovy="58" mode="fixed" euler="2.70525955359 0 0"/>
<camera name="wrist_cam_left" pos="0 -0.0824748 -0.0095955" mode="fixed" euler="2.70525955359 0 0"
focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"/>
<body name="left/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
<inertial pos="0.0143478 -0.0284791 0.0122897" quat="0.535486 0.458766 -0.450407 0.547651"
@@ -156,8 +163,10 @@
@@ -157,8 +164,10 @@
<joint name="left/left_finger" class="left_finger"/>
<geom pos="0.0141637 0.0211727 0.06" class="visual" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
Expand All @@ -88,7 +88,7 @@
<geom name="left/left_g0" pos="0.013 -0.0892 0.0268" class="sphere_collision"/>
<geom name="left/left_g1" pos="0.0222 -0.0892 0.0268" class="sphere_collision"/>
<geom name="left/left_g2" pos="0.0182 -0.0845 0.0266" class="sphere_collision"/>
@@ -169,8 +178,10 @@
@@ -170,8 +179,10 @@
<joint name="left/right_finger" class="right_finger"/>
<geom pos="0.0141637 -0.0211727 0.0597067" class="visual" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
Expand All @@ -100,7 +100,7 @@
<geom name="left/right_g0" pos="0.013 0.0892 0.0268" class="sphere_collision"/>
<geom name="left/right_g1" pos="0.0222 0.0892 0.0268" class="sphere_collision"/>
<geom name="left/right_g2" pos="0.0182 0.0845 0.0266" class="sphere_collision"/>
@@ -224,7 +235,7 @@
@@ -225,7 +236,7 @@
<inertial pos="0.0395662 -2.56311e-07 0.00400649" quat="0.62033 0.619916 -0.339682 0.339869"
mass="0.251652" diaginertia="0.000689546 0.000650316 0.000468142"/>
<joint name="right/wrist_rotate" class="wrist_rotate"/>
Expand All @@ -109,15 +109,15 @@
<body name="right/gripper_base" euler="0 1.57 -1.57" pos="0.035 0 0">
<inertial pos="0.000182154 -0.0341589 -0.0106026" quat="0.435286 0.557074 -0.551539 0.442718"
mass="0.42158" diaginertia="0.00110438 0.000790537 0.000469727"/>
@@ -236,6 +247,7 @@
@@ -237,6 +248,7 @@
<geom class="collision" pos="0 -0.03525 -0.0227" quat="0 -0.707107 0 -0.707107" type="mesh" mesh="vx300s_7_gripper_wrist_mount"/>
<geom class="visual" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<geom class="collision" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
+ <geom class="primitive_collision" type="capsule" fromto="0.055 0 0.015 -0.055 0 0.015" size="0.03" />
<camera name="wrist_cam_right" pos="0 -0.0824748 -0.0095955" fovy="58" mode="fixed" euler="2.70525955359 0 0"/>
<camera name="wrist_cam_right" pos="0 -0.0824748 -0.0095955" mode="fixed" euler="2.70525955359 0 0"
focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"/>
<body name="right/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
<inertial pos="0.0143478 -0.0284791 0.0122897" quat="0.535486 0.458766 -0.450407 0.547651"
@@ -243,8 +255,10 @@
@@ -245,8 +257,10 @@
<joint name="right/left_finger" class="left_finger"/>
<geom pos="0.0141637 0.0211727 0.06" class="visual" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
Expand All @@ -129,7 +129,7 @@
<geom name="right/left_g0" pos="0.013 -0.0892 0.0268" class="sphere_collision"/>
<geom name="right/left_g1" pos="0.0222 -0.0892 0.0268" class="sphere_collision"/>
<geom name="right/left_g2" pos="0.0182 -0.0845 0.0266" class="sphere_collision"/>
@@ -256,8 +270,10 @@
@@ -258,8 +272,10 @@
<joint name="right/right_finger" class="right_finger"/>
<geom pos="0.0141637 -0.0211727 0.0597067" class="visual" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
Expand All @@ -141,11 +141,11 @@
<geom name="right/right_g0" pos="0.013 0.0892 0.0268" class="sphere_collision"/>
<geom name="right/right_g1" pos="0.0222 0.0892 0.0268" class="sphere_collision"/>
<geom name="right/right_g2" pos="0.0182 0.0845 0.0266" class="sphere_collision"/>
@@ -283,6 +299,5 @@
@@ -285,6 +301,5 @@
<joint joint1="right/left_finger" joint2="right/right_finger" polycoef="0 1 0 0 0"/>
</equality>

- <include file="joint_position_actuators.xml"/>
+ <include file="mjx_filtered_cartesian_actuators.xml"/>
- <include file="keyframe_ctrl.xml"/>
+ <include file="mjx_filtered_cartesian_actuators.xml"/>
</mujoco>
10 changes: 5 additions & 5 deletions aloha/mjx_scene.patch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
--- scene.xml 2024-04-22 03:09:14.000000000 -0700
+++ mjx_scene.xml 2024-06-13 15:56:08.000000000 -0700
--- scene.xml 2024-07-18 11:10:27.000000000 +0100
+++ mjx_scene.xml 2024-07-18 13:17:11.000000000 +0100
@@ -1,7 +1,13 @@
<mujoco model="aloha_scene">
<compiler meshdir="assets" texturedir="assets"/>
Expand Down Expand Up @@ -33,6 +33,6 @@
<geom mesh="tablelegs" material="table" class="visual" pos="0 0 -0.75" quat="1 0 0 1"/>
- <geom name="table" pos="0 0 -0.1009" size="0.61 0.37 0.1" type="box" class="collision"/>
+ <geom name="table" pos="0 0 0.0008" size="0.61 0.37 0.1" type="plane" class="collision" contype="1" conaffinity="1"/>
<camera name="overhead_cam" pos="0 -0.303794 1.02524" fovy="58" mode="fixed" quat="0.976332 0.216277 0 0"/>
<camera name="worms_eye_cam" pos="0 -0.377167 0.0316055" fovy="58" mode="fixed" quat="0.672659 0.739953 0 0"/>
<geom class="frame" pos="0.44 -0.361 1.03" quat="0 1 0 1" mesh="extrusion_2040_880"/>
<camera name="overhead_cam" focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"
pos="0 -0.303794 1.02524" mode="fixed" quat="0.976332 0.216277 0 0"/>
<camera name="worms_eye_cam" focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"
6 changes: 4 additions & 2 deletions aloha/scene.xml
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,10 @@
<geom mesh="tabletop" material="table" class="visual" pos="0 0 -0.75" quat="1 0 0 1"/>
<geom mesh="tablelegs" material="table" class="visual" pos="0 0 -0.75" quat="1 0 0 1"/>
<geom name="table" pos="0 0 -0.1009" size="0.61 0.37 0.1" type="box" class="collision"/>
<camera name="overhead_cam" pos="0 -0.303794 1.02524" fovy="58" mode="fixed" quat="0.976332 0.216277 0 0"/>
<camera name="worms_eye_cam" pos="0 -0.377167 0.0316055" fovy="58" mode="fixed" quat="0.672659 0.739953 0 0"/>
<camera name="overhead_cam" focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"
pos="0 -0.303794 1.02524" mode="fixed" quat="0.976332 0.216277 0 0"/>
<camera name="worms_eye_cam" focal="1.93e-3 1.93e-3" resolution="1296 816" sensorsize="3896e-6 2453e-6"
pos="0 -0.377167 0.0316055" mode="fixed" quat="0.672659 0.739953 0 0"/>
<geom class="frame" pos="0.44 -0.361 1.03" quat="0 1 0 1" mesh="extrusion_2040_880"/>
<geom class="frame" pos="0.44 -0.371 0.61" quat="1 0 -1 0" mesh="extrusion_150"/>
<geom class="frame" pos="0 -0.303794 1.02524" quat="0 0 0.976296 0.21644" mesh="d405_solid"/>
Expand Down

0 comments on commit 3d593a3

Please sign in to comment.