maxspahn / gym_envs_urdf

URDF environments for gym
https://maxspahn.github.io/gym_envs_urdf/
GNU General Public License v3.0
46 stars 14 forks source link

mobilePanda slowly collapse. With action and velocity set to zero. #240

Closed Quirina300 closed 11 months ago

Quirina300 commented 11 months ago

The mobile panda slowly collapses even when the actions and velocity are set to zero. The code we used to get this issue:

import gymnasium as gym
from urdfenvs.robots.generic_urdf import GenericUrdfReacher
import numpy as np

def run_mobile_reacher(n_steps=10000, render=False, goal=False, obstacles=True):
    robots = [
        GenericUrdfReacher(urdf="mobilePanda.urdf", mode="vel"),
    ]
    env = gym.make(
        "urdf-env-v0",
        dt=0.01, robots=robots, render=render
    )

    action = np.zeros(env.n())
    vel0 = np.zeros(env.n())
    pos0 = np.array([ 0., 0.,  0.,  0.,  0.,  0., 0., 0.,  1.8675,  0.,  0.02,  0.02])
    # pos0[3] = 0 

    ob = env.reset(pos=pos0, vel=vel0)
    print(f"Initial observation : {ob}")
    history = []
    print(env)
    for i in range(n_steps):
        action[3] = 0
        ob, *_ = env.step(action)
        history.append(ob)
    env.close()
    return history

if __name__ == "__main__":
    run_mobile_reacher(render=True)
maxspahn commented 11 months ago

Hi @Quirina300 ,

Thanks for reporting this issue. I played around with the example and found that the problem is related to numerical inaccuracies. Specifically, pybullet's velocity controller cannot ensure that the target-velocity is reached within one time step. See https://pybullet.org/Bullet/phpBB3/viewtopic.php?t=12688 for a detailed discussion.

One solution to that is to increase the number of sub_steps performed in during one time step. The current setup in urdfenvs is num_sub_steps = 20. https://github.com/maxspahn/gym_envs_urdf/blob/57b82e7ead09941450f8b53200b6b1fd3c9811f7/urdfenvs/urdf_common/urdf_env.py#L85

When this value is increase to 200, or the time step dt=0.01 is decreased to dt=0.001 (the same effect), the problem is solved. However, it is currently not supported to change the value for num_sub_steps from the front-end. I will create a PR on that.