Troubleshooting common problems

This page contains a collection of tips and tricks for resolving common problems.

MultibodyPlant

Unconnected QueryObject port

The error message will include the message, “The provided context doesn’t show a connection for the plant’s query input port.”

MultibodyPlant (C++, Python) requires a connection to SceneGraph (C++, Python) in order to evaluate contact via its QueryObject (C++, Python). Attempts to evaluate output ports that expose or depend on contact results (the geometric data and/or forces that arise from the contact between bodies’ collision geometries) will fail. Evaluating the time derivatives (e.g., when running a continuous simulation) will likewise fail.

The connection can be reported as missing for several reasons:

  1. Was a SceneGraph instance created and connected?
    • The simplest solution is to use AddMultibodyPlantSceneGraph() (C++, Python). It will construct and connect the plant and scene graph together for you.
  2. Did you provide the right context?
    • You’ve created and connected the systems in a Diagram (C++, Python) and allocated a Context (C++, Python) for the Diagram.
    • Make sure you extract the MultibodyPlant’s context from the Diagram’s Context. Do not allocate a Context directly from the plant. Use System::GetMyContextFromRoot() (C++, Python) to acquire the plant’s Context from the Diagram’s context; this will preserve all of the necessary connections. E.g.,
       builder = DiagramBuilder()
       # Build plant and scene graph and automatically connect them.
       plant, scene_graph = AddMultibodyPlantSceneGraph(
           builder=builder, time_step=1e-3)
       ...
       diagram = builder.Build()
    
       # WRONG.  This will create a Context for the plant only (no connected
       # SceneGraph).
       xdot = plant.EvalTimeDerivatives(context=plant.CreateDefaultContext())
    
       context = diagram.CreateDefaultContext()
       # Extract the plant's context from the diagram's to invoke plant methods.
       plant_context = plant.GetMyContextFromRoot(root_context=context)
       xdot = plant.EvalTimeDerivatives(context=plant_context)
    

System Framework

Context-System mismatch

The error message will include one of the following:

  • A function call on a FooSystem system named '::_::foo' was passed the root Diagram's Context instead of the appropriate subsystem context.
  • A function call on the root Diagram was passed a subcontext associated with its subsystem named '::_::foo' instead of the root context.
  • A function call on a BarSystem named '::_::bar' was passed the Context of a system named '::_::foo' instead of the appropriate subsystem Context.

Contexts and Systems: An Overview

For every System (C++, Python) there is a corresponding Context (C++, Python). The System and Context work together. The Context holds the data values and the System defines the operations on that data.

For example, a MultibodyPlant (C++, Python) is such a system. We can use an instance of a MultibodyPlant to create one or more Contexts. Each Context contains the continuous and discrete state values for the plant’s model. These Contexts can be configured to represent the model in different configurations. However, if we want to evaluate some mechanical property (e.g., composite inertia of a robotic arm), we invoke a method on the plant, passing one of the contexts.

We can combine multiple Systems into a Diagram (C++, Python). The Systems within a Diagram will typically have their ports connected – this is how the Systems work together.

Contexts similarly form a parallel hierarchical structure. The Context associated with a Diagram is the combination of all of the Contexts associated with the Systems inside that Diagram. The port connections between Systems in the Diagram are mirrored in the Diagram’s Context.

Why did I get this error and how do I get rid of it?

Many System APIs require a Context. It is important to pass the right Context into the API. What’s the difference between a “right” and “wrong” Context?

  • The right Context was allocated by the System being evaluated.
  • If the System is part of a Diagram, then the Context provided should be a reference pointing inside the Diagrams Context (see below for how to do this).

The most common error is to pass the Diagram’s Context into a constituent System’s API. We’ll illustrate this using a Diagram with a MultibodyPlant. The solution is to use either GetMyContextFromRoot() (C++, Python) or GetMyMutableContextFromRoot() (C++, Python) as appropriate to extract a particular System’s Context from its Diagram’s Context.

  builder = DiagramBuilder()
  plant, _ = AddMultibodyPlantSceneGraph(builder=builder, time_step=1e-3)
  ...  # Populate the plant with interesting stuff.
  diagram = builder.Build()
  # Create a Context for diagram.
  root_context = diagram.CreateDefaultContext()

  my_body = plant.GetBodyByName("my_body")
  X_WB = RigidTransform(...)  # Define a pose for the body.
  # Error! plant has been given diagram's context.
  plant.SetFreeBodyPose(context=root_context, body=base, X_WB=X_WB_desired)

  # Get the Context for plant from diagram's context.
  plant_context = plant.GetMyContextFromRoot(root_context=root_context)
  # Successful operation; the provided context belongs to plant.
  plant.SetFreeBodyPose(context=plant_context, body=base, X_WB=X_WB_desired)

See the notes on System Compatibility for further discussion.

PyPI (pip)

No candidate version for this platform

When installing Drake from PyPI on older platforms such as Ubuntu Focal, you may receive the error “no candidate version for this platform”. This is caused by older versions of pip which do not recognize the manylinux platform used by Drake. This is remedied by installing a newer version of pip.

Use of a Python virtual environment may be required in order to get a newer version of pip, e.g.:

python3 -m venv env
env/bin/pip install --upgrade pip
env/bin/pip install drake
source env/bin/activate

Build problems

Out of memory

When compiling Drake from source, the build might run out of memory. The error message will include the message, “cc: fatal error: Killed signal terminated program cc1plus”.

By default, the Drake build will try use all available CPU and RAM resources on the machine. Sometimes, when there is not enough RAM per CPU, the build might crash because it tried to run a compiler process on every vCPU and together those compilation jobs consumed more RAM than was available.

In this case, you’ll need to add a bazel configuration dotfile to your home directory. Create a text file at $HOME/.bazelrc with this content:

build --jobs=HOST_CPUS*0.4

This instructs the build system to use only 40% of the available vCPUs. You may tune the fraction up or down to balance build speed vs resource crashes. You may also specify an exact number like build --jobs=2 instead of a fraction.

The dotfile will affect any Bazel builds that you run. If you prefer to change only the Drake build instead of all Bazel builds, you may place the dotfile in the Drake source tree at drake/user.bazelrc instead of your home directory.

Note that the concurrency level passed to make (e.g., make -j 2) does not propagate through to affect the concurrency of most of Drake’s build steps; you need to configure the dotfile in order to control the build concurrency.