Skip to content

Commit f7e4b38

Browse files
matlabbeLong Vuong
authored andcommitted
Fixed superglue deadlock on standalone (introlab#896). Fixed some elemSize opencv asserts in debug build (876)
1 parent 59046f1 commit f7e4b38

11 files changed

Lines changed: 68 additions & 129 deletions

File tree

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -389,6 +389,7 @@ IF(WITH_PYTHON)
389389
FIND_PACKAGE(Python3 COMPONENTS Interpreter Development NumPy)
390390
IF(Python3_FOUND)
391391
MESSAGE(STATUS "Found Python3")
392+
FIND_PACKAGE(pybind11 REQUIRED)
392393
ENDIF(Python3_FOUND)
393394
ENDIF(WITH_PYTHON)
394395

corelib/include/rtabmap/core/PythonInterface.h

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -11,31 +11,31 @@
1111

1212
#include <string>
1313
#include <rtabmap/utilite/UMutex.h>
14-
#include <Python.h>
14+
15+
namespace pybind11 {
16+
class scoped_interpreter;
17+
class gil_scoped_release;
18+
}
1519

1620
namespace rtabmap {
1721

22+
/**
23+
* Create a single PythonInterface on main thread at
24+
* global scope before any Python classes.
25+
*/
1826
class PythonInterface
1927
{
2028
public:
2129
PythonInterface();
2230
virtual ~PythonInterface();
2331

24-
protected:
25-
std::string getTraceback(); // should be called between lock() and unlock()
26-
void lock();
27-
void unlock();
28-
2932
private:
30-
static UMutex mutex_;
31-
static int refCount_;
32-
33-
protected:
34-
static PyThreadState * mainThreadState_;
35-
static unsigned long mainThreadID_;
36-
PyThreadState * threadState_;
33+
pybind11::scoped_interpreter* guard_;
34+
pybind11::gil_scoped_release* release_;
3735
};
3836

37+
std::string getPythonTraceback();
38+
3939
}
4040

4141
#endif /* CORELIB_SRC_PYTHON_PYTHONINTERFACE_H_ */

corelib/src/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -209,6 +209,7 @@ IF(WITH_PYTHON AND Python3_FOUND)
209209
${LIBRARIES}
210210
Python3::Python
211211
Python3::NumPy
212+
pybind11::embed
212213
)
213214
SET(SRC_FILES
214215
${SRC_FILES}

corelib/src/DBDriverSqlite3.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4298,9 +4298,9 @@ void DBDriverSqlite3::saveQuery(const std::list<Signature *> & signatures)
42984298
{
42994299
_memoryUsedEstimate += (*i)->getMemoryUsed();
43004300
// raw data are not kept in database
4301-
_memoryUsedEstimate -= (*i)->sensorData().imageRaw().total() * (*i)->sensorData().imageRaw().elemSize();
4302-
_memoryUsedEstimate -= (*i)->sensorData().depthOrRightRaw().total() * (*i)->sensorData().depthOrRightRaw().elemSize();
4303-
_memoryUsedEstimate -= (*i)->sensorData().laserScanRaw().data().total() * (*i)->sensorData().laserScanRaw().data().elemSize();
4301+
_memoryUsedEstimate -= (*i)->sensorData().imageRaw().empty()?0:(*i)->sensorData().imageRaw().total() * (*i)->sensorData().imageRaw().elemSize();
4302+
_memoryUsedEstimate -= (*i)->sensorData().depthOrRightRaw().empty()?0:(*i)->sensorData().depthOrRightRaw().total() * (*i)->sensorData().depthOrRightRaw().elemSize();
4303+
_memoryUsedEstimate -= (*i)->sensorData().laserScanRaw().empty()?0:(*i)->sensorData().laserScanRaw().data().total() * (*i)->sensorData().laserScanRaw().data().elemSize();
43044304

43054305
stepNode(ppStmt, *i);
43064306
}

corelib/src/SensorData.cpp

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -810,23 +810,23 @@ void SensorData::setFeatures(const std::vector<cv::KeyPoint> & keypoints, const
810810
unsigned long SensorData::getMemoryUsed() const // Return memory usage in Bytes
811811
{
812812
return sizeof(SensorData) +
813-
_imageCompressed.total()*_imageCompressed.elemSize() +
814-
_imageRaw.total()*_imageRaw.elemSize() +
815-
_depthOrRightCompressed.total()*_depthOrRightCompressed.elemSize() +
816-
_depthOrRightRaw.total()*_depthOrRightRaw.elemSize() +
817-
_userDataCompressed.total()*_userDataCompressed.elemSize() +
818-
_userDataRaw.total()*_userDataRaw.elemSize() +
819-
_laserScanCompressed.data().total()*_laserScanCompressed.data().elemSize() +
820-
_laserScanRaw.data().total()*_laserScanRaw.data().elemSize() +
821-
_groundCellsCompressed.total()*_groundCellsCompressed.elemSize() +
822-
_groundCellsRaw.total()*_groundCellsRaw.elemSize() +
823-
_obstacleCellsCompressed.total()*_obstacleCellsCompressed.elemSize() +
824-
_obstacleCellsRaw.total()*_obstacleCellsRaw.elemSize()+
825-
_emptyCellsCompressed.total()*_emptyCellsCompressed.elemSize() +
826-
_emptyCellsRaw.total()*_emptyCellsRaw.elemSize()+
813+
(_imageCompressed.empty()?0:_imageCompressed.total()*_imageCompressed.elemSize()) +
814+
(_imageRaw.empty()?0:_imageRaw.total()*_imageRaw.elemSize()) +
815+
(_depthOrRightCompressed.empty()?0:_depthOrRightCompressed.total()*_depthOrRightCompressed.elemSize()) +
816+
(_depthOrRightRaw.empty()?0:_depthOrRightRaw.total()*_depthOrRightRaw.elemSize()) +
817+
(_userDataCompressed.empty()?0:_userDataCompressed.total()*_userDataCompressed.elemSize()) +
818+
(_userDataRaw.empty()?0:_userDataRaw.total()*_userDataRaw.elemSize()) +
819+
(_laserScanCompressed.empty()?0:_laserScanCompressed.data().total()*_laserScanCompressed.data().elemSize()) +
820+
(_laserScanRaw.empty()?0:_laserScanRaw.data().total()*_laserScanRaw.data().elemSize()) +
821+
(_groundCellsCompressed.empty()?0:_groundCellsCompressed.total()*_groundCellsCompressed.elemSize()) +
822+
(_groundCellsRaw.empty()?0:_groundCellsRaw.total()*_groundCellsRaw.elemSize()) +
823+
(_obstacleCellsCompressed.empty()?0:_obstacleCellsCompressed.total()*_obstacleCellsCompressed.elemSize()) +
824+
(_obstacleCellsRaw.empty()?0:_obstacleCellsRaw.total()*_obstacleCellsRaw.elemSize())+
825+
(_emptyCellsCompressed.empty()?0:_emptyCellsCompressed.total()*_emptyCellsCompressed.elemSize()) +
826+
(_emptyCellsRaw.empty()?0:_emptyCellsRaw.total()*_emptyCellsRaw.elemSize())+
827827
_keypoints.size() * sizeof(cv::KeyPoint) +
828828
_keypoints3D.size() * sizeof(cv::Point3f) +
829-
_descriptors.total()*_descriptors.elemSize();
829+
(_descriptors.empty()?0:_descriptors.total()*_descriptors.elemSize());
830830
}
831831

832832
void SensorData::clearCompressedData(bool images, bool scan, bool userData)

corelib/src/Signature.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -348,7 +348,7 @@ unsigned long Signature::getMemoryUsed(bool withSensorData) const // Return memo
348348
total += _words.size() * (sizeof(int)*2+sizeof(std::multimap<int, cv::KeyPoint>::iterator)) + sizeof(std::multimap<int, cv::KeyPoint>);
349349
total += _wordsKpts.size() * sizeof(cv::KeyPoint) + sizeof(std::vector<cv::KeyPoint>);
350350
total += _words3.size() * sizeof(cv::Point3f) + sizeof(std::vector<cv::Point3f>);
351-
total += _wordsDescriptors.total() * _wordsDescriptors.elemSize() + sizeof(cv::Mat);
351+
total += _wordsDescriptors.empty()?0:_wordsDescriptors.total() * _wordsDescriptors.elemSize() + sizeof(cv::Mat);
352352
total += _wordsChanged.size() * (sizeof(int)*2+sizeof(std::map<int, int>::iterator)) + sizeof(std::map<int, int>);
353353
if(withSensorData)
354354
{

corelib/src/python/PyDetector.cpp

Lines changed: 11 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@
1010
#include <rtabmap/utilite/UConversion.h>
1111
#include <rtabmap/utilite/UTimer.h>
1212

13+
#include <pybind11/embed.h>
14+
1315
#define NPY_NO_DEPRECATED_API NPY_API_VERSION
1416
#include <numpy/arrayobject.h>
1517

@@ -32,7 +34,7 @@ PyDetector::PyDetector(const ParametersMap & parameters) :
3234
return;
3335
}
3436

35-
lock();
37+
pybind11::gil_scoped_acquire acquire;
3638

3739
std::string matcherPythonDir = UDirectory::getDir(path_);
3840
if(!matcherPythonDir.empty())
@@ -54,15 +56,13 @@ PyDetector::PyDetector(const ParametersMap & parameters) :
5456
if(!pModule_)
5557
{
5658
UERROR("Module \"%s\" could not be imported! (File=\"%s\")", scriptName.c_str(), path_.c_str());
57-
UERROR("%s", getTraceback().c_str());
59+
UERROR("%s", getPythonTraceback().c_str());
5860
}
59-
60-
unlock();
6161
}
6262

6363
PyDetector::~PyDetector()
6464
{
65-
lock();
65+
pybind11::gil_scoped_acquire acquire;
6666

6767
if(pFunc_)
6868
{
@@ -72,8 +72,6 @@ PyDetector::~PyDetector()
7272
{
7373
Py_DECREF(pModule_);
7474
}
75-
76-
unlock();
7775
}
7876

7977
void PyDetector::parseParameters(const ParametersMap & parameters)
@@ -102,7 +100,7 @@ std::vector<cv::KeyPoint> PyDetector::generateKeypointsImpl(const cv::Mat & imag
102100
return keypoints;
103101
}
104102

105-
lock();
103+
pybind11::gil_scoped_acquire acquire;
106104

107105
if(!pFunc_)
108106
{
@@ -116,7 +114,7 @@ std::vector<cv::KeyPoint> PyDetector::generateKeypointsImpl(const cv::Mat & imag
116114
if(result == NULL)
117115
{
118116
UERROR("Call to \"init(...)\" in \"%s\" failed!", path_.c_str());
119-
UERROR("%s", getTraceback().c_str());
117+
UERROR("%s", getPythonTraceback().c_str());
120118
return keypoints;
121119
}
122120
Py_DECREF(result);
@@ -129,7 +127,7 @@ std::vector<cv::KeyPoint> PyDetector::generateKeypointsImpl(const cv::Mat & imag
129127
else
130128
{
131129
UERROR("Cannot find method \"detect(...)\" in %s", path_.c_str());
132-
UERROR("%s", getTraceback().c_str());
130+
UERROR("%s", getPythonTraceback().c_str());
133131
if(pFunc_)
134132
{
135133
Py_DECREF(pFunc_);
@@ -141,15 +139,15 @@ std::vector<cv::KeyPoint> PyDetector::generateKeypointsImpl(const cv::Mat & imag
141139
else
142140
{
143141
UERROR("Cannot call method \"init(...)\" in %s", path_.c_str());
144-
UERROR("%s", getTraceback().c_str());
142+
UERROR("%s", getPythonTraceback().c_str());
145143
return keypoints;
146144
}
147145
Py_DECREF(pFunc);
148146
}
149147
else
150148
{
151149
UERROR("Cannot find method \"init(...)\"");
152-
UERROR("%s", getTraceback().c_str());
150+
UERROR("%s", getPythonTraceback().c_str());
153151
return keypoints;
154152
}
155153
UDEBUG("init time = %fs", timer.ticks());
@@ -167,7 +165,7 @@ std::vector<cv::KeyPoint> PyDetector::generateKeypointsImpl(const cv::Mat & imag
167165
if(pReturn == NULL)
168166
{
169167
UERROR("Failed to call match() function!");
170-
UERROR("%s", getTraceback().c_str());
168+
UERROR("%s", getPythonTraceback().c_str());
171169
}
172170
else
173171
{
@@ -220,8 +218,6 @@ std::vector<cv::KeyPoint> PyDetector::generateKeypointsImpl(const cv::Mat & imag
220218
Py_DECREF(pImageBuffer);
221219
}
222220

223-
unlock();
224-
225221
return keypoints;
226222
}
227223

corelib/src/python/PyDetector.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
namespace rtabmap
1919
{
2020

21-
class PyDetector : public Feature2D, public PythonInterface
21+
class PyDetector : public Feature2D
2222
{
2323
public:
2424
PyDetector(const ParametersMap & parameters = ParametersMap());

corelib/src/python/PyMatcher.cpp

Lines changed: 11 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@
1010
#include <rtabmap/utilite/UConversion.h>
1111
#include <rtabmap/utilite/UTimer.h>
1212

13+
#include <pybind11/embed.h>
14+
1315
#define NPY_NO_DEPRECATED_API NPY_API_VERSION
1416
#include <numpy/arrayobject.h>
1517

@@ -39,7 +41,7 @@ PyMatcher::PyMatcher(
3941
return;
4042
}
4143

42-
lock();
44+
pybind11::gil_scoped_acquire acquire;
4345

4446
std::string matcherPythonDir = UDirectory::getDir(path_);
4547
if(!matcherPythonDir.empty())
@@ -59,15 +61,13 @@ PyMatcher::PyMatcher(
5961
if(!pModule_)
6062
{
6163
UERROR("Module \"%s\" could not be imported! (File=\"%s\")", scriptName.c_str(), path_.c_str());
62-
UERROR("%s", getTraceback().c_str());
64+
UERROR("%s", getPythonTraceback().c_str());
6365
}
64-
65-
unlock();
6666
}
6767

6868
PyMatcher::~PyMatcher()
6969
{
70-
lock();
70+
pybind11::gil_scoped_acquire acquire;
7171
if(pFunc_)
7272
{
7373
Py_DECREF(pFunc_);
@@ -76,7 +76,6 @@ PyMatcher::~PyMatcher()
7676
{
7777
Py_DECREF(pModule_);
7878
}
79-
unlock();
8079
}
8180

8281
std::vector<cv::DMatch> PyMatcher::match(
@@ -104,7 +103,7 @@ std::vector<cv::DMatch> PyMatcher::match(
104103
imageSize.width>0 && imageSize.height>0)
105104
{
106105

107-
lock();
106+
pybind11::gil_scoped_acquire acquire;
108107

109108
UDEBUG("matchThreshold=%f, iterations=%d, cuda=%d", matchThreshold_, iterations_, cuda_?1:0);
110109

@@ -120,7 +119,7 @@ std::vector<cv::DMatch> PyMatcher::match(
120119
if(result == NULL)
121120
{
122121
UERROR("Call to \"init(...)\" in \"%s\" failed!", path_.c_str());
123-
UERROR("%s", getTraceback().c_str());
122+
UERROR("%s", getPythonTraceback().c_str());
124123
return matches;
125124
}
126125
Py_DECREF(result);
@@ -133,7 +132,7 @@ std::vector<cv::DMatch> PyMatcher::match(
133132
else
134133
{
135134
UERROR("Cannot find method \"match(...)\" in %s", path_.c_str());
136-
UERROR("%s", getTraceback().c_str());
135+
UERROR("%s", getPythonTraceback().c_str());
137136
if(pFunc_)
138137
{
139138
Py_DECREF(pFunc_);
@@ -145,15 +144,15 @@ std::vector<cv::DMatch> PyMatcher::match(
145144
else
146145
{
147146
UERROR("Cannot call method \"init(...)\" in %s", path_.c_str());
148-
UERROR("%s", getTraceback().c_str());
147+
UERROR("%s", getPythonTraceback().c_str());
149148
return matches;
150149
}
151150
Py_DECREF(pFunc);
152151
}
153152
else
154153
{
155154
UERROR("Cannot find method \"init(...)\"");
156-
UERROR("%s", getTraceback().c_str());
155+
UERROR("%s", getPythonTraceback().c_str());
157156
return matches;
158157
}
159158
UDEBUG("init time = %fs", timer.ticks());
@@ -216,7 +215,7 @@ std::vector<cv::DMatch> PyMatcher::match(
216215
if(pReturn == NULL)
217216
{
218217
UERROR("Failed to call match() function!");
219-
UERROR("%s", getTraceback().c_str());
218+
UERROR("%s", getPythonTraceback().c_str());
220219
}
221220
else
222221
{
@@ -260,7 +259,6 @@ std::vector<cv::DMatch> PyMatcher::match(
260259

261260
UDEBUG("Fill matches (%d/%d) and cleanup time = %fs", matches.size(), std::min(descriptorsQuery.rows, descriptorsTrain.rows), timer.ticks());
262261
}
263-
unlock();
264262
}
265263
else
266264
{

corelib/src/python/PyMatcher.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
namespace rtabmap
1717
{
1818

19-
class PyMatcher : public PythonInterface
19+
class PyMatcher
2020
{
2121
public:
2222
PyMatcher(const std::string & pythonMatcherPath,

0 commit comments

Comments
 (0)