Skip to content

Fix https://github.com/jsk-ros-pkg/jsk_recognition/issues/2860 #2866

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 2 commits into from
May 2, 2025

Conversation

mqcmd196
Copy link
Member

close #2860

libsiftfast has so many static global variables, so it is not thread-safe when called from multiple nodelets. This PR adds a global mutex to restrict the access to those variables to make it thread-safe.

Since the entire mutex is taken, if n imagesift nodelet are loaded, the time required to compute each feature is n times longer. But I think it is fine because the node is implemented with ConnectionBasedNodelet. If the user doesn't subscribe, the slow calculation doesn't occur. Making the user code work is much important.

The clean method is to make libsiftfast thread-safe, but I think we should write it from scratch or use OpenCV if we do so.

You can try the bug occurs just reverting 365b2d0 and execute test_two_imagesift.test

@mqcmd196 mqcmd196 requested review from iory and k-okada April 15, 2025 13:46
@mqcmd196 mqcmd196 force-pushed the fix-imagesift-segfault branch from fbeae6a to 08ed039 Compare April 23, 2025 02:23
@mqcmd196
Copy link
Member Author

requests.exceptions.ConnectionError: HTTPConnectionPool(host='jenkins.jsk.imi.i.u-tokyo.ac.jp', port=8080): Max retries exceeded with url: /crumbIssuer/api/json (Caused by NewConnectionError('<urllib3.connection.HTTPConnection object at 0x7f22e150c5d0>: Failed to establish a new connection: [Errno -5] No address associated with hostname',))

@mqcmd196
Copy link
Member Author

CI green

@k-okada
Copy link
Member

k-okada commented Apr 28, 2025

can you compare calculation speed in single thread with and whitout this PR? because libsiftfast is originally developed to pursue high speed processing by several optimization technique, so I'd like to know how this changes the performance.

@mqcmd196
Copy link
Member Author

calculation speed in single thread

What do you mean? Making the nodelet's num_worker_thread=1 or making the libsiftfast's OpenMP flag OFF?

@k-okada
Copy link
Member

k-okada commented May 1, 2025

sorry
x single thread
o single nodelet
I just want to know if adding global mutex lock affect comptation speed .

@mqcmd196 mqcmd196 force-pushed the fix-imagesift-segfault branch from 08ed039 to 1cfce13 Compare May 1, 2025 13:24
@mqcmd196
Copy link
Member Author

mqcmd196 commented May 1, 2025

I've tested the performance with launching roslaunch imagesift test_imagesift.test

With this PR

❯ rostopic hz /Feature0D
subscribed to [/Feature0D]
average rate: 4.721
        min: 0.212s max: 0.212s std dev: 0.00000s window: 2
average rate: 5.819
        min: 0.143s max: 0.212s std dev: 0.02245s window: 8
average rate: 5.846
        min: 0.143s max: 0.212s std dev: 0.01867s window: 14
average rate: 5.835
        min: 0.143s max: 0.212s std dev: 0.01760s window: 19
average rate: 5.890
        min: 0.143s max: 0.212s std dev: 0.01553s window: 25
average rate: 5.883
        min: 0.143s max: 0.212s std dev: 0.01401s window: 31
average rate: 5.904
        min: 0.143s max: 0.212s std dev: 0.01329s window: 37
average rate: 5.984
        min: 0.143s max: 0.212s std dev: 0.01325s window: 44
average rate: 6.029
        min: 0.143s max: 0.212s std dev: 0.01290s window: 50
average rate: 6.078
        min: 0.143s max: 0.212s std dev: 0.01261s window: 57
average rate: 6.099
        min: 0.143s max: 0.212s std dev: 0.01221s window: 63
average rate: 6.127
        min: 0.143s max: 0.212s std dev: 0.01191s window: 69
average rate: 6.151
        min: 0.143s max: 0.212s std dev: 0.01157s window: 76
average rate: 6.171
        min: 0.143s max: 0.212s std dev: 0.01131s window: 82
average rate: 6.192
        min: 0.143s max: 0.212s std dev: 0.01101s window: 89
average rate: 6.206
        min: 0.143s max: 0.212s std dev: 0.01079s window: 95
average rate: 6.222
        min: 0.143s max: 0.212s std dev: 0.01054s window: 102
average rate: 6.231
        min: 0.143s max: 0.212s std dev: 0.01031s window: 108
average rate: 6.242
        min: 0.143s max: 0.212s std dev: 0.01011s window: 114
average rate: 6.247
        min: 0.143s max: 0.212s std dev: 0.00985s window: 121
average rate: 6.254
        min: 0.143s max: 0.212s std dev: 0.00965s window: 127
average rate: 6.258
        min: 0.143s max: 0.212s std dev: 0.00946s window: 133
average rate: 6.266
        min: 0.143s max: 0.212s std dev: 0.00927s window: 140
average rate: 6.271
        min: 0.143s max: 0.212s std dev: 0.00911s window: 146
average rate: 6.277
        min: 0.143s max: 0.212s std dev: 0.00895s window: 153
average rate: 6.281
        min: 0.143s max: 0.212s std dev: 0.00880s window: 159
average rate: 6.285
        min: 0.143s max: 0.212s std dev: 0.00868s window: 165
average rate: 6.291
        min: 0.143s max: 0.212s std dev: 0.00855s window: 172
average rate: 6.295
        min: 0.143s max: 0.212s std dev: 0.00846s window: 178
average rate: 6.299
        min: 0.143s max: 0.212s std dev: 0.00832s window: 185
average rate: 6.298
        min: 0.143s max: 0.212s std dev: 0.00823s window: 191
average rate: 6.290
        min: 0.143s max: 0.212s std dev: 0.00820s window: 197
average rate: 5.838
        min: 0.143s max: 2.617s std dev: 0.17268s window: 203
average rate: 5.845
        min: 0.143s max: 2.617s std dev: 0.17018s window: 209
average rate: 5.851
        min: 0.143s max: 2.617s std dev: 0.16778s window: 215
average rate: 5.858
        min: 0.143s max: 2.617s std dev: 0.16548s window: 221
average rate: 5.856
        min: 0.143s max: 2.617s std dev: 0.16327s window: 227

Without this PR

❯ rostopic hz /Feature0D
subscribed to [/Feature0D]
no new messages
average rate: 4.211
        min: 0.158s max: 0.351s std dev: 0.08044s window: 6
average rate: 5.041
        min: 0.135s max: 0.351s std dev: 0.06602s window: 12
average rate: 5.612
        min: 0.135s max: 0.351s std dev: 0.05779s window: 19
average rate: 5.856
        min: 0.135s max: 0.351s std dev: 0.05094s window: 26
average rate: 6.010
        min: 0.135s max: 0.351s std dev: 0.04682s window: 32
average rate: 6.111
        min: 0.135s max: 0.351s std dev: 0.04279s window: 39
average rate: 6.234
        min: 0.134s max: 0.351s std dev: 0.04022s window: 46
average rate: 6.325
        min: 0.133s max: 0.351s std dev: 0.03798s window: 53
average rate: 6.403
        min: 0.131s max: 0.351s std dev: 0.03623s window: 60
average rate: 6.464
        min: 0.131s max: 0.351s std dev: 0.03461s window: 67
average rate: 6.506
        min: 0.131s max: 0.351s std dev: 0.03315s window: 74
average rate: 6.530
        min: 0.131s max: 0.351s std dev: 0.03184s window: 81
average rate: 6.566
        min: 0.131s max: 0.351s std dev: 0.03079s window: 88
average rate: 6.596
        min: 0.131s max: 0.351s std dev: 0.02978s window: 95
average rate: 6.604
        min: 0.131s max: 0.351s std dev: 0.02895s window: 101
average rate: 6.611
        min: 0.131s max: 0.351s std dev: 0.02814s window: 108
average rate: 6.626
        min: 0.131s max: 0.351s std dev: 0.02740s window: 115
average rate: 6.628
        min: 0.131s max: 0.351s std dev: 0.02670s window: 122
average rate: 6.639
        min: 0.131s max: 0.351s std dev: 0.02612s window: 129
average rate: 6.656
        min: 0.131s max: 0.351s std dev: 0.02554s window: 136
average rate: 6.674
        min: 0.131s max: 0.351s std dev: 0.02504s window: 143
average rate: 6.684
        min: 0.131s max: 0.351s std dev: 0.02456s window: 150
average rate: 6.692
        min: 0.131s max: 0.351s std dev: 0.02413s window: 156
average rate: 6.694
        min: 0.131s max: 0.351s std dev: 0.02375s window: 163
average rate: 6.154
        min: 0.131s max: 2.369s std dev: 0.17180s window: 170
average rate: 6.180
        min: 0.131s max: 2.369s std dev: 0.16840s window: 177
average rate: 6.201
        min: 0.131s max: 2.369s std dev: 0.16518s window: 184
average rate: 6.221
        min: 0.131s max: 2.369s std dev: 0.16257s window: 190
average rate: 6.243
        min: 0.131s max: 2.369s std dev: 0.15968s window: 197
average rate: 6.258
        min: 0.131s max: 2.369s std dev: 0.15693s window: 204
average rate: 6.272
        min: 0.131s max: 2.369s std dev: 0.15431s window: 211
average rate: 6.284
        min: 0.131s max: 2.369s std dev: 0.15182s window: 218
average rate: 6.296
        min: 0.131s max: 2.369s std dev: 0.14978s window: 224
average rate: 6.304
        min: 0.131s max: 2.369s std dev: 0.14750s window: 231
average rate: 6.313
        min: 0.131s max: 2.369s std dev: 0.14532s window: 238
average rate: 6.321
        min: 0.131s max: 2.369s std dev: 0.14353s window: 244

@k-okada k-okada merged commit c45c488 into jsk-ros-pkg:master May 2, 2025
17 checks passed
@mqcmd196 mqcmd196 deleted the fix-imagesift-segfault branch May 2, 2025 07:26
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

libsiftfast Segmentation Fault when 2 libsiftfast nodelets are loaded then publishe the topics
3 participants