KIT-ISAS/lili-om

LiLi-OM-ROT BackendFusion node died randomly using own data

wwtinwhu opened this issue · 6 comments

Hello! I test LiLi-OM-ROT with my own data. Sometimes, the BackendFusion node will die in the function called saveKeyFramesAndFactors(). The specific code line where it dies is as follows.
if(imu_buf[i]->header.stamp.toSec() > timeodom_cur)
By the way, this error happens randomly. Do you have any suggestions? Thank you very much!

PS: the error output in terminal is as follows

BackendFusion: /usr/include/boost/smart_ptr/shared_ptr.hpp:734: typename boost::detail::sp_member_access::type boost::shared_ptr::operator->() const [with T = const sensor_msgs::Imu_<std::allocator >; typename boost::detail::sp_member_access::type = const sensor_msgs::Imu_<std::allocator >*]: Assertion `px != 0' failed

I suppose you just need to tune the parameters according to your own scenario as well as hardware. Also pay attention to your time synchronization. The BackendFusion node cannot die if things are set up properly.

I suppose you just need to tune the parameters according to your own scenario as well as hardware. Also pay attention to your time synchronization. The BackendFusion node cannot die if things are set up properly.

Thanks for your advice! I will try to figure it out.

I suppose you just need to tune the parameters according to your own scenario as well as hardware. Also pay attention to your time synchronization. The BackendFusion node cannot die if things are set up properly.

Thanks for your advice! I will try to figure it out.

This may be caused by the code in the function imuHandler() where the specific line is as follows.
imu_buf[imu_buf.size() - 601] = nullptr;
I comment this line and this error hasn't happened yet. I think it is relevant to the type of this shared_ptr which is the const type. Need professional answers!

I suppose you just need to tune the parameters according to your own scenario as well as hardware. Also pay attention to your time synchronization. The BackendFusion node cannot die if things are set up properly.

Thanks for your advice! I will try to figure it out.

This may be caused by the code in the function imuHandler() where the specific line is as follows.
imu_buf[imu_buf.size() - 601] = nullptr;
I comment this line and this error hasn't happened yet. I think it is relevant to the type of this shared_ptr which is the const type. Need professional answers!

I meet the same error.Did you fix this problem?

I suppose you just need to tune the parameters according to your own scenario as well as hardware. Also pay attention to your time synchronization. The BackendFusion node cannot die if things are set up properly.

Thanks for your advice! I will try to figure it out.

This may be caused by the code in the function imuHandler() where the specific line is as follows.
imu_buf[imu_buf.size() - 601] = nullptr;
I comment this line and this error hasn't happened yet. I think it is relevant to the type of this shared_ptr which is the const type. Need professional answers!

I meet the same error.Did you fix this problem?

No. For now, I just comment it. Do you have any advice? @pangchenglin

The problem stems from trying to access a nullptr. In saveKeyFramesAndFactors it accesses imu_buf without checking if there still is a valid measurement at imu_idx. Only upto the last 600 imu msg ptrs in imu_buf contain valid pointers. A higher imu data rate would fill in faster and result in imu_buf[imu_idx] being a nullptr.
Commenting the previously mentioned line prevents setting older ones to nullptr, hence no apparent problem.
BUT the std::vector of ìmu_buf (as well as many others like biases in backendfusion) never shrinks, so running it on huge datasets is memory limited. For this kind of max-size buffers, it would be better to use a std::deque instead. Changing it though won't be as easy, since creating indices from someVector.size()-someOtherSize is quite often used throughout the backendfusion.