0

I'm currently creating a system of spheres which can actuate to push each other away. There are center bodies (teal) at each corner which are connected to connecting bodies (yellow) via PrismaticJoint which are connected in the same way to the next corner.

When creating a one dimensional system of spheres, for example, a 1x1x4 system, I run into no errors and the system behaves as expected.

In trying to create a system of eight spheres in a 2x2x2 orientation, I'm running into mobilization errors. Here is what the system looks like:

2x2x2 system, where teal spheres are centers and yellow spheres are connecting bodies

And the error:

terminate called after throwing an instance of 'std::runtime_error'
  what():  This mobilizer is creating a closed loop since the outboard body already has an inboard mobilizer connected to it. If a physical loop is really needed, consider using a constraint instead.
Aborted (core dumped)

I understand that the error comes for joints sharing child or outward bodies, like in the case for two sides of the cube actuating one corner. Unfortunately, I haven't found a way to pivot using constraints successfully. How can I better define this system?

1 Answers1

1

One way to address this is to use a Drake bushing element (essentially a stiff spring and damper) to emulate a "weld" constraint. There is a nice example of this approach in Drake -- see examples/multibody/four_bar.

The general idea is to break topological loops by sawing through one or more bodies, then welding them back together with a bushing (which does not count as a topological loop).

Sherm
  • 643
  • 4
  • 6
  • This may have been exactly what I was looking for - as I wanted a bit of compliance between these body connections anyway! I'll see how this goes. – Joaquin Giraldo-Laguna May 13 '20 at 16:39
  • I attempted this with a single joint connection in the orientation I had but am running into some strange errors. It attempt to connect connectors from two different spheres on the Z axis, which should be welded together. Setting k_z above ~210 causes the visualizer to fail, or for the bodies involved to disappear. With d_z there is a similar limit. There are also other unexplained behaviors such as the joints seeming to ignore joint limits, etc. – Joaquin Giraldo-Laguna May 13 '20 at 20:44
  • I wonder if you are running into stability problems? See if it works at a smaller step size. If you are doing continuous integration you could try an implicit integrator also. If you aren't already, I would suggest making a very small, simple system for debugging and then building up to the full system after the small one is working satisfactorily. – Sherm May 14 '20 at 03:19
  • 1
    I found constants which worked for my system and now it behaves much better! Yes, I initially tested only 'welding' two bodies, and then expanded to the rest. Check it out: https://i.imgur.com/ewKbyX8.png Unfortunately, I still haven't solved my joint limits problem though, and put it here: https://stackoverflow.com/questions/61788760/prismaticjoint-limits-not-enforced – Joaquin Giraldo-Laguna May 14 '20 at 04:40