Closed antonioaa1979 closed 1 year ago
As suggested in https://github.com/deepmind/mujoco/issues/197, you could potentially use weld constraints for this. If you have kinematic chain A-B-C, you could create A-B1 and B2-C. Then you could disable collisions (and rendering) for B2, perhaps even reducing its mass to near 0 as well. After welding B1 and B2 together you would expect similar behaviour to the original A-B-C. If the break does not need to be at a joint then the issue is simpler.
Then you can deactivate the weld between B1 and B2 by changing eq_active
in the model when your condition of choice happens, which would allow them to fall apart.
Thank you for quick reply, i will try with your suggestion
@antonioaa1979 have you been able to get it working? I've been trying to bring this idea into life, without much success. See below my attempt
<mujoco model="BrittleStarMorphology">
<compiler angle="radian"/>
<default>
<default class="/">
<geom contype="1" conaffinity="0" condim="3"/>
</default>
</default>
<worldbody>
<body name="main">
<geom type="box" size="1 1 1"/>
<body name="A" pos="1.5 0.5 0.5">
<joint pos="-1.5 0.5 0.5" name="A_in_plane" class="/" type="hinge" axis="0 0 1" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
<joint pos="-1.5 0.5 0.5" name="A_out_plane" class="/" type="hinge" axis="0 -1 0" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
<geom type="box" size="0.5 0.5 0.5" rgba="1 0 0 1"/>
</body>
<body name="B" pos="2.5 0.5 0.5">
<geom type="box" size="0.5 0.5 0.5" rgba="0 1 0 1"/>
<joint name="B_in_plane" pos="-0.5 0.5 0.5" class="/" type="hinge" axis="0 0 1" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
<joint name="B_out_plane" pos="-0.5 0.5 0.5" class="/" type="hinge" axis="0 -1 0" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
</body>
</body>
<camera name="side_camera" class="/" mode="track" pos="0 -2 2.5" quat="0.93969262078590843 0.34202014332566871 0 0"/>
</worldbody>
<equality>
<weld body1="A" body2="B" anchor="2.5 0.5 0.5"/>
</equality>
<actuator>
</actuator>
<sensor>
</sensor>
</mujoco>
After adding the weld constraint, I'd expect for body B to move when body A is moved using body A's joints, but I don't see this happen in the mujoco viewer. Any help would be greatly appreciated.
Hi, long time since i did this, but i indeed followed the recommendation of the first answer from @Balint-H, in python code:
self.physics.named.model.eq_active[0] = 0
Should be data.eq_active[]
. The attribute in model is model.eq_active0[]
, i.e. the value of data.eq_active
upon load.
I see I didn't quite explain my problem properly: I am having difficulties transforming the A-B-C chain into A-B1 and B2-C. Following XML is an arm segment from a larger model on which I'm trying to get the body breaking simulation working.
<mujoco model="BrittleStarMorphology">
<compiler angle="radian"/>
<default>
<default class="/">
<geom contype="1" conaffinity="0" condim="3"/>
</default>
</default>
<worldbody>
<body name="A" pos="0.125 0 0" euler="0 0 0">
<geom name="arm_0_segment_0_capsule" class="/" type="capsule" size="0.025000000000000001 0.037499999999999999" rgba="0.49019607843137253 0.70980392156862748 0.6588235294117647 1" pos="0.0625 0 0" euler="0 1.5707963267948966 0"/>
<geom name="arm_0_segment_0_connector" class="/" type="sphere" contype="0" conaffinity="0" size="0.012500000000000001" rgba="0.34901960784313724 0.34901960784313724 0.34901960784313724 1" pos="0 0 0"/>
<joint name="arm_0_segment_0_in_plane_joint" class="/" type="hinge" axis="0 0 1" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="0"/>
<joint name="arm_0_segment_0_out_of_plane_joint" class="/" type="hinge" axis="0 -1 0" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
<body name="B" pos="0.125 0 0" euler="0 0 0">
<geom name="arm_0_segment_1_capsule" class="/" type="capsule" size="0.018750000000000003 0.025000000000000001" rgba="0.49019607843137253 0.70980392156862748 0.6588235294117647 1" pos="0.043750000000000004 0 0" euler="0 1.5707963267948966 0"/>
<geom name="arm_0_segment_1_connector" class="/" type="sphere" contype="0" conaffinity="0" size="0.0093750000000000014" rgba="0.34901960784313724 0.34901960784313724 0.34901960784313724 1" pos="0 0 0"/>
<joint name="arm_0_segment_1_in_plane_joint" pos="0 0 0" class="/" type="hinge" axis="0 0 1" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
<joint name="arm_0_segment_1_out_of_plane_joint" class="/" type="hinge" axis="0 -1 0" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
</body>
</body>
<camera name="side_camera" class="/" mode="track" pos="0 -2 2.5" quat="0.93969262078590843 0.34202014332566871 0 0"/>
</worldbody>
<equality>
</equality>
<actuator>
</actuator>
<sensor>
</sensor>
</mujoco>
Following is my attempt at recreating the abovementioned chain:
<mujoco model="BrittleStarMorphology">
<compiler angle="radian"/>
<default>
<default class="/">
<geom contype="1" conaffinity="0" condim="3"/>
</default>
</default>
<worldbody>
<body name="A" pos="0.125 0 0" euler="0 0 0">
<geom name="arm_0_segment_0_capsule" class="/" type="capsule" size="0.025000000000000001 0.037499999999999999" rgba="0.49019607843137253 0.70980392156862748 0.6588235294117647 1" pos="0.0625 0 0" euler="0 1.5707963267948966 0"/>
<geom name="arm_0_segment_0_connector" class="/" type="sphere" contype="0" conaffinity="0" size="0.012500000000000001" rgba="0.34901960784313724 0.34901960784313724 0.34901960784313724 1" pos="0 0 0"/>
<body name="B1" pos="0 0 0">
<geom type="sphere" size="0.01"/>
<joint name="arm_0_segment_0_in_plane_joint" class="/" type="hinge" axis="0 0 1" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="0"/>
<joint name="arm_0_segment_0_out_of_plane_joint" class="/" type="hinge" axis="0 -1 0" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
</body>
</body>
<body name="B2" pos="0.250 0 0" euler="0 0 0">
<geom name="arm_0_segment_1_capsule" class="/" type="capsule" size="0.018750000000000003 0.025000000000000001" rgba="0.49019607843137253 0.70980392156862748 0.6588235294117647 1" pos="0.043750000000000004 0 0" euler="0 1.5707963267948966 0"/>
<geom name="arm_0_segment_1_connector" class="/" type="sphere" contype="0" conaffinity="0" size="0.0093750000000000014" rgba="0.34901960784313724 0.34901960784313724 0.34901960784313724 1" pos="0 0 0"/>
<body name="C">
<geom type="sphere" size="0.01"/>
<joint name="arm_0_segment_1_in_plane_joint" pos="0 0 0" class="/" type="hinge" axis="0 0 1" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
<joint name="arm_0_segment_1_out_of_plane_joint" class="/" type="hinge" axis="0 -1 0" limited="true" stiffness="1.1084000000000001" range="-0.52359877559829882 0.52359877559829882" armature="0.45000000000000001" damping="5.5084"/>
</body>
</body>
<camera name="side_camera" class="/" mode="track" pos="0 -2 2.5" quat="0.93969262078590843 0.34202014332566871 0 0"/>
</worldbody>
<equality>
<weld name="weld_0" body1="B1" body2="B2" />
</equality>
<actuator>
</actuator>
<sensor>
</sensor>
</mujoco>
When I load the model below into mujoco.viewer, it does not move the same way the first model does. I'm attempting to move it by mouse using Ctrl + Right mouse button on a selected segment. @Balint-H is something like this what you initially described?
Could you provide a video of the two cases? The simplest issue I can imagine would be due to added collisions between the geoms of the two B bodies (previously they dont occur because they are on the same body, you can try disabling collisions between those geoms)
Nested:
https://github.com/google-deepmind/mujoco/assets/54912465/64533f6c-dd0f-44fa-9cef-26ad4914debb
Welded:
https://github.com/google-deepmind/mujoco/assets/54912465/fc691163-16ef-4130-a41c-6f58339c7114
Adding
<contact>
<exclude body1="B1" body2="B2"/>
</contact>
seems to have no effect
Ah, it's clear now, B2 is missing a freejoint. It is unable to move in space therefore, and so is B1 (since it is welded). The weld will enforce the joint constraints of B1 onto B2, but B2 needs to be free to move to do so.
Also, I don't think C needs joints in this case.
Hi, I am playing with MuJoCo to experiment with RL agents, just for fun. I am using the dm_control python wrapper.
I was wondering if it is possible to use some tricks to somehow simulate a body breakage at runtime? I am thinking for example to have 2 bodies linked by a joint, and once a certain force is sensed on the joint, I could dynamically 'remove' the joint to let the 2 bodies 'fall apart'. Is this somehow achievable? Any directions?
Thanks very much, Antonio