[C++] Segfault accessing element of SX matrix

112 views
Skip to first unread message

Max Basescu

unread,
Apr 3, 2023, 3:46:16 PM4/3/23
to CasADi
Hi all,

I'm noticing an issue when using the C++ interface for CasADi where SX element access will sometimes segfault. Attached is a simplified example of the code where the segfault occurs, although I'm having trouble reproducing it in isolation from the rest of my application. Worth noting that I never see the issue on the first instantiation / usage of a matrix with this sparsity pattern, only on subsequent later instantiations after the previous matrix objects have gone out of scope. I've also attached the relevant portion of a stack trace for the segfault. Based on this stacktrace and the context in which the error occurs, I suspect there may be some issue with the sparsity caching mechanism in `Sparsity::assign_cached()`. I have tried disabling the use of previously cached sparsity patterns by commenting out the if (bucket_count_before>0)
block in `assign_cached()`, but this didn't seem to fix the issue.

Does this issue match any known limitations with the sparsity caching / garbage collection approach? If not, let me know if there is any additional context that I can provide to gain clarity on the root cause of the issue.

0x00007f81abe9ec21 in casadi::Sparsity::nnz() const ()
1655940    from /opt/user/install/lib/libcasadi.so.3.6
1655941 #0  0x00007f81abe9ec21 in casadi::Sparsity::nnz() const ()
1655942    from /opt/user/install/lib/libcasadi.so.3.6
1655943 #1  0x00007f81abde85ab in casadi::Matrix<casadi::SXElem>::Matrix(casadi::Sparsity const&, casadi::SXElem const&, bool) ()
1655944    from /opt/user/install/lib/libcasadi.so.3.6
1655945 #2  0x00007f81abdf49da in casadi::Matrix<casadi::SXElem>::get_nz(casadi::Matrix<casadi::SXElem>&, bool, casadi::Matrix<long long> const&) const ()
1655946    from /opt/user/install/lib/libcasadi.so.3.6
1655947 #3  0x00007f81abdf59ca in casadi::Matrix<casadi::SXElem>::get(casadi::Matrix<casadi::SXElem>&, bool, casadi::Matrix<long long> const&) const ()
1655948    from /opt/user/install/lib/libcasadi.so.3.6
1655949 #4  0x00007f81ac6b630b in casadi::GenericMatrix<casadi::Matrix<casadi::SXElem> >::operator()<long> (rr=<synthetic pointer>, this=0x7fff5f600390)
1655950     at /opt/user/install/include/casadi/core/generic_matrix.hpp:212

const casadi::SX matrix{ casadi::SX::sym("test", 5) };
std::cout << matrix(0).get_elements().front() << std::endl;

Joel Andersson

unread,
Apr 3, 2023, 9:22:35 PM4/3/23
to CasADi
I'm not able to reproduce the segfault on my system. You can create an issue for it in github, specifying the version of CasADi you're using and your system, especially which compiler you're using. But if we can't reproduce it on our systems, we're probably can't get much further.

Best,
Joel

Max Basescu

unread,
Apr 3, 2023, 11:03:43 PM4/3/23
to CasADi
Understood! I knew the code snippet was too minimalistic to reproduce the issue with, was just kind of hoping it looked like a familiar bug :).

At this point I've traced it a bit further and believe the static `ScalarSparsity` in `Sparsity::getScalar()` is somehow getting corrupted. As far as I understand, the row index passed into the `operator()` call is getting implicitly converted into a `Matrix<casadi_int>` via the `Matrix(double val)` constructor when `self().get(ret, false, rr)` is called from `GenericMatrix`, and somehow the sparsity object corresponding to the converted `const Matrix<casadi_int>& rr` object is getting set to the sparsity object for the original `matrix` object (`sp_.size()` is identical, and so is the memory address returned by `colind()`). When I see the correct non-crashing behavior, the sparsity pattern for the row index matrix has the correct `sp_.size() == 5` and a static memory address for `colind()`. I'm checking this with some prints in `SparsityInternal`, where I see the attached output during an `operator()` function call directly before the crash. Anyway, I'm going to keep digging and will try to figure out more, but let me know if any of this starts ringing bells.

/// Number of structural non-zeros
inline casadi_int nnz() const {
std::cout << "In nnz()" << std::endl;
std::cout << "size2(): " << size2() << std::endl;
std::cout << "sp_.size(): " << sp_.size() << std::endl;
std::cout << "colind(): " << colind() << std::endl;
return colind()[size2()];
}

----------------------------------------------

Constructing symbolic matrix with name: state_0
70098724 Creating new sparsity pattern (not using cache)
70098725 In nnz()
70098726 size2(): 1
70098727 sp_.size(): 9
70098728 colind(): 0x244f6c0
70098729 In nnz()
70098730 size2(): 1
70098731 sp_.size(): 9
70098732 colind(): 0x244f6c0
70098733 In nnz()
70098734 size2(): 1
70098735 sp_.size(): 9
70098736 colind(): 0x244f6c0
70098737 In nnz()
70098738 size2(): 1
70098739 sp_.size(): 9
70098740 colind(): 0x244f6c0
70098741 In nnz()
70098742 size2(): 1
70098743 sp_.size(): 9
70098744 colind(): 0x244f6c0
70098745 In nnz()
70098746 size2(): 1
70098747 sp_.size(): 9
70098748 colind(): 0x244f6c0
70098749 In nnz()
70098750 size2(): 1
70098751 sp_.size(): 9
70098752 colind(): 0x244f6c0
70098753 Symbolic vector row size: 5
70098754 Symbolic vector column size: 1
-------------------------------------------------
Accessing matrix element (0):
70098756 In GenericMatrix::operator()
In void Matrix<Scalar>::get(Matrix<Scalar>& m, bool ind1, const Matrix<casadi_int>& rr)
70098758 In nnz()
70098759 size2(): 1
70098760 sp_.size(): 9
70098761 colind(): 0x244f6c0
70098762 In nnz()
70098763 size2(): 1
70098764 sp_.size(): 9
70098765 colind(): 0x244f6c0
Reply all
Reply to author
Forward
0 new messages