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

Related to bullet featherstone benchmarking results. #4636

Open
yaswanth1701 opened this issue Jul 13, 2024 · 0 comments
Open

Related to bullet featherstone benchmarking results. #4636

yaswanth1701 opened this issue Jul 13, 2024 · 0 comments

Comments

@yaswanth1701
Copy link

Hi everyone, I am working on benchmarking physics engines as part of Google Summer of Code'24 with the Open Source Robotics Foundation(OSRF). We are trying to build a simulator-independent benchmarking suite. I tested running our benchmarking with the gazebo classic and the new gazebo(gz-sim). Gazebo supports both bullet and bullet Featherstone and we found the results for both bullet versions to be a bit off from other engines (eg: dart, simbody, ode). So, to investigate further I ran the same benchmarking on pybullet with maximal coordinates and reduced coordinates version(Featherstone). We found that the results for the maximal coordinates version are similar to other physics engines and are mostly likely correct. However, the Featherstone version is entirely wrong (and is not even close to what was obtained on gz - sim) and has huge errors in both position and velocity compared to the analytical solutions. A detailed description of our benchmark can be found here.

There is only gravity force acting in the z direction and no force along the x and y directions. But it seems while using reduced coordinates, velocities in the x and y directions are changing which is not the case with the maximal coordinates version.

Below is the code I am using, to switch between maximal and reduced coordinates, I am changing only the useMaximalCoordinates argument except that everything is same.

import pybullet as p
import time
import pybullet_data
import numpy as np
import os
import csv

STATES_NAMES = ["sim_time",
                "model_no",
                "linear_velocity_x",
                "linear_velocity_y",
                "linear_velocity_z",
                "angular_velocity_x",
                "angular_velocity_y",
                "angular_velocity_z",
                "position_x",
                "position_y",
                "position_z",
                "quaternion_w",
                "quaternion_x",
                "quaternion_y",
                "quaternion_z",]

CONFIGURATION  = ["physics_engine", "time_step", "complex", 
                  "collisiion", "model_count","wall_time", 
                  "log_multiple", "classname"]


benchmark_dir = os.getcwd()
world_dir = os.path.join(benchmark_dir,"BENCHMARK_boxes_dt_TEST")
file_names = os.listdir(world_dir)
file_names = sorted(file_names, reverse=False)
file_names = file_names[1:] + file_names[0:1]
print(file_names)


dt_min = 1e-4
dt_max = 1e-3
dt_step = 1e-4
dt_list = np.arange(dt_min, dt_max + dt_min, dt_step).tolist()
print(dt_list)


for i,file_name in enumerate(file_names):
    dt = dt_list[i]
    csv_file = open('maximal_coordinates/'+'bullet'+file_name.split('.world')[0] + '.csv', mode='w', newline='')
    csv_writer = csv.writer(csv_file)
    csv_writer.writerow(CONFIGURATION)
    csv_writer.writerow(["bullet", dt, True, True, 1, 0, False,"DtComplex"])
    physicsClient = p.connect(p.DIRECT )
    p.setGravity(0,0,-9.8)
    
    box = p.loadSDF("BENCHMARK_boxes_dt_TEST/" + file_name, useMaximalCoordinates=True)
    print(f"test name is {file_name} and time step is {dt_list[i]}")

    p.resetBaseVelocity(box[0], [-2.0, 2.0, 8.0], [0.1, 5.0, 0.1])
    
    p.setTimeStep(dt)
    steps = int(10/dt)
    csv_writer.writerow(STATES_NAMES)
    sim_time = 0
    for i in range(steps):
       
       p.stepSimulation()
       pose = p.getBasePositionAndOrientation(box[0])
       pos = pose[0]
       quat = pose[1]
       twist = p.getBaseVelocity(box[0])
       linear_vel = twist[0]
       angular_vel = twist[1]
       sim_time+= dt
       row = [ sim_time, 1, twist[0][0], twist[0][1], twist[0][2],
               twist[1][0], twist[1][1], twist[1][2], pos[0], 
               pos[1], pos[2], quat[3], quat[0], quat[1], quat[2]]
       csv_writer.writerow(row)
       time.sleep(dt)
    csv_file.close()
    
    p.disconnect()

Here are all the benchmarking worlds which we using in sdf format.
BENCHMARK_boxes_dt_TEST.zip

The result for Featherstone version on gz-sim can be found here.

Results for pybullet can be found here

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

No branches or pull requests

1 participant