Keeping a block in a certain height #2202
-
MuJoCo: 3.2.2 Hi, I am trying to lift a block to a certain height and try to make it float on that height by applying external force F = W = mg, but when I try to apply that, the block's height keeps increasing, instead of remaining constant minimal XML<mujoco model="block scene">
<asset>
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3"
markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0" rgba="1 1 1 0.7"/>
</asset>
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
<camera name="fixed" pos="0 0 0" xyaxes="1 0 0 0 0 1"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane" solimp="0.995 0.999 0.0000001 0.5 2"/>
<body name="block_0" pos="0 0 .03">
<joint name="block_joint" type="free" damping="0"></joint>
<inertial pos="0 0 0" mass="0.1" diaginertia="0.001 0.001 0.001" />
<geom name="blue_subbox" size="0.030 0.03 0.03" pos="0 0 0" type="box" rgba="0.3 0.5 0.8 1"
solimp="0.99 0.995 0.0000001 0.5 2" solref="0.005 2" friction="5 0.3 0.001" />
</body>
</worldbody>
<sensor>
<framepos name= "block_pos" objtype = "body" objname="block_0" />
</sensor>
</mujoco>
</details>
Code:
model = mujoco.MjModel.from_xml_string(xml_string)
data = mujoco.MjData(model)
mujoco.mj_resetData(model, data)
#viewer = mujoco.viewer.launch_passive(model, data)
n_frames = 1000
height = 240
width = 320
frames = []
times = []
heights = []
fps = 60.0
with mujoco.Renderer(model, height, width) as renderer:
for i in range(n_frames):
while data.time < i/fps:
block_mass = model.body('block_0').mass[0]
gravity = -model.opt.gravity[2]
mg = block_mass * gravity
block_pos = data.sensor('block_pos').data.copy()
block_height = block_pos[2]
block_body_id = model.body('block_0').id
print(f"Block height: {block_height}")
if block_height < 0.7:
data.xfrc_applied[block_body_id] = [0, 0, mg + 0.01, 0, 0, 0]
else:
data.xfrc_applied[block_body_id] = [0, 0, mg, 0, 0, 0]
mujoco.mj_step(model, data)
times.append(data.time)
heights.append(block_height)
renderer.update_scene(data, "fixed")
frame = renderer.render()
frames.append(frame)
plt.plot(times, heights)
plt.xlabel('Time (s)')
plt.ylabel('Block Height (m)')
plt.title('Block Height vs Time')
plt.grid(True)
plt.savefig("block_height_vs_time.png")
print("Plot saved as 'block_height_vs_time.png'.")
![block_height_vs_time](https://github.com/user-attachments/assets/af24f679-37c9-4a3e-9635-b51f8b2268e4) |
Beta Was this translation helpful? Give feedback.
Answered by
yuvaltassa
Nov 4, 2024
Replies: 1 comment
-
This is due to Newton's Second Law of motion. You are accelerating the body and then not accelerating any more, so it keeps moving. Also, read about |
Beta Was this translation helpful? Give feedback.
0 replies
Answer selected by
adawne
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
This is due to Newton's Second Law of motion. You are accelerating the body and then not accelerating any more, so it keeps moving.
Also, read about
<body gravcomp>