Skip to content
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

process exits abnormally with range check exception #23

Closed
cmraaron opened this issue Mar 6, 2023 · 9 comments
Closed

process exits abnormally with range check exception #23

cmraaron opened this issue Mar 6, 2023 · 9 comments

Comments

@cmraaron
Copy link

cmraaron commented Mar 6, 2023

after four hours of running happily, the sick_safetyscanners2_node process exited with vector::_M_range_check: __n (which is 18446744073709551615) >= this->size() (which is 0)

probably not easy to reproduce, its the first time I've seen it. But worth logging.
Interesting the size of the vector is 0, and the index is probably -1. Perhaps that offers some clues.
The only code i've seen that looks like that is here


But it would never have entered the loop if the size was 0

@lenpuc
Copy link
Collaborator

lenpuc commented Apr 4, 2023

Thanks for noticing, this seems to be a bug which transferred form the ROS1 version to the ROS2 version.
And yes you are correct, so far I was not able to reproduce the error. I will continue looking and trying to catch the error, however this already proved difficult in the ROS1 version since it happens rarely and so far never on my own system.

@reinzor
Copy link
Contributor

reinzor commented Oct 24, 2023

Still in latest version:

[robot_73981][INFO] 2023-10-19 16:15:28,219:   what():  vector::_M_range_check: __n (which is 18446744073709551615) >= this->size() (which is 0)

I will try to reproduce this in a DEBUG build

@TanmayDeshmukh
Copy link
Contributor

Hi,
We had this exact issue appear once after several hours of running as well.
Could it be coming from deeper within? sick_safetyscanners_base/cola maybe?

@TanmayDeshmukh
Copy link
Contributor

TanmayDeshmukh commented May 13, 2024

The ROS2 node itself doesn't crash, and continues to publish diagnostic_msgs, but stops publishing scan data, which suggests that one of the threads spawned internally exits.
I suspect this thread in sick_safetyscanners_base simply disappears after the range check exception. The try..catch would explain why it exits "normally".
I'm not familiar with the code-base so just speculating.

It seems to happen usually after over 24 hours. I will setup gdb and try to get a backtrace.

@reinzor
Copy link
Contributor

reinzor commented May 13, 2024

@YannickdeHoop fyi

@TanmayDeshmukh
Copy link
Contributor

Here's the stacktrace
Looks like the culprint is this line:

.at(data.getMeasurementDataPtr()->getScanPointsVector().size() - 1)

#0  0x00007ffff78649fc in pthread_kill () from target:/lib/x86_64-linux-gnu/libc.so.6
#1  0x00007ffff7810476 in raise () from target:/lib/x86_64-linux-gnu/libc.so.6
#2  0x00007ffff77f67f3 in abort () from target:/lib/x86_64-linux-gnu/libc.so.6
#3  0x00007ffff7abbb9e in ?? () from target:/lib/x86_64-linux-gnu/libstdc++.so.6
#4  0x00007ffff7ac720c in ?? () from target:/lib/x86_64-linux-gnu/libstdc++.so.6
#5  0x00007ffff7ac7277 in std::terminate() () from target:/lib/x86_64-linux-gnu/libstdc++.so.6
#6  0x00007ffff7ac74d8 in __cxa_throw () from target:/lib/x86_64-linux-gnu/libstdc++.so.6
#7  0x00007ffff7abe4cd in ?? () from target:/lib/x86_64-linux-gnu/libstdc++.so.6
#8  0x00005555555b09bc in std::vector<sick::datastructure::ScanPoint, std::allocator<sick::datastructure::ScanPoint> >::_M_range_check (this=0x7fffe67fa5e0, this=0x7fffe67fa5e0, __n=<optimized out>)
    at /usr/include/c++/11/bits/stl_vector.h:1073
#9  std::vector<sick::datastructure::ScanPoint, std::allocator<sick::datastructure::ScanPoint> >::at (__n=<optimized out>, this=0x7fffe67fa5e0) at /usr/include/c++/11/bits/stl_vector.h:1094
#10 sick::MessageCreator::createLaserScanMsg (this=this@entry=0x55555568b1a0, data=..., now=<incomplete type>) at /home/ros/tanmay_ws/src/sick_safetyscanners2/src/utils/MessageCreator.cpp:62
#11 0x00005555555823ed in sick::SickSafetyscannersRos2::receiveUDPPaket (this=0x5555555ecb80, data=...) at /home/ros/tanmay_ws/src/sick_safetyscanners2/src/SickSafetyscannersRos2.cpp:88
#12 0x00007ffff7f4bfdc in std::function<void (sick::datastructure::Data const&)>::operator()(sick::datastructure::Data const&) const (__args#0=..., this=0x5555556812c0)
    at /usr/include/c++/11/bits/std_function.h:590
#13 sick::AsyncSickSafetyScanner::processUDPPacket (this=0x55555567e9e0, buffer=...) at /home/ros/tanmay_ws/src/sick_safetyscanners_base/src/SickSafetyscanners.cpp:294
#14 0x00007ffff7f726bc in std::function<void (sick::datastructure::PacketBuffer const&)>::operator()(sick::datastructure::PacketBuffer const&) const (__args#0=..., this=0x55555567ea98)
    at /usr/include/c++/11/bits/std_function.h:590
#15 sick::communication::UDPClient::handleReceive (this=0x55555567ea18, ec=..., bytes_recv=<optimized out>) at /home/ros/tanmay_ws/src/sick_safetyscanners_base/src/communication/UDPClient.cpp:125
#16 0x00007ffff7f72a49 in operator() (bytes_recvd=<optimized out>, ec=..., __closure=0x7fffe67fb360) at /home/ros/tanmay_ws/src/sick_safetyscanners_base/src/communication/UDPClient.cpp:139
#17 boost::asio::detail::binder2<sick::communication::UDPClient::beginReceive()::<lambda(boost::system::error_code, std::size_t)>, boost::system::error_code, long unsigned int>::operator() (
    this=0x7fffe67fb360) at /usr/include/boost/asio/detail/bind_handler.hpp:182
#18 boost::asio::asio_handler_invoke<boost::asio::detail::binder2<sick::communication::UDPClient::beginReceive()::<lambda(boost::system::error_code, std::size_t)>, boost::system::error_code, long unsigned int> > (function=...) at /usr/include/boost/asio/handler_invoke_hook.hpp:88
#19 boost_asio_handler_invoke_helpers::invoke<boost::asio::detail::binder2<sick::communication::UDPClient::beginReceive()::<lambda(boost::system::error_code, std::size_t)>, boost::system::error_code, long unsigned int>, sick::communication::UDPClient::beginReceive()::<lambda(boost::system::error_code, std::size_t)> > (context=..., function=...)
    at /usr/include/boost/asio/detail/handler_invoke_helpers.hpp:54
#20 boost::asio::detail::handler_work<sick::communication::UDPClient::beginReceive()::<lambda(boost::system::error_code, std::size_t)>, boost::asio::execution::any_executor<boost::asio::execution::context_as_t<boost::asio::execution_context&>, boost::asio::execution::detail::blocking::never_t<0>, boost::asio::execution::prefer_only<boost::asio::execution::detail::blocking::possibly_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::outstanding_work::tracked_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::outstanding_work::untracked_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::relationship::fork_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::relationship::continuation_t<0> > >, void>::complete<boost::asio::detail::binder2<sick::communication::UDPClient::beginReceive()::<lambda(boost::system::error_code, std::size_t)>, boost::system::error_code, long unsigned int> > (handler=..., function=..., 
    this=0x7fffe67fb380) at /usr/include/boost/asio/detail/handler_work.hpp:425
#21 boost::asio::detail::reactive_socket_recvfrom_op<boost::asio::mutable_buffers_1, boost::asio::ip::basic_endpoint<boost::asio::ip::udp>, sick::communication::UDPClient::beginReceive()::<lambda(boost::system::error_code, std::size_t)>, boost::asio::execution::any_executor<boost::asio::execution::context_as_t<boost::asio::execution_context&>, boost::asio::execution::detail::blocking::never_t<0>, boost::asio::execution::prefer_only<boost::asio::execution::detail::blocking::possibly_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::outstanding_work::tracked_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::outstanding_work::untracked_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::relationship::fork_t<0> >, boost::asio::execution::prefer_only<boost::asio::execution::detail::relationship::continuation_t<0> > > >::do_complete(void *, boost::asio::detail::operation *, const boost::system::error_code &, std::size_t) (
    owner=0x555555681360, base=0x55555568ebd0) at /usr/include/boost/asio/detail/reactive_socket_recvfrom_op.hpp:150
#22 0x00007ffff7f51917 in boost::asio::detail::scheduler_operation::complete (bytes_transferred=0, ec=..., owner=0x555555681360, this=0x55555568ebd0)
    at /usr/include/boost/asio/detail/scheduler_operation.hpp:40
#23 boost::asio::detail::scheduler::do_run_one (this=this@entry=0x555555681360, lock=..., this_thread=..., ec=...) at /usr/include/boost/asio/detail/impl/scheduler.ipp:481
#24 0x00007ffff7f54da1 in boost::asio::detail::scheduler::run (this=0x555555681360, ec=...) at /usr/include/boost/asio/detail/impl/scheduler.ipp:204
#25 0x00007ffff7f4bbb8 in boost::asio::io_context::run (this=0x55555567e9c0) at /usr/include/boost/asio/impl/io_context.ipp:63
#26 operator() (__closure=<optimized out>) at /home/ros/tanmay_ws/src/sick_safetyscanners_base/src/SickSafetyscanners.cpp:247
#27 boost::detail::thread_data<sick::AsyncSickSafetyScanner::AsyncSickSafetyScanner(sick::types::ip_address_t, sick::types::port_t, sick::datastructure::CommSettings, sick::types::ScanDataCb)::<lambda()> >::run(void) (this=<optimized out>) at /usr/include/boost/thread/detail/thread.hpp:120
#28 0x00007ffff77c10cb in ?? () from target:/lib/x86_64-linux-gnu/libboost_thread.so.1.74.0
#29 0x00007ffff7862ac3 in ?? () from target:/lib/x86_64-linux-gnu/libc.so.6
#30 0x00007ffff78f4850 in ?? () from target:/lib/x86_64-linux-gnu/libc.so.6

locals at frame 10 (createLaserScanMsg):

#10 sick::MessageCreator::createLaserScanMsg (this=this@entry=0x55555568b1a0, data=..., now=<incomplete type>) at /home/ros/tanmay_ws/src/sick_safetyscanners2/src/utils/MessageCreator.cpp:62
62	          .at(data.getMeasurementDataPtr()->getScanPointsVector().size() - 1)
(gdb) info locals
scan = {header = {stamp = {sec = 1716428246, nanosec = 163538809}, frame_id = {static npos = 18446744073709551615, 
      _M_dataplus = {<std::allocator<char>> = {<__gnu_cxx::new_allocator<char>> = {<No data fields>}, <No data fields>}, _M_p = 0x7fffe67fa948 "laser"}, _M_string_length = 5, {
        _M_local_buf = "laser\000\000\000`\251\177\346\377\177\000", _M_allocated_capacity = 491328332140}}}, angle_min = -1.88786495, angle_max = 0, angle_increment = 0, time_increment = 0, 
  scan_time = 0, range_min = 0, range_max = 0, ranges = {<std::_Vector_base<float, std::allocator<float> >> = {
      _M_impl = {<std::allocator<float>> = {<__gnu_cxx::new_allocator<float>> = {<No data fields>}, <No data fields>}, <std::_Vector_base<float, std::allocator<float> >::_Vector_impl_data> = {
          _M_start = 0x0, _M_finish = 0x0, _M_end_of_storage = 0x0}, <No data fields>}}, <No data fields>}, intensities = {<std::_Vector_base<float, std::allocator<float> >> = {
      _M_impl = {<std::allocator<float>> = {<__gnu_cxx::new_allocator<float>> = {<No data fields>}, <No data fields>}, <std::_Vector_base<float, std::allocator<float> >::_Vector_impl_data> = {
          _M_start = 0x0, _M_finish = 0x0, _M_end_of_storage = 0x0}, <No data fields>}}, <No data fields>}}
scan_points = {<std::_Vector_base<sick::datastructure::ScanPoint, std::allocator<sick::datastructure::ScanPoint> >> = {
    _M_impl = {<std::allocator<sick::datastructure::ScanPoint>> = {<__gnu_cxx::new_allocator<sick::datastructure::ScanPoint>> = {<No data fields>}, <No data fields>}, <std::_Vector_base<sick::datastructure::ScanPoint, std::allocator<sick::datastructure::ScanPoint> >::_Vector_impl_data> = {_M_start = 0x0, _M_finish = 0x0, _M_end_of_storage = 0x0}, <No data fields>}}, <No data fields>}
num_scan_points = 0
angle_max = <optimized out>
time_increment = <optimized out>
scan_time = <optimized out>

locals at frame 11(receiveUDPPaket):

#11 0x00005555555823ed in sick::SickSafetyscannersRos2::receiveUDPPaket (this=0x5555555ecb80, data=...) at /home/ros/tanmay_ws/src/sick_safetyscanners2/src/SickSafetyscannersRos2.cpp:88
88	    auto scan = m_config.m_msg_creator->createLaserScanMsg(data, this->now());
(gdb) info locals
scan = {header = {stamp = {sec = 1716428246, nanosec = 163538809}, frame_id = {static npos = 18446744073709551615, 
      _M_dataplus = {<std::allocator<char>> = {<__gnu_cxx::new_allocator<char>> = {<No data fields>}, <No data fields>}, _M_p = 0x7fffe67fa948 "laser"}, _M_string_length = 5, {
        _M_local_buf = "laser\000\000\000`\251\177\346\377\177\000", _M_allocated_capacity = 491328332140}}}, angle_min = -1.88786495, angle_max = 0, angle_increment = 0, time_increment = 0, 
  scan_time = 0, range_min = 0, range_max = 0, ranges = {<std::_Vector_base<float, std::allocator<float> >> = {
      _M_impl = {<std::allocator<float>> = {<__gnu_cxx::new_allocator<float>> = {<No data fields>}, <No data fields>}, <std::_Vector_base<float, std::allocator<float> >::_Vector_impl_data> = {
          _M_start = 0x0, _M_finish = 0x0, _M_end_of_storage = 0x0}, <No data fields>}}, <No data fields>}, intensities = {<std::_Vector_base<float, std::allocator<float> >> = {
      _M_impl = {<std::allocator<float>> = {<__gnu_cxx::new_allocator<float>> = {<No data fields>}, <No data fields>}, <std::_Vector_base<float, std::allocator<float> >::_Vector_impl_data> = {
          _M_start = 0x0, _M_finish = 0x0, _M_end_of_storage = 0x0}, <No data fields>}}, <No data fields>}}
extended_scan = {laser_scan = {header = {stamp = {sec = -872382792, nanosec = 32767}, frame_id = {static npos = 18446744073709551615, 
        _M_dataplus = {<std::allocator<char>> = {<__gnu_cxx::new_allocator<char>> = {<No data fields>}, <No data fields>}, _M_p = 0x7fffcc059520 <incomplete sequence \374>}, 
        _M_string_length = 16821290307275575415, {_M_local_buf = "0>\000\314\377\177\000\000\024\000\000\000\377\177\000", _M_allocated_capacity = 140736615956016}}}, angle_min = -35017888, 
    angle_max = 4.59163468e-41, angle_increment = -34028096, time_increment = 4.59163468e-41, scan_time = 0, range_min = 4.59163468e-41, range_max = -34028096, 
    ranges = {<std::_Vector_base<float, std::allocator<float> >> = {
        _M_impl = {<std::allocator<float>> = {<__gnu_cxx::new_allocator<float>> = {<No data fields>}, <No data fields>}, <std::_Vector_base<float, std::allocator<float> >::_Vector_impl_data> = {
            _M_start = 0x7ffff787262b, _M_finish = 0x7fffcc035350, _M_end_of_storage = 0x7fffcc000090}, <No data fields>}}, <No data fields>}, 
    intensities = {<std::_Vector_base<float, std::allocator<float> >> = {
        _M_impl = {<std::allocator<float>> = {<__gnu_cxx::new_allocator<float>> = {<No data fields>}, <No data fields>}, <std::_Vector_base<float, std::allocator<float> >::_Vector_impl_data> = {
            _M_start = 0x7fffcc0819a8, _M_finish = 0x7fffcc0819a8, _M_end_of_storage = 0x3cc003550}, <No data fields>}}, <No data fields>}}, 
  reflektor_status = {<std::_Bvector_base<std::allocator<bool> >> = {
      _M_impl = {<std::allocator<unsigned long>> = {<__gnu_cxx::new_allocator<unsigned long>> = {<No data fields>}, <No data fields>}, <std::_Bvector_base<std::allocator<bool> >::_Bvector_impl_data> = {
          _M_start = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x28, 
              _M_offset = 3422565712}, <No data fields>}, _M_finish = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, 
              _M_p = 0x7fff00000014, _M_offset = 3422565720}, <No data fields>}, _M_end_of_storage = 0x0}, <No data fields>}}, <No data fields>}, 
  reflektor_median = {<std::_Bvector_base<std::allocator<bool> >> = {
      _M_impl = {<std::allocator<unsigned long>> = {<__gnu_cxx::new_allocator<unsigned long>> = {<No data fields>}, <No data fields>}, <std::_Bvector_base<std::allocator<bool> >::_Bvector_impl_data> = {
          _M_start = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x0, _M_offset = 3}, <No data fields>}, 
          _M_finish = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x0, _M_offset = 0}, <No data fields>}, 
          _M_end_of_storage = 0x0}, <No data fields>}}, <No data fields>}, intrusion = {<std::_Bvector_base<std::allocator<bool> >> = {
      _M_impl = {<std::allocator<unsigned long>> = {<__gnu_cxx::new_allocator<unsigned long>> = {<No data fields>}, <No data fields>}, <std::_Bvector_base<std::allocator<bool> >::_Bvector_impl_data> = {
          _M_start = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x770000007c, 
              _M_offset = 110}, <No data fields>}, _M_finish = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, 
              _M_p = 0x7ffff7873139 <malloc+153>, _M_offset = 3423084632}, <No data fields>}, _M_end_of_storage = 0xfffffffffffff790}, <No data fields>}}, <No data fields>}}
output_paths = {status = {<std::_Bvector_base<std::allocator<bool> >> = {
      _M_impl = {<std::allocator<unsigned long>> = {<__gnu_cxx::new_allocator<unsigned long>> = {<No data fields>}, <No data fields>}, <std::_Bvector_base<std::allocator<bool> >::_Bvector_impl_data> = {
          _M_start = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x7ffff7ec49c0 <vtable for rclcpp::Time+16>, 
              _M_offset = 1460028281}, <No data fields>}, _M_finish = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, 
              _M_p = 0x555500000001, _M_offset = 4148673184}, <No data fields>}, _M_end_of_storage = 0x1e05180001}, <No data fields>}}, <No data fields>}, 
  is_safe = {<std::_Bvector_base<std::allocator<bool> >> = {
      _M_impl = {<std::allocator<unsigned long>> = {<__gnu_cxx::new_allocator<unsigned long>> = {<No data fields>}, <No data fields>}, <std::_Bvector_base<std::allocator<bool> >::_Bvector_impl_data> = {
          _M_start = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x3e2aaaa000000000, 
              _M_offset = 3556783040}, <No data fields>}, _M_finish = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, 
              _M_p = 0x555555614f10, _M_offset = 0}, <No data fields>}, _M_end_of_storage = 0x7fffe67fa710}, <No data fields>}}, <No data fields>}, 
  is_valid = {<std::_Bvector_base<std::allocator<bool> >> = {
      _M_impl = {<std::allocator<unsigned long>> = {<__gnu_cxx::new_allocator<unsigned long>> = {<No data fields>}, <No data fields>}, <std::_Bvector_base<std::allocator<bool> >::_Bvector_impl_data> = {
          _M_start = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x39fec1237741, 
              _M_offset = 0}, <No data fields>}, _M_finish = {<std::_Bit_iterator_base> = {<std::iterator<std::random_access_iterator_tag, bool, long, bool*, bool&>> = {<No data fields>}, _M_p = 0x0, 
              _M_offset = 0}, <No data fields>}, _M_end_of_storage = 0x7fff00000000}, <No data fields>}}, <No data fields>}, active_monitoring_case = 0}
__func__ = <optimized out>

locals at frame 13(processUDPPacket):

#13 sick::AsyncSickSafetyScanner::processUDPPacket (this=0x55555567e9e0, buffer=...) at /home/ros/tanmay_ws/src/sick_safetyscanners_base/src/SickSafetyscanners.cpp:294
294	    m_scan_data_cb(data);
deployed_buffer = {
  m_buffer = {<std::__shared_ptr<std::vector<unsigned char, std::allocator<unsigned char> > const, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<std::vector<unsigned char, std::allocator<unsigned char> > const, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc007910, _M_refcount = {_M_pi = 0x7fffcc007900}}, <No data fields>}}
data_parser = {
  m_data_header_parser_ptr = {<std::__shared_ptr<sick::data_processing::ParseDataHeader, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::data_processing::ParseDataHeader, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc037ca0, _M_refcount = {_M_pi = 0x7fffcc037c90}}, <No data fields>}, 
  m_derived_values_parser_ptr = {<std::__shared_ptr<sick::data_processing::ParseDerivedValues, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::data_processing::ParseDerivedValues, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc02db60, _M_refcount = {_M_pi = 0x7fffcc02db50}}, <No data fields>}, 
  m_measurement_data_parser_ptr = {<std::__shared_ptr<sick::data_processing::ParseMeasurementData, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::data_processing::ParseMeasurementData, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc01ce50, _M_refcount = {_M_pi = 0x7fffcc01ce40}}, <No data fields>}, 
  m_general_system_state_parser_ptr = {<std::__shared_ptr<sick::data_processing::ParseGeneralSystemState, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::data_processing::ParseGeneralSystemState, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc035630, _M_refcount = {_M_pi = 0x7fffcc035620}}, <No data fields>}, 
  m_intrusion_data_parser_ptr = {<std::__shared_ptr<sick::data_processing::ParseIntrusionData, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::data_processing::ParseIntrusionData, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc0462b0, _M_refcount = {_M_pi = 0x7fffcc0462a0}}, <No data fields>}, 
  m_application_data_parser_ptr = {<std::__shared_ptr<sick::data_processing::ParseApplicationData, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::data_processing::ParseApplicationData, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc037f10, _M_refcount = {_M_pi = 0x7fffcc037f00}}, <No data fields>}}
data = {
  m_data_header_ptr = {<std::__shared_ptr<sick::datastructure::DataHeader, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::datastructure::DataHeader, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc0817d0, _M_refcount = {_M_pi = 0x7fffcc0817c0}}, <No data fields>}, 
  m_general_system_state_ptr = {<std::__shared_ptr<sick::datastructure::GeneralSystemState, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::datastructure::GeneralSystemState, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc001cb0, _M_refcount = {_M_pi = 0x7fffcc001ca0}}, <No data fields>}, 
  m_derived_values_ptr = {<std::__shared_ptr<sick::datastructure::DerivedValues, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::datastructure::DerivedValues, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc015620, _M_refcount = {_M_pi = 0x7fffcc015610}}, <No data fields>}, 
  m_measurement_data_ptr = {<std::__shared_ptr<sick::datastructure::MeasurementData, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::datastructure::MeasurementData, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc08e750, _M_refcount = {_M_pi = 0x7fffcc08e740}}, <No data fields>}, 
  m_intrusion_data_ptr = {<std::__shared_ptr<sick::datastructure::IntrusionData, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::datastructure::IntrusionData, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc018ed0, _M_refcount = {_M_pi = 0x7fffcc018ec0}}, <No data fields>}, 
  m_application_data_ptr = {<std::__shared_ptr<sick::datastructure::ApplicationData, (__gnu_cxx::_Lock_policy)2>> = {<std::__shared_ptr_access<sick::datastructure::ApplicationData, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}, _M_ptr = 0x7fffcc000ca0, _M_refcount = {_M_pi = 0x7fffcc000c90}}, <No data fields>}}

@lenpuc
Copy link
Collaborator

lenpuc commented May 27, 2024

Thanks for the stacktrace! This will hopefully help in fixing the issue.

@lenpuc
Copy link
Collaborator

lenpuc commented Aug 21, 2024

Please check if c8e4b0d resovled the issue

@lenpuc
Copy link
Collaborator

lenpuc commented Sep 25, 2024

The fix is included in the newest release 1.0.4, which will be rolled out with the next sync of each distro.

Therefore, this should be fixed, if not please reopen or make a new issue

@lenpuc lenpuc closed this as completed Sep 25, 2024
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

No branches or pull requests

4 participants