drake
drake copied to clipboard
`HPolyhedron` to `VPolytope` randomly segfaults on Gurobi
What happened?
I have a simple snippet that tries to convert from HPolyedron to VPolytope - but this seems to segfault randomly 20% of the time. This seems very strange given that I'm running this snippet with the exact same problem data.
import numpy as np
from pydrake.all import (
VPolytope,
HPolyhedron
)
A_du_poly = np.load("A_poly.npy")
b_du_poly = np.load("b_poly.npy")
while True:
du_polytope_h = HPolyhedron(A_du_poly, b_du_poly)
du_polytope_v = VPolytope(du_polytope_h)
Ideally this code should run forever - but after some random time it segfaults.
The ambient dimension is 6, there are 56 faces, and I've uploaded the files here for reproducing the bug.
GDB says
Thread 1 "python" received signal SIGSEGV, Segmentation fault.
0x00007fffa573c9f3 in Eigen::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >(Eigen::EigenBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&) () from /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so
and I've attached the valgrind log in the relevant log output section which I've run on a debug-build of Drake.
Version
efa53019f71c18c5a714200612fac475a0910f7b
What operating system are you using?
Ubuntu 22.04
What installation option are you using?
compiled from source code using CMake
Relevant log output
==148549== Memcheck, a memory error detector
==148549== Copyright (C) 2002-2017, and GNU GPL'd, by Julian Seward et al.
==148549== Using Valgrind-3.18.1 and LibVEX; rerun with -h for copyright info
==148549== Command: python sandbox/iiwa_bimanual_planar/debug_qhull.py --track_origins=yes --leak-check=full
==148549==
==148549== Conditional jump or move depends on uninitialised value(s)
==148549== at 0x61821089: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x4D3DF67: __pthread_once_slow (pthread_once.c:116)
==148549== by 0x61820F79: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x400647D: call_init.part.0 (dl-init.c:70)
==148549== by 0x4006567: call_init (dl-init.c:33)
==148549== by 0x4006567: _dl_init (dl-init.c:117)
==148549== by 0x4E18C84: _dl_catch_exception (dl-error-skeleton.c:182)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:808)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:771)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x400E34D: _dl_open (dl-open.c:883)
==148549== by 0x4D346BB: dlopen_doit (dlopen.c:56)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x4E18CF2: _dl_catch_error (dl-error-skeleton.c:227)
==148549==
==148549== Conditional jump or move depends on uninitialised value(s)
==148549== at 0x61821096: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x4D3DF67: __pthread_once_slow (pthread_once.c:116)
==148549== by 0x61820F79: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x400647D: call_init.part.0 (dl-init.c:70)
==148549== by 0x4006567: call_init (dl-init.c:33)
==148549== by 0x4006567: _dl_init (dl-init.c:117)
==148549== by 0x4E18C84: _dl_catch_exception (dl-error-skeleton.c:182)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:808)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:771)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x400E34D: _dl_open (dl-open.c:883)
==148549== by 0x4D346BB: dlopen_doit (dlopen.c:56)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x4E18CF2: _dl_catch_error (dl-error-skeleton.c:227)
==148549==
==148549== Conditional jump or move depends on uninitialised value(s)
==148549== at 0x484EFED: strncpy (vg_replace_strmem.c:599)
==148549== by 0x618210B5: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x4D3DF67: __pthread_once_slow (pthread_once.c:116)
==148549== by 0x61820F79: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x400647D: call_init.part.0 (dl-init.c:70)
==148549== by 0x4006567: call_init (dl-init.c:33)
==148549== by 0x4006567: _dl_init (dl-init.c:117)
==148549== by 0x4E18C84: _dl_catch_exception (dl-error-skeleton.c:182)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:808)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:771)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x400E34D: _dl_open (dl-open.c:883)
==148549== by 0x4D346BB: dlopen_doit (dlopen.c:56)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549==
==148549== Conditional jump or move depends on uninitialised value(s)
==148549== at 0x484F017: strncpy (vg_replace_strmem.c:599)
==148549== by 0x618210B5: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x4D3DF67: __pthread_once_slow (pthread_once.c:116)
==148549== by 0x61820F79: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x400647D: call_init.part.0 (dl-init.c:70)
==148549== by 0x4006567: call_init (dl-init.c:33)
==148549== by 0x4006567: _dl_init (dl-init.c:117)
==148549== by 0x4E18C84: _dl_catch_exception (dl-error-skeleton.c:182)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:808)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:771)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x400E34D: _dl_open (dl-open.c:883)
==148549== by 0x4D346BB: dlopen_doit (dlopen.c:56)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549==
==148549== Conditional jump or move depends on uninitialised value(s)
==148549== at 0x484F08F: strncpy (vg_replace_strmem.c:599)
==148549== by 0x618210B5: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x4D3DF67: __pthread_once_slow (pthread_once.c:116)
==148549== by 0x61820F79: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x400647D: call_init.part.0 (dl-init.c:70)
==148549== by 0x4006567: call_init (dl-init.c:33)
==148549== by 0x4006567: _dl_init (dl-init.c:117)
==148549== by 0x4E18C84: _dl_catch_exception (dl-error-skeleton.c:182)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:808)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:771)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x400E34D: _dl_open (dl-open.c:883)
==148549== by 0x4D346BB: dlopen_doit (dlopen.c:56)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549==
==148549== Use of uninitialised value of size 8
==148549== at 0x618210BD: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x4D3DF67: __pthread_once_slow (pthread_once.c:116)
==148549== by 0x61820F79: ??? (in /home/terry/Documents/drake/build/install/lib/libtbb.so.12.8)
==148549== by 0x400647D: call_init.part.0 (dl-init.c:70)
==148549== by 0x4006567: call_init (dl-init.c:33)
==148549== by 0x4006567: _dl_init (dl-init.c:117)
==148549== by 0x4E18C84: _dl_catch_exception (dl-error-skeleton.c:182)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:808)
==148549== by 0x400DFF5: dl_open_worker (dl-open.c:771)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x400E34D: _dl_open (dl-open.c:883)
==148549== by 0x4D346BB: dlopen_doit (dlopen.c:56)
==148549== by 0x4E18C27: _dl_catch_exception (dl-error-skeleton.c:208)
==148549== by 0x4E18CF2: _dl_catch_error (dl-error-skeleton.c:227)
==148549==
Set parameter Username
Academic license - for non-commercial use only - expires 2024-09-11
==148549== Use of uninitialised value of size 8
==148549== at 0x5A57E9F3: Eigen::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >(Eigen::EigenBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&) (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x5DAA636A: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549==
==148549== Invalid read of size 8
==148549== at 0x5DAA6480: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:112)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:99)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:123)
==148549== by 0x251095: UnknownInlinedFun (ceval.c:5893)
==148549== by 0x251095: _PyEval_EvalFrameDefault (ceval.c:4213)
==148549== Address 0x56b6ac10 is 0 bytes inside a block of size 40 free'd
==148549== at 0x484B27F: free (vg_replace_malloc.c:872)
==148549== by 0x5A4958A0: Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::resize(long, long) (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x5DAA63F1: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== Block was alloc'd at
==148549== at 0x4848899: malloc (vg_replace_malloc.c:381)
==148549== by 0x5DAA663E: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549==
==148549== Invalid read of size 16
==148549== at 0x5DAA64AD: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:112)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:99)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:123)
==148549== by 0x251095: UnknownInlinedFun (ceval.c:5893)
==148549== by 0x251095: _PyEval_EvalFrameDefault (ceval.c:4213)
==148549== Address 0x56b6ac18 is 8 bytes inside a block of size 40 free'd
==148549== at 0x484B27F: free (vg_replace_malloc.c:872)
==148549== by 0x5A4958A0: Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::resize(long, long) (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x5DAA63F1: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== Block was alloc'd at
==148549== at 0x4848899: malloc (vg_replace_malloc.c:381)
==148549== by 0x5DAA663E: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549==
==148549== Invalid read of size 8
==148549== at 0x5DAA64D0: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:112)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:99)
==148549== by 0x251095: UnknownInlinedFun (abstract.h:123)
==148549== by 0x251095: UnknownInlinedFun (ceval.c:5893)
==148549== by 0x251095: _PyEval_EvalFrameDefault (ceval.c:4213)
==148549== Address 0x5347e00 is 32 bytes inside a block of size 40 free'd
==148549== at 0x484B27F: free (vg_replace_malloc.c:872)
==148549== by 0x5A4958A0: Eigen::PlainObjectBase<Eigen::Matrix<double, -1, 1, 0, -1, 1> >::resize(long, long) (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x5DAA63F1: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== Block was alloc'd at
==148549== at 0x4848899: malloc (vg_replace_malloc.c:381)
==148549== by 0x5DAA663E: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549==
==148549== Invalid read of size 4
==148549== at 0x5A57E9F3: Eigen::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >(Eigen::EigenBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&) (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x5DAA636A: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== Address 0x110cdbb24 is not stack'd, malloc'd or (recently) free'd
==148549==
==148549==
==148549== Process terminating with default action of signal 11 (SIGSEGV)
==148549== Access not within mapped region at address 0x110CDBB24
==148549== at 0x5A57E9F3: Eigen::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >::PartialPivLU<Eigen::Matrix<double, -1, -1, 0, -1, -1> >(Eigen::EigenBase<Eigen::Matrix<double, -1, -1, 0, -1, -1> > const&) (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x5DAA636A: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x5DAA61A6: drake::geometry::optimization::VPolytope::VPolytope(drake::geometry::optimization::HPolyhedron const&, double) (in /home/terry/Documents/drake/build/install/lib/libdrake.so)
==148549== by 0x66E0CD1C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x66D0B2BB: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/geometry/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x26210D: cfunction_call.lto_priv.0 (methodobject.c:543)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:112)
==148549== by 0x270C1F: UnknownInlinedFun (abstract.h:99)
==148549== by 0x270C1F: method_vectorcall (classobject.c:83)
==148549== by 0x26D086: slot_tp_init.lto_priv.0 (typeobject.c:7737)
==148549== by 0x258E2A: type_call.lto_priv.0 (typeobject.c:1135)
==148549== by 0x5A2CA52C: ??? (in /home/terry/Documents/drake/build/install/lib/python3.10/site-packages/pydrake/common/__init__.cpython-310-x86_64-linux-gnu.so)
==148549== by 0x258A7A: _PyObject_MakeTpCall (call.c:215)
==148549== If you believe this happened as a result of a stack
==148549== overflow in your program's main thread (unlikely but
==148549== possible), you can try to increase the size of the
==148549== main thread stack using the --main-stacksize= flag.
==148549== The main thread stack size used in this run was 8388608.
==148549==
==148549== HEAP SUMMARY:
==148549== in use at exit: 24,623,563 bytes in 99,476 blocks
==148549== total heap usage: 324,743 allocs, 225,267 frees, 116,349,193 bytes allocated
==148549==
==148549== LEAK SUMMARY:
==148549== definitely lost: 128 bytes in 2 blocks
==148549== indirectly lost: 0 bytes in 0 blocks
==148549== possibly lost: 303,199 bytes in 319 blocks
==148549== still reachable: 24,320,236 bytes in 99,155 blocks
==148549== suppressed: 0 bytes in 0 blocks
==148549== Rerun with --leak-check=full to see details of leaked memory
==148549==
==148549== Use --track-origins=yes to see where uninitialised values come from
==148549== For lists of detected and suppressed errors, rerun with: -s
==148549== ERROR SUMMARY: 121 errors from 11 contexts (suppressed: 0 from 0)
Segmentation fault (core dumped)
Update: This error only seems to happen when Gurobi is used as a LP solver. I am not seeing any segfaults in Mosek or Clarabel, which is very interesting.
It seems from reading the Eigen docs that the partialPivLu should have been safe as a temporary, but maybe it's not. Try changing some of the terms on that line into named locals, e.g., like this:
--- a/geometry/optimization/vpolytope.cc
+++ b/geometry/optimization/vpolytope.cc
@@ -343,9 +343,9 @@ VPolytope::VPolytope(const HPolyhedron& hpoly, const double tol)
vertex_A.row(jj) = Eigen::Map<Eigen::RowVectorXd, Eigen::Unaligned>(
hyperplane.data(), hyperplane.size());
}
- vertices_.col(ii) = vertex_A.partialPivLu().solve(
- VectorXd::Ones(incident_hyperplanes.count())) +
- eigen_center;
+ const VectorXd foo = vertex_A.partialPivLu().solve(
+ VectorXd::Ones(incident_hyperplanes.count()));
+ vertices_.col(ii) = foo + eigen_center;
ii++;
}
}
I tried the suggestion, and it still segfaults at the partialPivLu line (before adding eigen_center).
I looked into this a bit more, and it seems like the segfault happens because sometimes vertex_A is not a square matrix in this line
https://github.com/RobotLocomotion/drake/blob/14f202659212304462cca960f18ec8d557d86a2e/geometry/optimization/vpolytope.cc#L339
with incident_hyperplanes.count() = 6 and hpoly.ambient_dimension() = 5 for the above example. But partialPivLu can only be done in square invertible matrices. Ideally Eigen should check for squareness before segfaulting.
I'm guessing it's probably not related to #20985, but you could try building off the code in #21009, which fixes that bug. But I don't see how that bug could lead to the matrix not being square.
I'll keep backtracking, but the trouble happens in this line: https://github.com/RobotLocomotion/drake/blob/14f202659212304462cca960f18ec8d557d86a2e/geometry/optimization/vpolytope.cc#L282
At the first pass through the constructor, the ambient dimension (6) is bigger than the affine dimension (5), and it goes through affine change of basis to create hpoly_subspace which now has an ambient dimension of 5. Then this is passed through the constructor again, and this is where it fails.
The question is: why is incident_hyperplanes.count() sometimes larger than the ambient dimension on our second pass through the constructor? and why does it only happen on Gurobi?
@cohnt is it possible for some facets to have vertices more than the ambient dimension ever? Most facets have number of vertices equal to ambient dimension, but one(or more) doesn't.
I'm guessing it's probably not related to #20985, but you could try building off the code in #21009, which fixes that bug. But I don't see how that bug could lead to the matrix not being square.
yep - I tried this branch and confirm it still segfaults
Yup, I just gave it back to @hongkai-dai. I don't expect to work on this at all.
Hopefully the GCS crew can solve it.
@jwnimmer-tri while we investigate with Hongkai, do you think it's a good idea if I submit a very short PR that does DRAKE_THROW_UNLESS for squareness of the matrix before it goes through partialPivLu?
Yes, it's always a good idea to convert segfaults into exceptions.
I also seem to be hitting this bug sometimes! Sometimes, but not always, calling ReduceInequalities with a higher value for tol helps. It. would be nice to have a bit more intuition for what exactly is breaking
Update: This error only seems to happen when Gurobi is used as a LP solver. I am not seeing any segfaults in Mosek or Clarabel, which is very interesting. I don't think this has anything to do with the convex solvers. You likely just have a relatively flat polytope that Gurobi and Mosek are performing slightly differently on.
is it possible for some facets to have vertices more than the ambient dimension ever? Most facets have number of vertices equal to ambient dimension, but one(or more) doesn't.
I think the question you're asking @hjsuh94 is whether more faces than the ambient dimension can be active at a vertex, even if the polytope is "clean" (i.e. it doesn't have any redundant faces). The answer is yes.
The simplest example and a MWE that triggers DRAKE_THROW_UNLESS(incident_hyperplanes.count() == hpoly.ambient_dimension()); is
HPolyhedron H=HPolyhedron::MakeL1Ball(3);
VPolytope V(H);
The reason this happens is because the L1 ball in 3 dimensions is "degenerate" in the sense that 4 hyperplanes are active at every vertex, and therefore QHull identifies these 4 planes for every vertex. However, the resulting linear system is full column rank and so is fine to solve. Switching the linear solver is the fix given in #21527