Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Impossible to set timestep lower then 1e-7 #245

Closed
traversaro opened this issue Sep 26, 2020 · 3 comments · Fixed by #246
Closed

Impossible to set timestep lower then 1e-7 #245

traversaro opened this issue Sep 26, 2020 · 3 comments · Fixed by #246

Comments

@traversaro
Copy link
Contributor

If using the devel branch I try to run the following script:

import numpy as np
from gym_ignition import utils
import idyntree.bindings as idt
from gym_ignition.rbd import idyntree
from scenario import gazebo as scenario_gazebo
from gym_ignition.utils.scenario import init_gazebo_sim

# Configure numpy output
np.set_printoptions(precision=3, suppress=True, floatmode='fixed')

scenario_gazebo.set_verbosity(scenario_gazebo.Verbosity_info)

urdf = f"""
<robot name="oneLink">
    <link name="base_link">
        <inertial>
            <origin xyz="0 0 5.0" rpy="0 0 0"/>
            <mass value="1"/>
            <inertia ixx="2e-5" ixy="0" ixz="0" iyy="2e-5" iyz="0" izz="2e-5"/>
        </inertial>
    </link>
</robot>
"""
urdf_file = utils.misc.string_to_file(urdf)

# Get the simulator and the world
step_size=1e-7;
print(step_size)
gazebo, world = init_gazebo_sim(step_size=step_size)
assert world.set_gravity([0, 0, 0])

# Show the GUI
# import time
# gazebo.gui()
# gazebo.run(paused=True)
# time.sleep(3)

# Insert the model
world.insert_model(urdf_file)
gazebo.run(paused=True)
model = world.get_model(model_name="oneLink").to_gazebo()

# Reset the state of the model
model.to_gazebo().reset_base_pose([0, 0, 0], [1, 0, 0, 0])
model.to_gazebo().reset_base_world_linear_velocity([0, 0, 4.])
gazebo.run(paused=True)

I get the error (that originates from DART):

Warning [World.cpp:138] [World] Attempting to set negative timestep. Ignoring this request because it can lead to undefined behavior.

Everything instead works fine using a timestep of 1e-6 . Based on a quick debugging, the problem is probably in https://github.com/robotology/gym-ignition/blob/devel/cpp/scenario/gazebo/src/helpers.cpp#L375 , where the timestep value is passed to Gazebo as a string that is converted using std::to_string , that is not ideal for two reasons:

@traversaro
Copy link
Contributor Author

While fixing the bug is relatively trivial, as you just need to substitute std::to_string with something that return the shortest decimal string that round-trips. Fortunately C++17 has exactly a function for that, that is std::to_chars. Unfortunately, while std::to_chars with double is available in MSVC since VS2017, GCC only added it a few months ago (see gcc-mirror/gcc@932fbc8) and still need to be released, and Clang still needs to integrate it (see https://reviews.llvm.org/D70631).

For this reason, (unless this functionality is provided in some Ignition or SDFormat library) it is necessary to either just convert a the double to string via stringstream with an arbitrary high precision (24 significant digits should be sufficient, but I am not sure) add or vendor a dependency for this double to shortest exact string. In iDynTree for this in robotology/idyntree#554 / robotology/idyntree@5982124 I imported fpconv, https://github.com/night-shift/fpconv .

@diegoferigo let me know which solution you prefer, if stringstream + setprecision(17) or adding fpconv to the repo.

@traversaro
Copy link
Contributor Author

For the testing, it is a bit tricky as the run method returns true even if the Warning [World.cpp:138] [World] Attempting to set negative timestep. Ignoring this request because it can lead to undefined behavior. message is printed.

traversaro added a commit to traversaro/gym-ignition that referenced this issue Sep 26, 2020
std::to_string truncates the values with 1e-6 precision, and is prone
to locale-related bug.

Fix robotology-legacy#245
@diegoferigo
Copy link
Collaborator

diegoferigo commented Sep 27, 2020

Thanks for catching this bug and providing all the information!

Unfortunately it's not straightforward returning false because what we do is editing the in-memory DOM of the world to add the value to the desired physics step and RTF, and then pass it to Gazebo. The warning you reported is not generated by us and we are not able to catch any return value from that. This is the reason why we return true in this case.

A test, however, could be done exploiting World::time() similarly to the following existing test:

https://github.com/robotology/gym-ignition/blob/0a3d86575940cb222ee405eab9184c8aa3eb1987/tests/test_scenario/test_world.py#L185-L210

The (0.001, 1.0, 1) tuple in the decorator is (step_size, rtf, iterations_per_run). If you add a new tuple (1E-9, 1.0, 1) to the list, it will fail without the fix of #246.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging a pull request may close this issue.

2 participants