RobotLocomotion / drake

Model-based design and verification for robotics.
https://drake.mit.edu
Other
3.34k stars 1.27k forks source link

PYDRAKE_PREVENT_PYTHON3_MODULE_REIMPORT causes failures under python3-dbg #11868

Closed jamiesnape closed 5 years ago

jamiesnape commented 5 years ago

Assertion fails within python3-dbg version 3.6.8 on Bionic:

$ bazel test --python_path=/usr/bin/python3-dbg --action_env=DRAKE_PYTHON_BIN_PATH=/usr/bin/python3-dbg ...

...

python3-dbg: ../Modules/gcmodule.c:380: visit_decref: Assertion `_PyGCHead_REFS(gc) != 0' failed.
external/bazel_tools/tools/test/test-setup.sh: line 310: 11800 Aborted                 (core dumped) "${TEST_PATH}" "$@" 2>&1
jamiesnape commented 5 years ago

Actually, not all tests, but the following:

//bindings/pydrake:py/all_test
//bindings/pydrake:py/automotive_test
//bindings/pydrake:py/geometry_test
//bindings/pydrake:py/perception_test
//bindings/pydrake/attic:py/attic_forwarding_test
//bindings/pydrake/attic/multibody:py/rigid_body_plant_test
//bindings/pydrake/attic/systems:py/controllers_test
//bindings/pydrake/attic/systems:py/sensors_test
//bindings/pydrake/doc:gen_sphinx_test
//bindings/pydrake/examples:py/acrobot_test
//bindings/pydrake/examples:py/compass_gait_test
//bindings/pydrake/examples:py/manipulation_station_test
//bindings/pydrake/examples:py/pendulum_test
//bindings/pydrake/examples:py/quadrotor_test
//bindings/pydrake/examples:py/rimless_wheel_test
//bindings/pydrake/examples:py/van_der_pol_test
//bindings/pydrake/examples/multibody:cart_pole_passive_simulation_test
//bindings/pydrake/examples/multibody:pendulum_lqr_monte_carlo_analysis_test
//bindings/pydrake/maliput:py/maliput_test
//bindings/pydrake/manipulation:py/planner_test
//bindings/pydrake/manipulation:py/simple_ui_test
//bindings/pydrake/multibody:py/inverse_kinematics_test
//bindings/pydrake/multibody:py/parsing_test
//bindings/pydrake/multibody:py/plant_test
//bindings/pydrake/solvers:py/ipopt_solver_test
//bindings/pydrake/solvers:py/mathematicalprogram_test
//bindings/pydrake/solvers:py/nlopt_solver_test
//bindings/pydrake/solvers:py/osqp_solver_test
//bindings/pydrake/solvers:py/scs_solver_test
//bindings/pydrake/systems:drawing_graphviz_example_test
//bindings/pydrake/systems:py/controllers_test
//bindings/pydrake/systems:py/custom_test
//bindings/pydrake/systems:py/general_test
//bindings/pydrake/systems:py/lcm_test
//bindings/pydrake/systems:py/lifetime_test
//bindings/pydrake/systems:py/meshcat_visualizer_test
//bindings/pydrake/systems:py/monte_carlo_test
//bindings/pydrake/systems:py/perception_test
//bindings/pydrake/systems:py/primitives_test
//bindings/pydrake/systems:py/rendering_test
//bindings/pydrake/systems:py/scalar_conversion_test
//bindings/pydrake/systems:py/sensors_test
//bindings/pydrake/systems:py/trajectory_optimization_test
//bindings/pydrake/systems:py/value_test
//examples/manipulation_station:end_effector_teleop_mouse_test
//examples/manipulation_station:end_effector_teleop_sliders_test
//examples/manipulation_station:joint_teleop_test
//examples/manipulation_station:print_station_context_test
//examples/van_der_pol:plot_limit_cycle_test
//manipulation/util:py/geometry_inspector_test
//manipulation/util:py/show_model_test
EricCousineau-TRI commented 5 years ago

Can reproduce this error if you just have a single file that just imports an offending module:

import pydrake.systems.framework

No code necessary.

EDIT: More specifically, in framework_py.cc, if I only have DefineFrameworkPyValues(m) (and comment out the others), it still fails. Further bisection...

EDIT 2: From more investigation, seems like AddValueInstantiation may be the offending code. Commenting out this snippet removes the failure when just doing an import: https://github.com/RobotLocomotion/drake/blob/53983b70189029ff30172d6357d36c289141e1b4/bindings/pydrake/systems/framework_py_values.cc#L159-L176

EDIT 3: Or perhaps AddTemplateClass: https://github.com/RobotLocomotion/drake/blob/1051d639123b0565919ecd93e0c3f6b831b3ae8e/bindings/pydrake/common/value_pybind.h#L31

Though //bindings/pydrake/common:py/cpp_template_pybind_test doesn't emit any warnings (although it has a scoped interpreter...)

EDIT 4: Or perhaps... PYDRAKE_PREVENT_PYTHON3_MODULE_REIMPORT: https://github.com/RobotLocomotion/drake/blob/f529b99d5/bindings/pydrake/common/value_pybind.h#L31

EricCousineau-TRI commented 5 years ago

Yup, confirmed that it's the PYDRAKE_PREVENT_PYTHON3_MODULE_REIMPORT hack: b9d060b5d

@jamiesnape Can you try to see if there's simple enough workaround / fix for this? If not, I can look into more on Thursday.

EricCousineau-TRI commented 5 years ago

If we can't find a workaround, we can always re-engineer the imports to not be cyclic. First part would be address the TODO to move Value<> stuff outside of pydrake.systems.framework and into pydrake.common.

jamiesnape commented 5 years ago

@jamiesnape Can you try to see if there's simple enough workaround / fix for this? If not, I can look into more on Thursday.

Sure, let me catch up with the history of that code and I will get back to you.

jamiesnape commented 5 years ago

If we can't find a workaround, we can always re-engineer the imports to not be cyclic.

I think it makes sense to do this anyway. I don't think I have a workaround that I am confident does not have unintended side effects.

EricCousineau-TRI commented 5 years ago

FTR, this workaround (one-liner) suppresses the warning: 42ed5c513