upkie / vulp

Robot/simulation switch for the mjbots stack
Apache License 2.0
61 stars 4 forks source link

Creating a Bullet client in a different process #80

Closed ubgk closed 4 months ago

ubgk commented 5 months ago

I am fiddling with Bullet to create new simulation environments for Upkie, such as creating objects in the simulation (i.e. ramps or boxes for Upkie to jump off).

I gather that for now, we can only do that in the spine (more specifically, only in vulp as b3RobotSimulatorClientAPI bullet_ seems to be private), where we have access to the (C++) Bullet API. I would, however, prefer to have more flexibility, and potentially use a Python script to populate the environment.

  1. Is this possible with the existing implementation? (I guess not)
  2. Can the simulation be launched in a way that allows other clients (e.g., pybullet to connect)?

The following flag spawns Bullet either in DIRECT or GUI mode: https://github.com/upkie/vulp/blob/5f59efb493e2a4aa74dcd32401d4cb1f293c4530/vulp/actuation/BulletInterface.cpp#L31

I tried launching a shared memory server (e.g., eCONNECT_GUI -> eCONNECT_GUI_SERVER), and the simulation launches, but I cannot connect to it:

>>> import pybullet as pyb
pybullet build time: Jan 20 2024 18:22:27
>>> pyb.connect(pyb.SHARED_MEMORY)
-1

Upon a little digging I find that both flags do the same thing here (if it's the right file to look at):

        case eCONNECT_GUI:
        {
            int argc = 0;
            char* argv[1] = {0};
#ifdef __APPLE__
            sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv);
#else
            sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv);
#endif
            break;
        }
        case eCONNECT_GUI_SERVER:
        {
            int argc = 0;
            char* argv[1] = {0};
#ifdef __APPLE__
            sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv);
#else
            sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv);
#endif
            break;

and that both call b3CreateInProcessPhysicsServerAndConnectMainThread which seems to create a shared memory, but I didn't dig further.

Also, I have not been able to test this on Linux, so I cannot attest if b3CreateInProcessPhysicsServerAndConnect behaves properly.

stephane-caron commented 5 months ago

Populating the environment from Python

Can the simulation be launched in a way that allows other clients (e.g., pybullet to connect)?

At this point you know as much as I do :sweat_smile: I didn't know about Bullet's shared-memory mechanism. If you find a way to allow for that (that preferably doesn't break existing clients) we can update Vulp. I guess the right places to ask about it are the Bullet forum, or the Bullet discussions on GitHub.

Alternatives

Populating the environment from a separate Python process would be the most flexible, but it may create complexity to implement. Alternatives I can think of (less flexible, easier to implement):

I'd recommend starting from the command-line approach, as it looks like a lower-hanging fruit.