Touch Sensors not always registering contact #2483
-
IntroHi! I am an independent researcher interested in using reinforcement learning to solve various problems and to build experiments in MujoCo. My setupGoogle Colab T4 My questionI am trying to build a reinforcement learning system that learns to bounce a ball using Gymnasium, Stable Baselines3, and MuJoCo. In reviewing the simulation recording and contact data, there appears to be a misalignment between what the video shows and how many times the touch sensor registers a force. The embedded video shows at least six (6) bounces, but the sensor data only lists three (3) (see attached CSV). Relevant Issues:
The above issues stem from the touch sensor area being too small. So, I increased the site size to include the entire paddle, but the touch sensor does not always appear to register contact. Relevant Documentation:
What is the reason why MuJoCo is not registering all contact instances via the touch sensor? Is it because the timestep is too big, or how the solref is defined for the paddle and ball geom? Any help would be greatly appreciated! Minimal model and/or code that explain my questionLink to Google Colab Notebook[Ball Bounce] Soft Actor-Critic (SAC) MuJoCo World Model<mujoco>
<option timestep=".002" />
<asset>
<texture name="grid" type="2d" builtin="checker" rgb1=".1 .2 .3"
rgb2=".2 .3 .4" width="300" height="300" mark="none" />
<material name="grid" texture="grid" texrepeat="1 1"
texuniform="true" reflectance=".2" />
</asset>
<worldbody>
<light name="light" pos="0 0 1" />
<geom name="floor" type="plane" pos="0 0 -0.5" size="2 2 .1" material="grid" />
<body name="paddle_body" pos="0 0 0">
<site name="bounce_sensor" pos="0 0 0.025" size="0.21 0.21 0.075" type="box" rgba="1 0 0 .05" />
<joint name="rotate_x" pos="0 0 0" axis="1 0 0" range="-.3 .3" damping="10" />
<joint name="rotate_y" pos="0 0 0" axis="0 1 0" range="-.3 .3" damping="10" />
<joint name="rotate_z" pos="0 0 0" axis="0 0 1" range="-.3 .3" damping="10" />
<joint axis="0 0 1" limited="true" name="slider_z" range="0 0.5" type="slide" />
<joint axis="0 1 0" limited="true" name="slider_y" range="-.2 .2" type="slide" />
<joint axis="1 0 0" limited="true" name="slider_x" range="-.2 .2" type="slide" />
<geom name="paddle_geom" type="box" size=".2 .2 .02" rgba="0.2 0.2 1 1" solref="0.02 0.07" />
</body>
<body name="ball_body" pos="0 0 0.3">
<freejoint name="ball_freejoint" />
<geom name="ball_geom" type="sphere" size=".04" rgba="0 1 0 1" solref="0.02 0.07" />
</body>
</worldbody>
<actuator>
<general name="act_x" joint="rotate_x" ctrlrange="-1 1" gainprm="500 0 0" />
<general name="act_y" joint="rotate_y" ctrlrange="-1 1" gainprm="500 0 0" />
<general name="act_z" joint="rotate_z" ctrlrange="-1 1" gainprm="500 0 0" />
<motor ctrllimited="true" ctrlrange="-1 1" gear="50" joint="slider_z" name="slider_z_motor" />
<motor ctrllimited="true" ctrlrange="-1 1" gear="50" joint="slider_y" name="slider_y_motor" />
<motor ctrllimited="true" ctrlrange="-1 1" gear="50" joint="slider_x" name="slider_x_motor" />
</actuator>
<sensor>
<touch name="touch_sensor" site="bounce_sensor" />
</sensor>
</mujoco> Confirmations
|
Beta Was this translation helpful? Give feedback.
Replies: 3 comments 2 replies
-
It's a bit hard to see in your video, but I think the touch sensor is not properly aligned, it seems to be above the box rather than enclosing it. If you have a deep penetration then the position of the contact could easily be quite deep in the paddle, which would not be caught by the sensor. |
Beta Was this translation helpful? Give feedback.
-
PS, you might want to consider using a fromto sensor, and registering a collision when the fromto vector flips direction |
Beta Was this translation helpful? Give feedback.
-
Thanks for the advice! I added a Updated Results300,000 Training Stepsball_bounce_300000-step-0-to-step-10000.7.mp4Best Model (500,000 Training Steps)best_model_ball_bounce-step-0-to-step-10000.14.mp4Updated MuJoCo Model<mujoco>
<option timestep=".002" />
<asset>
<texture name="grid" type="2d" builtin="checker" rgb1=".1 .2 .3"
rgb2=".2 .3 .4" width="300" height="300" mark="none" />
<material name="grid" texture="grid" texrepeat="1 1"
texuniform="true" reflectance=".2" />
</asset>
<worldbody>
<light name="light" pos="0 0 1" />
<geom name="floor" type="plane" pos="0 0 -0.5" size="2 2 .1" material="grid" />
<body name="paddle_body" pos="0 0 0">
<site name="bounce_sensor" pos="0 0 0.025" size="0.21 0.21 0.075" type="box" rgba="1 0 0 .15" />
<joint name="rotate_x" pos="0 0 0" axis="1 0 0" range="-.3 .3" damping="10" />
<joint name="rotate_y" pos="0 0 0" axis="0 1 0" range="-.3 .3" damping="10" />
<joint name="rotate_z" pos="0 0 0" axis="0 0 1" range="-.3 .3" damping="10" />
<joint axis="0 0 1" limited="true" name="slider_z" range="0 0.5" type="slide" />
<joint axis="0 1 0" limited="true" name="slider_y" range="-.2 .2" type="slide" />
<joint axis="1 0 0" limited="true" name="slider_x" range="-.2 .2" type="slide" />
<geom name="paddle_geom" type="box" size=".2 .2 .02" rgba="0.2 0.2 1 1" solref="0.02 0.07" />
</body>
<body name="ball_body" pos="0 0 0.3">
<freejoint name="ball_freejoint" />
<site name="ball_site" pos="0 0 0" size="0.04" rgba="0 1 0 1" />
<geom name="ball_geom" type="sphere" size=".04" rgba="0 1 0 1" solref="0.02 0.07" />
</body>
</worldbody>
<actuator>
<general name="act_x" joint="rotate_x" ctrlrange="-1 1" gainprm="500 0 0" />
<general name="act_y" joint="rotate_y" ctrlrange="-1 1" gainprm="500 0 0" />
<general name="act_z" joint="rotate_z" ctrlrange="-1 1" gainprm="500 0 0" />
<motor ctrllimited="true" ctrlrange="-1 1" gear="50" joint="slider_z" name="slider_z_motor" />
<motor ctrllimited="true" ctrlrange="-1 1" gear="50" joint="slider_y" name="slider_y_motor" />
<motor ctrllimited="true" ctrlrange="-1 1" gear="50" joint="slider_x" name="slider_x_motor" />
</actuator>
<sensor>
<fromto name="ball_to_paddle" body1="ball_body" body2="paddle_body" />
<accelerometer site="ball_site" name="ball_accelerometer" />
<velocimeter site="ball_site" name="ball_velocity" />
<touch name="touch_sensor" site="bounce_sensor" />
</sensor>
</mujoco> The ball's velocity is aligned with the recorded simulation. However, the I appreciate your help with this! Let me know if you need any other details or want to see any specific code! |
Beta Was this translation helpful? Give feedback.
I don't think there is a problem, everything is measured. The contact forces and accelerations are simply very high (for a short span of time), so the smaller forces/accelerations related to the smooth motions aren't visible in your auto-scaled plots. If you zoom in the y-axis you will see all the details...