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

create_waitable_callback causing segmentation fault #18

Open
tonynajjar opened this issue Mar 31, 2023 · 9 comments
Open

create_waitable_callback causing segmentation fault #18

tonynajjar opened this issue Mar 31, 2023 · 9 comments

Comments

@tonynajjar
Copy link

tonynajjar commented Mar 31, 2023

Hi @alsora, I recently started seeing this sporadic crash in a node where we use the events executor

nice-2] Stack trace (most recent call last):
[nice-2] #20   Object "", at 0xffffffffffffffff, in 
[nice-2] #19   Object "/code/ros2_ws/build/nav2_controller/controller_server", at 0x55e598ae5684, in _start
[nice-2] #18   Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7f5488381e3f, in __libc_start_main
[nice-2] #17   Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7f5488381d8f, in 
[nice-2] #16   Source "/code/ros2_ws/src/navigation2/nav2_controller/src/main.cpp", line 30, in main [0x55e598ae5882]
[nice-2]          27:   auto executor = std::make_shared<rclcpp::executors::EventsExecutor>();
[nice-2]          28: 
[nice-2]          29:   executor->add_node(node->get_node_base_interface());
[nice-2]       >  30:   executor->spin();
[nice-2]          31:   rclcpp::shutdown();
[nice-2]          32: 
[nice-2]          33:   return 0;
[nice-2] #15   Source "/code/ros2_ws/src/irobot_events_executor/irobot_events_executor/src/rclcpp/executors/events_executor/events_executor.cpp", line 74, in spin [0x7f54888622fe]
[nice-2]          71:     ExecutorEvent event;
[nice-2]          72:     bool has_event = events_queue_->dequeue(event);
[nice-2]          73:     if (has_event) {
[nice-2]       >  74:       this->execute_event(event);
[nice-2]          75:     }
[nice-2]          76:   }
[nice-2]          77: }
[nice-2] #14   Source "/code/ros2_ws/src/irobot_events_executor/irobot_events_executor/src/rclcpp/executors/events_executor/events_executor.cpp", line 265, in execute_event [0x7f5488862fe2]
[nice-2]         262:         if (waitable) {
[nice-2]         263:           for (size_t i = 0; i < event.num_events; i++) {
[nice-2]         264:             auto data = waitable->take_data_by_entity_id(event.gen_entity_id);
[nice-2]       > 265:             waitable->execute(data);
[nice-2]         266:           }
[nice-2]         267:         }
[nice-2]         268:         break;
[nice-2] #13   Source "/code/ros2_ws/src/irobot_events_executor/irobot_events_executor/src/rclcpp/executors/events_executor/events_executor_entities_collector.cpp", line 99, in execute [0x7f548884c2df]
[nice-2]          97:   // For all groups registered in the executor, set their event callbacks.
[nice-2]          98:   set_entities_event_callbacks_from_map(weak_groups_associated_with_executor_to_nodes_);
[nice-2]       >  99:   set_entities_event_callbacks_from_map(weak_groups_to_nodes_associated_with_executor_);
[nice-2]         100: }
[nice-2]         101: 
[nice-2]         102: void
[nice-2] #12   Source "/code/ros2_ws/src/irobot_events_executor/irobot_events_executor/src/rclcpp/executors/events_executor/events_executor_entities_collector.cpp", line 182, in set_entities_event_callbacks_from_map [0x7f548884c895]
[nice-2]         179:     if (!node || !group || !group->can_be_taken_from().load()) {
[nice-2]         180:       continue;
[nice-2]         181:     }
[nice-2]       > 182:     set_callback_group_entities_callbacks(group);
[nice-2]         183:   }
[nice-2]         184: }
[nice-2] #11   Source "/code/ros2_ws/src/irobot_events_executor/irobot_events_executor/src/rclcpp/executors/events_executor/events_executor_entities_collector.cpp", line 230, in set_callback_group_entities_callbacks [0x7f548884cf06]
[nice-2]         227:       }
[nice-2]         228:       return false;
[nice-2]         229:     });
[nice-2]       > 230:   group->find_waitable_ptrs_if(
[nice-2]         231:     [this](const rclcpp::Waitable::SharedPtr & waitable) {
[nice-2]         232:       if (waitable) {
[nice-2]         233:         weak_waitables_map_.emplace(waitable.get(), waitable);
[nice-2] #10   Source "/opt/ros/humble/include/rclcpp/rclcpp/callback_group.hpp", line 137, in find_waitable_ptrs_if<rclcpp::executors::EventsExecutorEntitiesCollector::set_callback_group_entities_callbacks(rclcpp::CallbackGroup::SharedPtr)::<lambda(const SharedPtr&)> > [0x7f548884e18d]
[nice-2]         134:   rclcpp::Waitable::SharedPtr
[nice-2]         135:   find_waitable_ptrs_if(Function func) const
[nice-2]         136:   {
[nice-2]       > 137:     return _find_ptrs_if_impl<rclcpp::Waitable, Function>(func, waitable_ptrs_);
[nice-2]         138:   }
[nice-2]         139: 
[nice-2]         140:   RCLCPP_PUBLIC
[nice-2] #9    Source "/opt/ros/humble/include/rclcpp/rclcpp/callback_group.hpp", line 245, in _find_ptrs_if_impl<rclcpp::Waitable, rclcpp::executors::EventsExecutorEntitiesCollector::set_callback_group_entities_callbacks(rclcpp::CallbackGroup::SharedPtr)::<lambda(const SharedPtr&)> > [0x7f548884ebfb]
[nice-2]         242:     std::lock_guard<std::mutex> lock(mutex_);
[nice-2]         243:     for (auto & weak_ptr : vect_ptrs) {
[nice-2]         244:       auto ref_ptr = weak_ptr.lock();
[nice-2]       > 245:       if (ref_ptr && func(ref_ptr)) {
[nice-2]         246:         return ref_ptr;
[nice-2]         247:       }
[nice-2]         248:     }
[nice-2] #8    Source "/code/ros2_ws/src/irobot_events_executor/irobot_events_executor/src/rclcpp/executors/events_executor/events_executor_entities_collector.cpp", line 235, in set_callback_group_entities_callbacks [0x7f548884cdb9]
[nice-2]         232:       if (waitable) {
[nice-2]         233:         weak_waitables_map_.emplace(waitable.get(), waitable);
[nice-2]         234: 
[nice-2]       > 235:         waitable->set_on_ready_callback(
[nice-2]         236:           create_waitable_callback(waitable.get()));
[nice-2]         237:       }
[nice-2]         238:       return false;
[standalone_converter-14] [INFO] [1680268851.997787714] [costmap_converter.costmap_converter]: Standalone costmap converter: costmap_converter::CostmapToPolygonsDBSMCCH loaded.
[nice-2] #7    Source "/opt/ros/humble/include/rclcpp/rclcpp/qos_event.hpp", line 187, in set_on_ready_callback [0x7f5488e6b257]
[nice-2]         184:     // Set it temporarily to the new callback, while we replace the old one.
[nice-2]         185:     // This two-step setting, prevents a gap where the old std::function has
[nice-2]         186:     // been replaced but the middleware hasn't been told about the new one yet.
[nice-2]       > 187:     set_on_new_event_callback(
[nice-2]         188:       rclcpp::detail::cpp_callback_trampoline<const void *, size_t>,
[nice-2]         189:       static_cast<const void *>(&new_callback));
[nice-2] #6    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7f54892392e3, in rclcpp::QOSEventHandlerBase::set_on_new_event_callback(void (*)(void const*, unsigned long), void const*)
[nice-2] #5    Object "/opt/ros/humble/lib/librmw_cyclonedds_cpp.so", at 0x7f5487a3c6f0, in rmw_event_set_callback
[nice-2] #4    Object "/opt/ros/humble/lib/librmw_cyclonedds_cpp.so", at 0x7f5487a53c41, in 
[nice-2] #3    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7f54891ec538, in void rclcpp::detail::cpp_callback_trampoline<void const*, unsigned long, void>(void const*, unsigned long)
[nice-2] #2    Source "/usr/include/c++/11/bits/std_function.h", line 290, in _M_invoke [0x7f548884f707]
[nice-2]         287:       static _Res
[nice-2]         288:       _M_invoke(const _Any_data& __functor, _ArgTypes&&... __args)
[nice-2]         289:       {
[nice-2]       > 290: 	return std::__invoke_r<_Res>(*_Base::_M_get_pointer(__functor),
[nice-2]         291: 				     std::forward<_ArgTypes>(__args)...);
[nice-2]         292:       }
[nice-2] #1    Source "/usr/include/c++/11/bits/invoke.h", line 111, in __invoke_r<void, rclcpp::executors::EventsExecutorEntitiesCollector::create_waitable_callback(void*)::<lambda(size_t, int)>&, long unsigned int, int> [0x7f548884fb45]
[nice-2]         108:       using __type = typename __result::type;
[nice-2]         109:       using __tag = typename __result::__invoke_type;
[nice-2]         110:       if constexpr (is_void_v<_Res>)
[nice-2]       > 111: 	std::__invoke_impl<__type>(__tag{}, std::forward<_Callable>(__fn),
[nice-2]         112: 					std::forward<_Args>(__args)...);
[nice-2]         113:       else
[nice-2]         114: 	return std::__invoke_impl<__type>(__tag{},
[nice-2] #0    Source "/usr/include/c++/11/bits/invoke.h", line 61, in __invoke_impl<void, rclcpp::executors::EventsExecutorEntitiesCollector::create_waitable_callback(void*)::<lambda(size_t, int)>&, long unsigned int, int> [0x7f548884fdf8]
[nice-2]          58:   template<typename _Res, typename _Fn, typename... _Args>
[nice-2]          59:     constexpr _Res
[nice-2]          60:     __invoke_impl(__invoke_other, _Fn&& __f, _Args&&... __args)
[nice-2]       >  61:     { return std::forward<_Fn>(__f)(std::forward<_Args>(__args)...); }
[nice-2]          62: 
[nice-2]          63:   template<typename _Res, typename _MemFun, typename _Tp, typename... _Args>
[nice-2]          64:     constexpr _Res
[nice-2] Segmentation fault (Address not mapped to object [0x1])

Tracing it back I suspected that this commit might be the culprit?

From the information I gave you so far are you able to tell if this commit is causing this crash or not? Thanks

@mauropasse
Copy link
Collaborator

mauropasse commented Apr 3, 2023

Hi @tonynajjar.
What rclcpp branch are you using?

The set_on_new_event_callback failing here has been updated on rolling (this PR), it's signature changed.
See on rolling. Humble did not backport this yet.
So, you can cherry pick those PR commits into your rclcpp.

@tonynajjar
Copy link
Author

Thanks for your answer

What rclcpp branch are you using?

I'm using humble binaries.

Humble did not backport this yet.

seems like there is no open PR for it even, should this be mentioned to rclcpp?

So, you can cherry pick those ros2/rclcpp#2059 commits into your rclcpp.

Will try it out and update you. Thanks

@tonynajjar
Copy link
Author

So I followed what the Readme proposed under Known bugs and limitations (including the cherrypick you suggested) but now I have another issue, the throttle node has a segmentation fault

root@logi-XMG-CORE-REN-M20:/code# ros2 run topic_tools throttle messages /backward_lidar_plugin/backward_lidar 0.5 /backward_lidar
[ros2run]: Segmentation fault

Here is my setup:

I noticed that the issue comes from cherrypicking ros2/rcl#995 and ros2/rclcpp#1979 but without those irobot_events_executor on humble-future won't build

@mauropasse
Copy link
Collaborator

Do you have more info about the segfault? Can you run it with gdb?

@tonynajjar
Copy link
Author

tonynajjar commented Apr 3, 2023

Do you have more info about the segfault? Can you run it with gdb?

I tried with backward_ros but that didn't output anything, I'll try once more and with gdb

@tonynajjar
Copy link
Author

root@logi-XMG-CORE-REN-M20:/code/ros2_ws# ros2 run --prefix 'gdb -ex run --args' topic_tools throttle messages /backward_lidar_plugin/backward_lidar 0.5 /backward_lidar
GNU gdb (Ubuntu 12.1-0ubuntu1~22.04) 12.1
Copyright (C) 2022 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law.
Type "show copying" and "show warranty" for details.
This GDB was configured as "x86_64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<https://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
    <http://www.gnu.org/software/gdb/documentation/>.

For help, type "help".
Type "apropos word" to search for commands related to "word"...
Reading symbols from /opt/ros/humble/lib/topic_tools/throttle...
(No debugging symbols found in /opt/ros/humble/lib/topic_tools/throttle)
Starting program: /opt/ros/humble/lib/topic_tools/throttle messages /backward_lidar_plugin/backward_lidar 0.5 /backward_lidar
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
[New Thread 0x7ffff623d640 (LWP 40282)]
[New Thread 0x7ffff5a3c640 (LWP 40283)]
[New Thread 0x7ffff523b640 (LWP 40284)]
[New Thread 0x7ffff4a3a640 (LWP 40285)]
[New Thread 0x7fffe7fff640 (LWP 40286)]
[New Thread 0x7fffe77fe640 (LWP 40287)]
[New Thread 0x7fffe6ffd640 (LWP 40288)]
[New Thread 0x7fffe67fc640 (LWP 40289)]

Thread 1 "throttle" received signal SIGSEGV, Segmentation fault.
0x00007ffff7b93658 in __gnu_cxx::__atomic_add (__val=1, __mem=0x5f647261776b6369) at /usr/include/c++/11/ext/atomicity.h:71
71	  { __atomic_fetch_add(__mem, __val, __ATOMIC_ACQ_REL); }
(gdb) backtrace
#0  0x00007ffff7b93658 in __gnu_cxx::__atomic_add (__val=1, __mem=0x5f647261776b6369) at /usr/include/c++/11/ext/atomicity.h:71
#1  __gnu_cxx::__atomic_add_dispatch (__val=1, __mem=0x5f647261776b6369) at /usr/include/c++/11/ext/atomicity.h:111
#2  std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_add_ref_copy (this=0x5f647261776b6361) at /usr/include/c++/11/bits/shared_ptr_base.h:148
#3  0x00007ffff7b91a85 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count (this=0x7fffffff8c28, __r=...) at /usr/include/c++/11/bits/shared_ptr_base.h:712
#4  0x00007ffff7d3f8e3 in std::__shared_ptr<rcl_subscription_s, (__gnu_cxx::_Lock_policy)2>::__shared_ptr (this=0x7fffffff8c20) at /usr/include/c++/11/bits/shared_ptr_base.h:1152
#5  0x00007ffff7d3f90d in std::shared_ptr<rcl_subscription_s>::shared_ptr (this=0x7fffffff8c20) at /usr/include/c++/11/bits/shared_ptr.h:150
#6  0x00007ffff7d3c5bb in rclcpp::SubscriptionBase::get_subscription_handle (this=0x5555555e1e30) at /code/ros2_ws/src/rclcpp/rclcpp/src/rclcpp/subscription_base.cpp:120
#7  0x00007ffff7bfa301 in rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&)::{lambda(std::shared_ptr<rclcpp::SubscriptionBase> const&)#1}::operator()(std::shared_ptr<rclcpp::SubscriptionBase> const&) const (__closure=0x7fffffff8e90, subscription=std::shared_ptr<rclcpp::SubscriptionBase> (use count 3, weak count 0) = {...})
    at /code/ros2_ws/src/rclcpp/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp:170
#8  0x00007ffff7c03aef in std::__invoke_impl<void, rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&)::{lambda(std::shared_ptr<rclcpp::SubscriptionBase> const&)#1}&, std::shared_ptr<rclcpp::SubscriptionBase> const&>(std::__invoke_other, rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&)::{lambda(std::shared_ptr<rclcpp::SubscriptionBase> const&)#1}&, std::shared_ptr<rclcpp::SubscriptionBase> const&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#9  0x00007ffff7c01c6a in std::__invoke_r<void, rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&)::{lambda(std::shared_ptr<rclcpp::SubscriptionBase> const&)#1}&, std::shared_ptr<rclcpp::SubscriptionBase> const&>(rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&)::{lambda(std::shared_ptr<rclcpp::SubscriptionBase> const&)#1}&, std::shared_ptr<rclcpp::SubscriptionBase> const&) (__fn=...)
    at /usr/include/c++/11/bits/invoke.h:111
#10 0x00007ffff7bfef8e in std::_Function_handler<void (std::shared_ptr<rclcpp::SubscriptionBase> const&), rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&)::{lambda(std::shared_ptr<rclcpp::SubscriptionBase> const&)#1}>::_M_invoke(std::_Any_data const&, std::shared_ptr<rclcpp::SubscriptionBase> const&) (__functor=..., 
    __args#0=std::shared_ptr<rclcpp::SubscriptionBase> (use count 3, weak count 0) = {...}) at /usr/include/c++/11/bits/std_function.h:290
#11 0x00007ffff7b920f7 in std::function<void (std::shared_ptr<rclcpp::SubscriptionBase> const&)>::operator()(std::shared_ptr<rclcpp::SubscriptionBase> const&) const (this=0x7fffffff8e90, 
    __args#0=std::shared_ptr<rclcpp::SubscriptionBase> (use count 3, weak count 0) = {...}) at /usr/include/c++/11/bits/std_function.h:590
#12 0x00007ffff7b8ed5b in rclcpp::CallbackGroup::collect_all_ptrs(std::function<void (std::shared_ptr<rclcpp::SubscriptionBase> const&)>, std::function<void (std::shared_ptr<rclcpp::ServiceBase> const&)>, std::function<void (std::shared_ptr<rclcpp::ClientBase> const&)>, std::function<void (std::shared_ptr<rclcpp::TimerBase> const&)>, std::function<void (std::shared_ptr<rclcpp::Waitable> const&)>) const (this=0x5555555a0d00, sub_func=..., service_func=..., client_func=..., timer_func=..., waitable_func=...)
    at /code/ros2_ws/src/rclcpp/rclcpp/src/rclcpp/callback_group.cpp:69
#13 0x00007ffff7bfa93c in rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities (this=0x55555557cf60, 
    weak_groups_to_nodes=std::map with 1 element = {...}) at /code/ros2_ws/src/rclcpp/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp:168
#14 0x00007ffff7bc4500 in rclcpp::Executor::wait_for_work (this=0x7fffffff99b0, timeout=...) at /code/ros2_ws/src/rclcpp/rclcpp/src/rclcpp/executor.cpp:700
#15 0x00007ffff7bc5656 in rclcpp::Executor::get_next_executable (this=0x7fffffff99b0, any_executable=..., timeout=...) at /code/ros2_ws/src/rclcpp/rclcpp/src/rclcpp/executor.cpp:912
#16 0x00007ffff7bd3592 in rclcpp::executors::SingleThreadedExecutor::spin (this=0x7fffffff99b0) at /code/ros2_ws/src/rclcpp/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp:36
#17 0x00007ffff7bd0a33 in rclcpp::spin (node_ptr=std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> (use count 22, weak count 4) = {...})
    at /code/ros2_ws/src/rclcpp/rclcpp/src/rclcpp/executors.cpp:35
#18 0x00007ffff7bd0b60 in rclcpp::spin (node_ptr=std::shared_ptr<rclcpp::Node> (use count 2, weak count 1) = {...}) at /code/ros2_ws/src/rclcpp/rclcpp/src/rclcpp/executors.cpp:42
#19 0x0000555555556832 in ?? ()
--Type <RET> for more, q to quit, c to continue without paging--
#20 0x00007ffff6d62d90 in __libc_start_call_main (main=main@entry=0x555555556660, argc=argc@entry=5, argv=argv@entry=0x7fffffffa1c8) at ../sysdeps/nptl/libc_start_call_main.h:58
#21 0x00007ffff6d62e40 in __libc_start_main_impl (main=0x555555556660, argc=5, argv=0x7fffffffa1c8, init=<optimized out>, fini=<optimized out>, rtld_fini=<optimized out>, 
    stack_end=0x7fffffffa1b8) at ../csu/libc-start.c:392
#22 0x0000555555556ed5 in ?? ()

I also noticed that when building topic_tools from source, this doesn't happen... I'm confused

@alsora
Copy link
Collaborator

alsora commented Apr 3, 2023

Late to the party, and I haven't looked yet into everything, but if the issue does not happen when building from sources I think it's because some of the PRs that you cherry-picked break the ABI and so are not compatible with some libraries provuded by the debian packages.

@tonynajjar
Copy link
Author

tonynajjar commented Apr 3, 2023

f the issue does not happen when building from sources I think it's because some of the PRs that you cherry-picked break the ABI and so are not compatible with some libraries provuded by the debian packages.

Ah thank you for this pointer, it helps me in the future determine ABI issues.

Are you able to tell quickly if ros2/rcl#995 or ros2/rclcpp#1979 breaks ABI? These are the problematic cherrypicks.
Also I'd be grateful if you could update the Readme with a working way of using the EventsExecutor on Humble

@mauropasse
Copy link
Collaborator

Yes, those PRs breaks ABI. For example in the rcl PR, rcl_timer_impl_s struct has a new member addition.

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

3 participants