2

I'm trying to load an SDF into drake but my program throws a std::runtime_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)

This is the code I'm running

  MultibodyPlant<double>* dp =
      builder.AddSystem<MultibodyPlant<double>>(max_time_step);
  dp->set_name("plant");
  dp->RegisterAsSourceForSceneGraph(&scene_graph);

  drake::multibody::Parser parser(dp);
  const std::string sdf_path = kDoublePendulumSdfPath;

  parser.AddModelFromFile(sdf_path);

  dp->Finalize();

This is my SDF

<sdf version="1.4">
<model name="t-wrecks">

<link name="left_foot"><pose>0 0 0 0 0 0</pose><collision name="collision"><geometry><box><size>1 1 1</size></box></geometry></collision><visual name="visual"><geometry><box><size>1 1 1</size></box></geometry></visual></link>

<link name="right_foot"><pose>2 0 0 0 0 0</pose><collision name="collision"><geometry><box><size>1 1 1</size></box></geometry></collision><visual name="visual"><geometry><box><size>1 1 1</size></box></geometry></visual></link>

<link name="left_leg"><pose>0 0 1.5 0 0 0</pose><collision name="collision"><geometry><box><size>0.5 0.5 2</size></box></geometry></collision><visual name="visual"><geometry><box><size>0.5 0.5 2</size></box></geometry></visual></link>

<link name="right_leg"><pose>2 0 1.5 0 0 0 0</pose><collision name="collision"><geometry><box><size>0.5 0.5 2</size></box></geometry></collision><visual name="visual"><geometry><box><size>0.5 0.5 2</size></box></geometry></visual></link>

<link name="left_thigh"><pose>0 -0.4 3 0.5 0 0</pose><collision name="collision"><geometry><box><size>0.5 0.5 2</size></box></geometry></collision><visual name="visual"><geometry><box><size>0.5 0.5 2</size></box></geometry></visual></link>

<link name="right_thigh"><pose>2 -0.4 3 0.5 0 0</pose><collision name="collision"><geometry><box><size>0.5 0.5 2</size></box></geometry></collision><visual name="visual"><geometry><box><size>0.5 0.5 2</size></box></geometry></visual></link>

<link name="pelvis"><pose>1.0 -0.75 3.75 0 0 0</pose><collision name="collision"><geometry><box><size>2.5 1 0.25</size></box></geometry></collision><visual name="visual"><geometry><box><size>2.5 1 0.25</size></box></geometry></visual></link>

<joint name="left_leg_foot" type="revolute"><pose>0 0 0 0 0 0</pose><child>left_foot</child><parent>left_leg</parent><axis><xyz>1 0 0</xyz></axis></joint>

<joint name="right_leg_foot" type="revolute"><pose>0 0 0 0 0 0</pose><child>right_foot</child><parent>right_leg</parent><axis><xyz>1 0 0</xyz></axis></joint><joint name="left_knee" type="revolute"><pose>0 0 1.0 0 0 0</pose><child>left_leg</child><parent>left_thigh</parent><axis><xyz>1 0 0</xyz></axis></joint><joint name="right_knee" type="revolute"><pose>0 0 1 0 0 0</pose><child>right_leg</child><parent>right_thigh</parent><axis><xyz>1 0 0</xyz></axis></joint>

<joint name="left_hip" type="revolute"><pose>0 0 1 0 0 0</pose><child>pelvis</child><parent>right_thigh</parent><axis><xyz>1 0 0</xyz></axis></joint><joint name="right_hip" type="revolute"><pose>0 0 1 0 0 0</pose><child>pelvis</child><parent>left_thigh</parent><axis><xyz>1 0 0</xyz></axis></joint>

</model>
<static>true</static>
</sdf>
cjds
  • 8,268
  • 10
  • 49
  • 84

1 Answers1

3

This is because currently we only support models that have a strict tree structure. From an SDF file, this tree structure is inferred from the <parent> and <child> tags, which due to this restriction, Drake understands as inboard and outboard bodies in the tree structure (we'll eventually lift this restriction, but probably not soon).

In your case, I see that you provided the pelvis body as the child of two other links; right_thigh and left_thigh, which is not supported today.

To fix the problem, swap child/parent in your joints left_hip and right_hip.

BTW, I see no inertia properties in your file, only visuals and collisions. Therefore you won't be able to simulate nor compute any useful dynamics information. I imagine this is only because this is work in progress.

Good luck.

Alejandro
  • 1,064
  • 1
  • 8
  • 22
  • Yep definitely a WIP. Thanks for the heads up about the inboard and outboard bodies :-) – cjds Jul 11 '20 at 15:45
  • great, I'm glad it was helpful. – Alejandro Jul 12 '20 at 16:18
  • 1
    FTR on the BTW: There will be inertia properties - they will come from unfortunately non-physical default values :P http://sdformat.org/spec?ver=1.7&elem=link#link_inertial (working slowly towards fixing that in Drake, then eventually in SDFormat). In general, you should avoid relying on those default values for useful models. – Eric Cousineau Jul 12 '20 at 17:55