mujoco
mujoco copied to clipboard
Help with composite objects
Hi,
I'm a robotics engineer and I'm trying to use MuJoCo to simulate composite materials with the Viper X manipulator from Interbotix. I am fairly new to the MuJoCo simulator and facing some issues. Following are the details-
The idea is to do some pick-and-place kinda actions on deformable objects with simple geometry like spheres and ellipsoids using a manipulator. I am considering "composite objects" to simulate deformable objects. When I bring either the manipulator or the composite object in the simulation, everything goes fine, but when I try to bring both, I get an error saying
Error: mass and inertia of moving bodies must be larger than mjMINVAL
Following is the MJCF structure I am using
Master file (simulation.xml)
<mujoco model="simulation">
<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" />
</equality>
<worldbody>
<!--Works fine if used standalone, throws error when used simultaneously/-->
<include file="manipulator.xml" />
<include file="composite.xml" />
<body mocap="true" name="mocap_left" pos="0.469 0.88 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.469 0.88 0.425"> <!--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>
</worldbody>
</mujoco>
Manipulator (manipulator.xml)
<mujocoinclude>
<body name="vx300s_left" pos="-0.469 0.325 0">
<geom quat="0 0 0 1" type="mesh" mesh="vx300s_1_base" name="vx300s_left/1_base" contype="0" conaffinity="0"/>
<body name="vx300s_left/shoulder_link" pos="0 0 0.079">
<inertial pos="0.000259233 -3.3552e-06 0.0116129" quat="-0.476119 0.476083 0.52279 0.522826" mass="0.798614" diaginertia="0.00120156 0.00113744 0.0009388" />
<joint name="vx300s_left/waist" pos="0 0 0" axis="0 0 1" limited="true" range="-3.14158 3.14158" frictionloss="50" />
<geom pos="0 0 -0.003" quat="0 0 0 1" type="mesh" mesh="vx300s_2_shoulder" name="vx300s_left/2_shoulder" />
<body name="vx300s_left/upper_arm_link" pos="0 0 0.04805">
<inertial pos="0.0206949 4e-10 0.226459" quat="0 0.0728458 0 0.997343" mass="0.792592" diaginertia="0.00911338 0.008925 0.000759317" />
<joint name="vx300s_left/shoulder" pos="0 0 0" axis="1 0 0" limited="true" range="-1.85005 1.25664" frictionloss="60" />
<geom quat="0 0 0 1" type="mesh" mesh="vx300s_3_upper_arm" name="vx300s_left/3_upper_arm"/>
<body name="vx300s_left/upper_forearm_link" pos="0 0.05955 0.3">
<inertial pos="0.105723 0 0" quat="-0.000621631 0.704724 0.0105292 0.709403" mass="0.322228" diaginertia="0.00144107 0.00134228 0.000152047" />
<joint name="vx300s_left/elbow" pos="0 0 0" axis="1 0 0" limited="true" range="-1.76278 1.6057" frictionloss="60" />
<geom quat="0.7071 0 0 0.7071" type="mesh" mesh="vx300s_4_upper_forearm" name="vx300s_left/4_upper_forearm" />
<body name="vx300s_left/lower_forearm_link" pos="0 0.2 0">
<inertial pos="0.0513477 0.00680462 0" quat="-0.702604 -0.0796724 -0.702604 0.0796724" mass="0.414823" diaginertia="0.0005911 0.000546493 0.000155707" />
<joint name="vx300s_left/forearm_roll" pos="0 0 0" axis="0 1 0" limited="true" range="-3.14158 3.14158" frictionloss="30" />
<geom quat="0 .7071 .7071 0" type="mesh" mesh="vx300s_5_lower_forearm" name="vx300s_left/5_lower_forearm"/>
<body name="vx300s_left/wrist_link" pos="0 0.1 0">
<inertial pos="0.046743 -7.6652e-06 0.010565" quat="-0.00100191 0.544586 0.0026583 0.8387" mass="0.115395" diaginertia="5.45707e-05 4.63101e-05 4.32692e-05" />
<joint name="vx300s_left/wrist_angle" pos="0 0 0" axis="1 0 0" limited="true" range="-1.8675 2.23402" frictionloss="30" />
<geom quat="0 0 0 1" type="mesh" mesh="vx300s_6_wrist" name="vx300s_left/6_wrist" />
<body name="vx300s_left/gripper_link" pos="0 0.069744 0">
<body name="vx300s_left/camera_focus" pos="0 0.15 0.01">
<site pos="0 0 0" size="0.01" type="sphere" name="left_cam_focus" rgba="0 0 1 0"/>
</body>
<site pos="0 0.15 0" size="0.003 0.003 0.03" type="box" name="cali_left_site1" rgba="0 0 1 0"/>
<site pos="0 0.15 0" size="0.003 0.03 0.003" type="box" name="cali_left_site2" rgba="0 0 1 0"/>
<site pos="0 0.15 0" size="0.03 0.003 0.003" type="box" name="cali_left_site3" rgba="0 0 1 0"/>
<camera name="left_wrist" pos="0 -0.1 0.16" fovy="20" mode="targetbody" target="vx300s_left/camera_focus"/>
<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="vx300s_left/wrist_rotate" pos="0 0 0" axis="0 1 0" limited="true" range="-3.14158 3.14158" frictionloss="30" />
<geom pos="0 -0.02 0" quat="0 0 0 1" type="mesh" mesh="vx300s_7_gripper" name="vx300s_left/7_gripper" />
<geom pos="0 -0.020175 0" quat="0 0 0 1" type="mesh" mesh="vx300s_9_gripper_bar" name="vx300s_left/9_gripper_bar" />
<body name="vx300s_left/gripper_prop_link" pos="0 0.0485 0">
<inertial pos="0.002378 2.85e-08 0" quat="0 0 0.897698 0.440611" mass="0.008009" diaginertia="4.2979e-06 2.8868e-06 1.5314e-06" />
<!-- <joint name="vx300s_left/gripper" pos="0 0 0" axis="1 0 0" frictionloss="30" />-->
<geom pos="0 -0.0685 0" quat="0 0 0 1" type="mesh" mesh="vx300s_8_gripper_prop" name="vx300s_left/8_gripper_prop" />
</body>
<body name="vx300s_left/left_finger_link" pos="0 0.0687 0">
<inertial pos="0.017344 -0.0060692 0" quat="0.449364 0.449364 -0.54596 -0.54596" mass="0.034796" diaginertia="2.48003e-05 1.417e-05 1.20797e-05" />
<joint name="vx300s_left/left_finger" pos="0 0 0" axis="1 0 0" type="slide" limited="true" range="0.021 0.057" frictionloss="30" />
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="-0.05 0 0" quat=".5 -.5 .5 .5" type="mesh" mesh="vx300s_10_gripper_finger_left" name="vx300s_left/10_left_gripper_finger"/>
</body>
<body name="vx300s_left/right_finger_link" pos="0 0.0687 0">
<inertial pos="0.017344 0.0060692 0" quat="0.44937 -0.44937 0.545955 -0.545955" mass="0.034796" diaginertia="2.48002e-05 1.417e-05 1.20798e-05" />
<joint name="vx300s_left/right_finger" pos="0 0 0" axis="1 0 0" type="slide" limited="true" range="-0.057 -0.021" frictionloss="30" />
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001" pos="0.05 0 0" euler="-1.57 0 1.57" type="mesh" mesh="vx300s_10_gripper_finger_right" name="vx300s_left/10_right_gripper_finger"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</mujocoinclude>
Composite material (composite.xml)
<mujocoinclude>
<body name="l1" pos="0 .575 0.0055">
<freejoint/>
<composite prefix="A" type="ellipsoid" count="7 7 4" spacing="0.005">
<skin texcoord="true" material="matsponge" rgba=".7 .7 .7 1"/>
<geom type="sphere" size=".005" mass="0.5" rgba=".8 .2 .1 1"/>
<joint kind="main" solreffix="0.03 1" solimpfix="0 .1 .01"/>
</composite>
</body>
</mujocoinclude>
Here are the screenshots of how things going:
While launching only manipulator
while launching only composite object (very small as I am planning for many small objects to pick)
Error when including both in the simulation
I have tried changing parameters like mass, geoms, type etc. I tried looking in the documentation but was not able to find anything useful.
I hope my query is clear. Hoping to get a solution.
Regards, Rohit
Would someone please help me with this? I am not finding a way out of it and confused.
This is odd. We'll take a look.
Thanks for responding. Did you find the cause, I'm still struggling.
I'm having the same problem, what can I do to fix it?
Can you please try to simplify the model and get to a minimum example that produces the issue?