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

Call rclcpp::shutdown in test_node for clean shutdown on Windows #1515

Merged
merged 1 commit into from
Jan 13, 2021

Conversation

eboasson
Copy link
Contributor

The graph_listener thread is started in the background in some of the tests and this thread is killed by Windows prior to executing global destructors if it is still running when leaving main(). This then corrupts state because the RMW layer is blocking in a waitset and causes Cyclone to hang trying to destroy the waitset.

This fixes the issue mentioned in ros2/rmw#293 (comment) (for me locally anyway!)

The graph_listener thread is started in the background in some of the tests and
this thread is killed by Windows prior to executing global destructors if it is
still running when leaving main().  This then corrupts state because the RMW
layer is blocking in a waitset and causes Cyclone to hang trying to destroy the
waitset.

Signed-off-by: Erik Boasson <eb@ilities.com>
Copy link
Contributor

@clalancette clalancette left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks good to me. Since this problem seems to happen every time, a simple CI up to rclcpp should show whether it is fixed. Running that next.

@clalancette
Copy link
Contributor

CI:

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@clalancette
Copy link
Contributor

Looking good! I'm going to go ahead and merge this, thanks again @eboasson .

@clalancette clalancette merged commit 8d2c682 into ros2:master Jan 13, 2021
@wjwwood
Copy link
Member

wjwwood commented Jan 13, 2021

I don't know about this pull request, it sounds like we need to ensure this doesn't happen without an explicit shutdown.

I don't see how the thread can be terminated before globals can be destructed...

@wjwwood
Copy link
Member

wjwwood commented Jan 13, 2021

I don't know about this pull request, it sounds like we need to ensure this doesn't happen without an explicit shutdown.

Specifically, we allow and even encourage our users to not necessarily explicitly shutdown in their code and in our examples. So this would not work on Windows. It's not a very satisfying solution (requiring an explicit shutdown).

@ivanpauno
Copy link
Member

Specifically, we allow and even encourage our users to not necessarily explicitly shutdown in their code and in our examples. So this would not work on Windows. It's not a very satisfying solution (requiring an explicit shutdown).

Yeah, I'm not sure if we will have to re-think that or not ....
Things hanging because of a forgotten rclcpp::shutdown() is definitely not "nice", and the only way I know to avoid that problem is to completely forbid objects with static lifetime that don't have "trivial" destructors (but this is a big restriction ...).

@wjwwood
Copy link
Member

wjwwood commented Jan 14, 2021

Things hanging because of a forgotten rclcpp::shutdown() is definitely not "nice",

That's my whole point. It's not forgotten, it's explicitly left out and that should work as far as I understand. I don't think an explicit shutdown should be required, unless someone can explain why that is the case from an architectural standpoint.

It may be the case that static destruction order is the problem, but that wasn't clear here. And if it is, then it's not rclcpp's fault. From my perspective all libraries in a stack for an application should make globals optional, so that this can be avoided. However, having globals be used optionally is ok, like we do in rclcpp. In the somewhat common case that the user is using rclcpp directly and utilizes the convenience singleton init/shutdown it should be fine since the user does not have static objects that rely on shutdown.

If the use of static objects in rcl/rmw or in cyclone are contributing to this problem we should aim to make their use optional, so they can coexist with rclcpp, anything else is (in my opinion) a bug of those layers, not rclcpp.

@ivanpauno
Copy link
Member

That's my whole point. It's not forgotten, it's explicitly left out and that should work as far as I understand. I don't think an explicit shutdown should be required, unless someone can explain why that is the case from an architectural standpoint.

Yes, I agree that rclcpp::shutdown shouldn't be necessary.

And if it is, then it's not rclcpp's fault. From my perspective all libraries in a stack for an application should make globals optional, so that this can be avoided. However, having globals be used optionally is ok, like we do in rclcpp

I slightly disagree.
You can almost always avoid objects with non-trivial destructors and static lifetimes (at the expense of some extra verbosity), as really their initialization/destruction order is difficult to predict (between different platforms, and sometimes between different builds in the same platform).

e.g. the google style guide recommends to only use object that can be constexpr constructed and with trivial destructors.
If you want something that doesn't have a trivial destructor, the recommendation is to leak the object.
(they also support not constexpr constructible objects if initialization order doesn't matter or if it's an "static local" variable, but initialization isn't usually the big issue, destruction is)
e.g.2 rust only supports statics that can be constructed at compile time and drop is never called on those objects, or they also support lazily initialized statics which will never be dropped (e.g. once_cell or lazy_static).

Of course, this might be an opinionated decision of an style guide and a programming language, but it seems to me that's based in difficult to predict behavior of static constructors/destructors.

If the use of static objects in rcl/rmw or in cyclone are contributing to this problem we should aim to make their use optional, so they can coexist with rclcpp, anything else is (in my opinion) a bug of those layers, not rclcpp.

That's a good question, @eboasson can this problem by avoided in rmw_cyclonedds or cyclonedds?

@wjwwood
Copy link
Member

wjwwood commented Jan 14, 2021

If I would amend the style guide slightly it would be to say, you can use static objects but only if they are unconnected to one another. The problem comes in when a non-trivial destructor of a static global uses another static global, especially one from another shared library. If the static globals are completely decoupled, then there's no issue if their destruction order is unknown. So in the case of our tests and many of our examples, rclcpp is (or should be) the only thing with static globals and the user (no any other library on top of rclcpp but below user code) is not using static globals that are some how connected to rclcpp, and therefore there should be no problem. rclcpp, via rcl, rmw, etc... should opt not to use static globals from underlying libraries if possible to keep this isolation of static globals. For example, we shifted to using locally created and owned logging objects from spdlog rather than a global static singleton (one of the reasons to stop using log4cxx which did not allow this).

If the user (or some library on top of rclcpp) wants to have things with a static lifetime that do use rclcpp (specifically the context or signal handler), then they would need to use the non-global version of init/shutdown. Since rclcpp provides this as an option and does not require the use of globals, I think it's ok.

I understand why the guided probably prohibits their use, because it's easier to say never do it then to do it safely (ensuring static globals do not interact may be non-trivial), but I don't think it's impossible.

If we wanted to, we could do the same as rust and just not call the destructor for these classes, but that might require shifts in other places.


That all being said, the explanation for why this bug was happening was something like "memory corruption" which means there is a bug somewhere else that's affecting memory improperly.

it is then still blocked on a waitset by the time Windows decides that thread really shouldn't exist. Indiscriminately killing that thread from a global destructor then corrupts internal state of Cyclone and leaves it blocking on trying to delete the entity.

ros2/rmw#293 (comment)

So maybe the right fix is to conditionally "kill" the thread, if that is possible. By this I assume @eboasson meant join the thread or attempt to exit it? I'm not really sure. But presumably it is possible to know from Windows if a thread has been terminated and then we could attempt to join it or whatever only conditionally.


I'm not advocating for reverting this (I know we're trying to make progress on switching the default), but I don't think this solves the issue.

My problem with this pull request is that it seems to remove the thing that triggers the bug but doesn't fix it...

If the answer is, well we can't fix that bug, then I think we must change our architecture to require or ensure explicit shutdown, or change it so that shutdown isn't required in a different way (maybe leaking things). At the very least our documentation should change if we cannot fix this better.

@ivanpauno
Copy link
Member

My problem with this pull request is that it seems to remove the thing that triggers the bug but doesn't fix it...

If the answer is, well we can't fix that bug, then I think we must change our architecture to require or ensure explicit shutdown, or change it so that shutdown isn't required in a different way (maybe leaking things). At the very least our documentation should change if we cannot fix this better.

👍

@eboasson
Copy link
Contributor Author

Firstly, @wjwwood I totally agree with your statement that requiring an explicit shutdown should not be required, and indeed on Linux and macOS it all works just fine. However, on Windows it doesn't because the threads are "disappeared". As far as I have been able to find out all threads other than the main thread quite simply

are killed prior to the execution of the static destructors. It won’t give any notification, they’re just gone, and if they happen to be in a critical section or if there happens to be any state associated with them, tough luck.

test_node_cdb.log is the result of my efforts to capture test_node with Cyclone but without the explicit call to rclcpp::shutdown in place. This more-or-less traces the sequence of events, but it is an imperfect trace because I only set a limited number of breakpoints in Windows (ntdll!*Process* and ntdll!*Thread*) in addition to rclcpp::Context::shutdown. Each time a breakpoint is hit, it prints the list of threads and their stack traces.

The last point where all threads still exist (and in particular, the main thread on line 868 and the graph_listener on line 913)

    858 .  0  Id: 1754.4b4 Suspend: 1 Teb: 000000cf`85666000 Unfrozen
    859    1  Id: 1754.1804 Suspend: 0 Teb: 000000cf`85668000 Unfrozen
    860    2  Id: 1754.1a0 Suspend: 0 Teb: 000000cf`8566a000 Unfrozen
    861    3  Id: 1754.bdc Suspend: 0 Teb: 000000cf`8566c000 Unfrozen
    862    4  Id: 1754.1410 Suspend: 0 Teb: 000000cf`8566e000 Unfrozen
    863   11  Id: 1754.178 Suspend: 0 Teb: 000000cf`8567c000 Unfrozen
    864   12  Id: 1754.1dc0 Suspend: 0 Teb: 000000cf`85714000 Unfrozen
    866 .  0  Id: 1754.4b4 Suspend: 1 Teb: 000000cf`85666000 Unfrozen
    865
    867 Child-SP          RetAddr           Call Site
    868 000000cf`858ffa88 00007ffe`f8773e41 ntdll!RtlUnlockProcessHeapOnProcessTerminate
    869 000000cf`858ffa90 00007ffe`f6d9e0ab ntdll!RtlExitUserProcess+0x61
    870 000000cf`858ffac0 00007ffe`c1d3467a KERNEL32!ExitProcessImplementation+0xb
    871 000000cf`858ffaf0 00007ffe`c1d34629 ucrtbased!exit_or_terminate_process+0x3a [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 144]
    872 000000cf`858ffb20 00007ffe`c1d349a6 ucrtbased!common_exit+0x79 [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 282]
    873 000000cf`858ffb80 00007ff7`06695257 ucrtbased!exit+0x16 [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 294]
    874 000000cf`858ffbb0 00007ff7`066950fe test_node!__scrt_common_main_seh+0x147 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\e
    874 xe_common.inl @ 297]
    875 000000cf`858ffc20 00007ff7`066953e9 test_node!__scrt_common_main+0xe [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\exe_com
    875 mon.inl @ 331]
    876 000000cf`858ffc50 00007ffe`f6d97034 test_node!mainCRTStartup+0x9 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\exe_main.cp
    876 p @ 17]
    877 000000cf`858ffc80 00007ffe`f875d0d1 KERNEL32!BaseThreadInitThunk+0x14
    878 000000cf`858ffcb0 00000000`00000000 ntdll!RtlUserThreadStart+0x21
…
    913   11  Id: 1754.178 Suspend: 0 Teb: 000000cf`8567c000 Unfrozen
    914 Child-SP          RetAddr           Call Site
    915 000000cf`863f7eb8 00007ffe`f8775281 ntdll!NtWaitForAlertByThreadId+0x14
    916 000000cf`863f7ec0 00007ffe`f63eba89 ntdll!RtlSleepConditionVariableSRW+0x131
    917 000000cf`863f7f40 00007ffe`ba9bccd7 KERNELBASE!SleepConditionVariableSRW+0x29
    918 000000cf`863f7f80 00007ffe`ba9bce80 ddsc!ddsrt_cond_wait+0x87 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\ddsrt\src\sync\wind    918 ows\sync.c @ 64]
    919 000000cf`863f7fb0 00007ffe`ba9bcdd6 ddsc!ddsrt_cond_waitfor+0x90 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\ddsrt\src\sync\w    919 indows\sync.c @ 104]
    920 000000cf`863f8000 00007ffe`ba98eaaf ddsc!ddsrt_cond_waituntil+0xe6 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\ddsrt\src\sync    920 \windows\sync.c @ 88]
    921 000000cf`863f8050 00007ffe`ba98e702 ddsc!dds_waitset_wait_impl+0x25f [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\sr    921 c\dds_waitset.c @ 79]
    922 000000cf`863f8100 00007ffe`c1f998a5 ddsc!dds_waitset_wait+0xa2 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\src\dds_    922 waitset.c @ 376]
    923 000000cf`863f8150 00007ffe`dd936466 rmw_cyclonedds_cpp!rmw_wait+0xa45 [C:\dev\ros2_ws\src\ros2\rmw_cyclonedds\rmw_cyclonedds_cpp\src\rm    923 w_node.cpp @ 3383]
    924 000000cf`863f8460 00007ffe`cc19744f rmw_implementation!rmw_wait+0xa6 [C:\dev\ros2_ws\src\ros2\rmw_implementation\rmw_implementation\src    924 \functions.cpp @ 491]
    925 000000cf`863f84c0 00007ffe`c2177d25 rcl!rcl_wait+0x95f [C:\dev\ros2_ws\src\ros2\rcl\rcl\src\rcl\wait.c @ 609]
    926 000000cf`863fd350 00007ffe`c21778c2 rclcpp!rclcpp::graph_listener::GraphListener::run_loop+0x425 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp    926 \src\rclcpp\graph_listener.cpp @ 187]
    927 000000cf`863fd5b0 00007ffe`c217a4de rclcpp!rclcpp::graph_listener::GraphListener::run+0x52 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\src\r    927 clcpp\graph_listener.cpp @ 113]
    928 000000cf`863ff6d0 00007ffe`c2179ca5 rclcpp!std::invoke<void (__cdecl rclcpp::graph_listener::GraphListener::*)(void),rclcpp::graph_list    928 ener::GraphListener *>+0x3e [C:\Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\type_trait    928 s @ 1614]
    929 000000cf`863ff700 00007ffe`c1d3542c rclcpp!std::thread::_Invoke<std::tuple<void (__cdecl rclcpp::graph_listener::GraphListener::*)(void    929 ),rclcpp::graph_listener::GraphListener *>,0,1>+0x75 [C:\Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28    929 .29333\include\thread @ 44]
    930 000000cf`863ff760 00007ffe`f6d97034 ucrtbased!thread_start<unsigned int (__cdecl*)(void *),1>+0x9c [minkernel\crts\ucrt\src\appcrt\star    930 tup\thread.cpp @ 97]
    931 000000cf`863ff7c0 00007ffe`f875d0d1 KERNEL32!BaseThreadInitThunk+0x14
    932 000000cf`863ff7f0 00000000`00000000 ntdll!RtlUserThreadStart+0x21

At the next breakpoint there are no other threads left. I don’t know what function got called; I wouldn’t be surprised if it all happens within ntdll!RtlExitUserProcess. Anyway, at the point all you have is:

    946 .  0  Id: 1754.4b4 Suspend: 1 Teb: 000000cf`85666000 Unfrozen
    947 Child-SP          RetAddr           Call Site
    948 000000cf`858ffa88 00007ffe`f8773e88 ntdll!RtlReportSilentProcessExit
    949 000000cf`858ffa90 00007ffe`f6d9e0ab ntdll!RtlExitUserProcess+0xa8
    950 000000cf`858ffac0 00007ffe`c1d3467a KERNEL32!ExitProcessImplementation+0xb
    951 000000cf`858ffaf0 00007ffe`c1d34629 ucrtbased!exit_or_terminate_process+0x3a [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 144]
    952 000000cf`858ffb20 00007ffe`c1d349a6 ucrtbased!common_exit+0x79 [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 282]
    953 000000cf`858ffb80 00007ff7`06695257 ucrtbased!exit+0x16 [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 294]
    954 000000cf`858ffbb0 00007ff7`066950fe test_node!__scrt_common_main_seh+0x147 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\e    954 xe_common.inl @ 297]
    955 000000cf`858ffc20 00007ff7`066953e9 test_node!__scrt_common_main+0xe [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\exe_com    955 mon.inl @ 331]
    956 000000cf`858ffc50 00007ffe`f6d97034 test_node!mainCRTStartup+0x9 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\exe_main.cp    956 p @ 17]
    957 000000cf`858ffc80 00007ffe`f875d0d1 KERNEL32!BaseThreadInitThunk+0x14
    958 000000cf`858ffcb0 00000000`00000000 ntdll!RtlUserThreadStart+0x21

A while later, the destructor finally runs:

   1046 .  0  Id: 1754.4b4 Suspend: 1 Teb: 000000cf`85666000 Unfrozen
   1047 Child-SP          RetAddr           Call Site
   1048 000000cf`858fd2e8 00007ffe`c211bb13 rclcpp!rclcpp::Context::shutdown [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\src\rclcpp\context.cpp @ 30
   1048 2]
   1049 000000cf`858fd2f0 00007ffe`c212f918 rclcpp!rclcpp::Context::~Context+0x93 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\src\rclcpp\context.cpp
   1049  @ 158]
   1050 000000cf`858ff510 00007ffe`c212f9cc rclcpp!rclcpp::contexts::DefaultContext::~DefaultContext+0x28
   1051 000000cf`858ff540 00007ffe`c212f3af rclcpp!rclcpp::contexts::DefaultContext::`scalar deleting destructor'+0x2c
   1052 000000cf`858ff570 00007ffe`c212fb0f rclcpp!std::_Destroy_in_place<rclcpp::contexts::DefaultContext>+0x2f [C:\Program Files (x86)\Micros
   1052 oft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\xmemory @ 279]
   1053 000000cf`858ff5a0 00007ffe`c21046b7 rclcpp!std::_Ref_count_obj2<rclcpp::contexts::DefaultContext>::_Destroy+0x2f [C:\Program Files (x86
   1053 )\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\memory @ 1582]
   1054 000000cf`858ff5d0 00007ffe`c212fa48 rclcpp!std::_Ref_count_base::_Decref+0x47 [C:\Program Files (x86)\Microsoft Visual Studio\2019\Comm
   1054 unity\VC\Tools\MSVC\14.28.29333\include\memory @ 644]
   1055 000000cf`858ff600 00007ffe`c212f8d8 rclcpp!std::_Ptr_base<rclcpp::contexts::DefaultContext>::_Decref+0x38 [C:\Program Files (x86)\Micro
   1055 soft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\memory @ 878]
   1056 000000cf`858ff630 00007ffe`c23677c1 rclcpp!std::shared_ptr<rclcpp::contexts::DefaultContext>::~shared_ptr<rclcpp::contexts::DefaultCont
   1056 ext>+0x28 [C:\Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\memory @ 1170]
   1057 000000cf`858ff660 00007ffe`c1d35107 rclcpp!`rclcpp::contexts::get_global_default_context'::`2'::`dynamic atexit destructor for 'default
   1057 _context''+0x21
   1058 000000cf`858ff690 00007ffe`c1d34b15 ucrtbased!<lambda_d121dba8a4adeaf3a9819e48611155df>::operator()+0x127 [minkernel\crts\ucrt\src\appc
   1058 rt\startup\onexit.cpp @ 206]
   1059 000000cf`858ff720 00007ffe`c1d34c4a ucrtbased!__crt_seh_guarded_call<int>::operator()<<lambda_6a47f4c8fd0152770a780fc1d70204eb>,<lambda
   1059 _d121dba8a4adeaf3a9819e48611155df> &,<lambda_6aaa2265f5b6a89667e7d7630012e97a> >+0x35 [vccrt\vcruntime\inc\internal_shared.h @ 204]
   1060 000000cf`858ff760 00007ffe`c1d352b1 ucrtbased!__acrt_lock_and_call<<lambda_d121dba8a4adeaf3a9819e48611155df> >+0x4a [minkernel\crts\ucr
   1060 t\inc\corecrt_internal.h @ 975]
   1061 000000cf`858ff7b0 00007ffe`c23283e9 ucrtbased!_execute_onexit_table+0x31 [minkernel\crts\ucrt\src\appcrt\startup\onexit.cpp @ 231]
   1062 000000cf`858ff7f0 00007ffe`c232901c rclcpp!__scrt_dllmain_uninitialize_c+0x19 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\utilit   1062 y\utility.cpp @ 399]
   1063 000000cf`858ff820 00007ffe`c2328df7 rclcpp!dllmain_crt_process_detach+0x4c [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\d   1063 ll_dllmain.cpp @ 182]
   1064 000000cf`858ff860 00007ffe`c232918e rclcpp!dllmain_crt_dispatch+0x67 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\dll_dll   1064 main.cpp @ 220]
   1065 000000cf`858ff8a0 00007ffe`c2329301 rclcpp!dllmain_dispatch+0xfe [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\dll_dllmain   1065 .cpp @ 293]
   1066 000000cf`858ff8f0 00007ffe`f8747cad rclcpp!_DllMainCRTStartup+0x31 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\dll_dllma   1066 in.cpp @ 335]
   1067 000000cf`858ff920 00007ffe`f8773ff1 ntdll!LdrpCallInitRoutine+0x61
   1068 000000cf`858ff990 00007ffe`f8773e8d ntdll!LdrShutdownProcess+0x141
   1069 000000cf`858ffa90 00007ffe`f6d9e0ab ntdll!RtlExitUserProcess+0xad
   1070 000000cf`858ffac0 00007ffe`c1d3467a KERNEL32!ExitProcessImplementation+0xb
   1071 000000cf`858ffaf0 00007ffe`c1d34629 ucrtbased!exit_or_terminate_process+0x3a [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 144]
   1072 000000cf`858ffb20 00007ffe`c1d349a6 ucrtbased!common_exit+0x79 [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 282]
   1073 000000cf`858ffb80 00007ff7`06695257 ucrtbased!exit+0x16 [minkernel\crts\ucrt\src\appcrt\startup\exit.cpp @ 294]
   1074 000000cf`858ffbb0 00007ff7`066950fe test_node!__scrt_common_main_seh+0x147 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\e   1074 xe_common.inl @ 297]
   1075 000000cf`858ffc20 00007ff7`066953e9 test_node!__scrt_common_main+0xe [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\exe_com   1075 mon.inl @ 331]
   1076 000000cf`858ffc50 00007ffe`f6d97034 test_node!mainCRTStartup+0x9 [d:\agent\_work\63\s\src\vctools\crt\vcstartup\src\startup\exe_main.cp   1076 p @ 17]
   1077 000000cf`858ffc80 00007ffe`f875d0d1 KERNEL32!BaseThreadInitThunk+0x14
   1078 000000cf`858ffcb0 00000000`00000000 ntdll!RtlUserThreadStart+0x21

It is always a tricky business guessing where to set breakpoints, but this at least substantiates my claim that Windows kills the threads, pretty much like kill -9 does with processes on Unix. And just like a kill -9 usually leaves processes using shared memory in a corrupt state, this leaves the process in an inconsistent state. If you look at the graph listener thread before it gets killed, it is blocked on a waitset (the Cyclone RMW layer maps waitsets to DDS waitsets). Cyclone properly protects the objects against race conditions such as trying to delete an entity/object while it is still in use, and hence it records the fact that there is currently a thread blocked in a call while holding a pointer to this waitset. When the thread is killed by Windows, that record remains.

The destructor then tries to trigger a guard condition to wake up the graph_listener, which ultimately ends up as a broadcast on a condition variable:

   1084 .  0  Id: 1754.4b4 Suspend: 1 Teb: 000000cf`85666000 Unfrozen
   1085 Child-SP          RetAddr           Call Site
   1086 000000cf`858fa758 00007ffe`f875d642 ntdll!NtAlertThreadByThreadId
   1087 000000cf`858fa760 00007ffe`ba9bcfe0 ntdll!RtlWakeAllConditionVariable+0x62
   1088 000000cf`858fa790 00007ffe`ba98ef8c ddsc!ddsrt_cond_broadcast+0x50 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\ddsrt\src\sync
   1088 \windows\sync.c @ 128]
   1089 000000cf`858fa7c0 00007ffe`ba984057 ddsc!dds_waitset_observer+0x19c [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\src
   1089 \dds_waitset.c @ 237]
   1090 000000cf`858fa840 00007ffe`ba9836a5 ddsc!dds_entity_observers_signal+0x67 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\dd
   1090 sc\src\dds_entity.c @ 1393]
   1091 000000cf`858fa880 00007ffe`ba99007c ddsc!dds_entity_trigger_set+0xb5 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\sr
   1091 c\dds_entity.c @ 1442]
   1092 000000cf`858fa8c0 00007ffe`c1f9889a ddsc!dds_set_guardcondition+0x5c [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\sr
   1092 c\dds_guardcond.c @ 87]
   1093 000000cf`858fa910 00007ffe`dd9362c1 rmw_cyclonedds_cpp!rmw_trigger_guard_condition+0xba [C:\dev\ros2_ws\src\ros2\rmw_cyclonedds\rmw_cyc   1093 lonedds_cpp\src\rmw_node.cpp @ 3092]
   1094 000000cf`858fa950 00007ffe`cc17559a rmw_implementation!rmw_trigger_guard_condition+0x61 [C:\dev\ros2_ws\src\ros2\rmw_implementation\rmw   1094 _implementation\src\functions.cpp @ 476]
   1095 000000cf`858fa990 00007ffe`c21782b8 rcl!rcl_trigger_guard_condition+0x5a [C:\dev\ros2_ws\src\ros2\rcl\rcl\src\rcl\guard_condition.c @ 1   1095 60]
   1096 000000cf`858fadd0 00007ffe`c21781b7 rclcpp!rclcpp::graph_listener::interrupt_+0x38 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\src\rclcpp\gr   1096 aph_listener.cpp @ 216]
   1097 000000cf`858fae40 00007ffe`c21777ee rclcpp!rclcpp::graph_listener::GraphListener::__shutdown+0x97 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcp   1097 p\src\rclcpp\graph_listener.cpp @ 352]
   1098 000000cf`858faec0 00007ffe`c217bdb7 rclcpp!rclcpp::graph_listener::GraphListener::shutdown+0x4e [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\   1098 src\rclcpp\graph_listener.cpp @ 374]
   1099 000000cf`858fd0e0 00007ffe`c217a488 rclcpp!<lambda_ce8062be14c7855075cc462eb8ce2d37>::operator()+0x67 [C:\dev\ros2_ws\src\ros2\rclcpp\r   1099 clcpp\src\rclcpp\graph_listener.cpp @ 100]
   1100 000000cf`858fd140 00007ffe`c21794d8 rclcpp!std::invoke<<lambda_ce8062be14c7855075cc462eb8ce2d37> &>+0x28 [C:\Program Files (x86)\Micros   1100 oft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\type_traits @ 1585]
   1101 000000cf`858fd170 00007ffe`c217c85f rclcpp!std::_Invoker_ret<void,1>::_Call<<lambda_ce8062be14c7855075cc462eb8ce2d37> &>+0x28 [C:\Progr   1101 am Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\functional @ 745]
   1102 000000cf`858fd1a0 00007ffe`c211aca3 rclcpp!std::_Func_impl_no_alloc<<lambda_ce8062be14c7855075cc462eb8ce2d37>,void>::_Do_call+0x2f [C:\   1102 Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\functional @ 948]
   1103 000000cf`858fd1d0 00007ffe`c211c845 rclcpp!std::_Func_class<void>::operator()+0x53 [C:\Program Files (x86)\Microsoft Visual Studio\2019   1103 \Community\VC\Tools\MSVC\14.28.29333\include\functional @ 996]
   1104 000000cf`858fd210 00007ffe`c211bb13 rclcpp!rclcpp::Context::shutdown+0x165 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\src\rclcpp\context.cp   1104 p @ 320]

It subsequently joins the thread (which succeeds immediately because the thread objects are signalled by the weird thread killing spree of Windows):

   1140 .  0  Id: 1754.4b4 Suspend: 1 Teb: 000000cf`85666000 Unfrozen
   1141 Child-SP          RetAddr           Call Site
   1142 000000cf`858fad28 00007ffe`f63f7a73 ntdll!NtQueryInformationThread
   1143 000000cf`858fad30 00007ffe`c429268c KERNELBASE!GetExitCodeThread+0x23
   1144 000000cf`858fada0 00007ffe`c2166ff3 MSVCP140D!_Thrd_join+0x3c [D:\a01\_work\6\s\src\vctools\crt\github\stl\src\cthread.cpp @ 57]
   1145 000000cf`858fade0 00007ffe`c21781cb rclcpp!std::thread::join+0x73 [C:\Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Too
   1145 ls\MSVC\14.28.29333\include\thread @ 113]
   1146 000000cf`858fae40 00007ffe`c21777ee rclcpp!rclcpp::graph_listener::GraphListener::__shutdown+0xab [C:\dev\ros2_ws\src\ros2\rclcpp\rclcp
   1146 p\src\rclcpp\graph_listener.cpp @ 354]
   1147 000000cf`858faec0 00007ffe`c217bdb7 rclcpp!rclcpp::graph_listener::GraphListener::shutdown+0x4e [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\
   1147 src\rclcpp\graph_listener.cpp @ 374]
   1148 000000cf`858fd0e0 00007ffe`c217a488 rclcpp!<lambda_ce8062be14c7855075cc462eb8ce2d37>::operator()+0x67 [C:\dev\ros2_ws\src\ros2\rclcpp\r
   1148 clcpp\src\rclcpp\graph_listener.cpp @ 100]
   1149 000000cf`858fd140 00007ffe`c21794d8 rclcpp!std::invoke<<lambda_ce8062be14c7855075cc462eb8ce2d37> &>+0x28 [C:\Program Files (x86)\Micros
   1149 oft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\type_traits @ 1585]
   1150 000000cf`858fd170 00007ffe`c217c85f rclcpp!std::_Invoker_ret<void,1>::_Call<<lambda_ce8062be14c7855075cc462eb8ce2d37> &>+0x28 [C:\Progr
   1150 am Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\functional @ 745]
   1151 000000cf`858fd1a0 00007ffe`c211aca3 rclcpp!std::_Func_impl_no_alloc<<lambda_ce8062be14c7855075cc462eb8ce2d37>,void>::_Do_call+0x2f [C:\
   1151 Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\functional @ 948]
   1152 000000cf`858fd1d0 00007ffe`c211c845 rclcpp!std::_Func_class<void>::operator()+0x53 [C:\Program Files (x86)\Microsoft Visual Studio\2019
   1152 \Community\VC\Tools\MSVC\14.28.29333\include\functional @ 996]
   1153 000000cf`858fd210 00007ffe`c211bb13 rclcpp!rclcpp::Context::shutdown+0x165 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\src\rclcpp\context.cp
   1153 p @ 320]

When it then tries to destroy the waitset, Cyclone notes that it is in use, interrupts the blocked operation and waits for the call to dds_waitset_wait made by the graph_listener to complete. But because the thread no longer exists (and only because it no longer exists), that never happens and the process hangs:

   1189 .  0  Id: 1754.4b4 Suspend: 1 Teb: 000000cf`85666000 Unfrozen
   1190 Child-SP          RetAddr           Call Site
   1191 000000cf`858fa548 00007ffe`f8775281 ntdll!NtWaitForAlertByThreadId
   1192 000000cf`858fa550 00007ffe`f63eba89 ntdll!RtlSleepConditionVariableSRW+0x131
   1193 000000cf`858fa5d0 00007ffe`ba9bccd7 KERNELBASE!SleepConditionVariableSRW+0x29
   1194 000000cf`858fa610 00007ffe`ba980620 ddsc!ddsrt_cond_wait+0x87 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\ddsrt\src\sync\wind
   1194 ows\sync.c @ 64]
   1195 000000cf`858fa640 00007ffe`ba9842b8 ddsc!dds_handle_close_wait+0xc0 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\src
   1195 \dds_handles.c @ 502]
   1196 000000cf`858fa680 00007ffe`ba9839a1 ddsc!really_delete_pinned_closed_locked+0xf8 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\
   1196 core\ddsc\src\dds_entity.c @ 450]
   1197 000000cf`858fa6e0 00007ffe`ba98417e ddsc!dds_delete_impl_pinned+0x71 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\sr
   1197 c\dds_entity.c @ 410]
   1198 000000cf`858fa710 00007ffe`ba981b37 ddsc!dds_delete_impl+0x7e [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\src\dds_e
   1198 ntity.c @ 384]
   1199 000000cf`858fa760 00007ffe`c1f98d85 ddsc!dds_delete+0x27 [C:\dev\ros2_ws\src\eclipse-cyclonedds\cyclonedds\src\core\ddsc\src\dds_entity
   1199 .c @ 368]
   1200 000000cf`858fa790 00007ffe`dd9363b1 rmw_cyclonedds_cpp!rmw_destroy_wait_set+0x125 [C:\dev\ros2_ws\src\ros2\rmw_cyclonedds\rmw_cyclonedd
   1200 s_cpp\src\rmw_node.cpp @ 3164]
   1201 000000cf`858fa950 00007ffe`cc19483e rmw_implementation!rmw_destroy_wait_set+0x61 [C:\dev\ros2_ws\src\ros2\rmw_implementation\rmw_implem
   1201 entation\src\functions.cpp @ 486]
   1202 000000cf`858fa990 00007ffe`c21780c1 rcl!rcl_wait_set_fini+0x8e [C:\dev\ros2_ws\src\ros2\rcl\rcl\src\rcl\wait.c @ 195]
   1203 000000cf`858fadd0 00007ffe`c2178240 rclcpp!rclcpp::graph_listener::GraphListener::cleanup_wait_set+0x41 [C:\dev\ros2_ws\src\ros2\rclcpp
   1203 \rclcpp\src\rclcpp\graph_listener.cpp @ 339]
   1204 000000cf`858fae40 00007ffe`c21777ee rclcpp!rclcpp::graph_listener::GraphListener::__shutdown+0x120 [C:\dev\ros2_ws\src\ros2\rclcpp\rclc
   1204 pp\src\rclcpp\graph_listener.cpp @ 359]
   1205 000000cf`858faec0 00007ffe`c217bdb7 rclcpp!rclcpp::graph_listener::GraphListener::shutdown+0x4e [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\
   1205 src\rclcpp\graph_listener.cpp @ 374]
   1206 000000cf`858fd0e0 00007ffe`c217a488 rclcpp!<lambda_ce8062be14c7855075cc462eb8ce2d37>::operator()+0x67 [C:\dev\ros2_ws\src\ros2\rclcpp\r
   1206 clcpp\src\rclcpp\graph_listener.cpp @ 100]
   1207 000000cf`858fd140 00007ffe`c21794d8 rclcpp!std::invoke<<lambda_ce8062be14c7855075cc462eb8ce2d37> &>+0x28 [C:\Program Files (x86)\Micros
   1207 oft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\type_traits @ 1585]
   1208 000000cf`858fd170 00007ffe`c217c85f rclcpp!std::_Invoker_ret<void,1>::_Call<<lambda_ce8062be14c7855075cc462eb8ce2d37> &>+0x28 [C:\Progr
   1208 am Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\functional @ 745]
   1209 000000cf`858fd1a0 00007ffe`c211aca3 rclcpp!std::_Func_impl_no_alloc<<lambda_ce8062be14c7855075cc462eb8ce2d37>,void>::_Do_call+0x2f [C:\
   1209 Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Tools\MSVC\14.28.29333\include\functional @ 948]
   1210 000000cf`858fd1d0 00007ffe`c211c845 rclcpp!std::_Func_class<void>::operator()+0x53 [C:\Program Files (x86)\Microsoft Visual Studio\2019
   1210 \Community\VC\Tools\MSVC\14.28.29333\include\functional @ 996]
   1211 000000cf`858fd210 00007ffe`c211bb13 rclcpp!rclcpp::Context::shutdown+0x165 [C:\dev\ros2_ws\src\ros2\rclcpp\rclcpp\src\rclcpp\context.cp
   1211 p @ 320]

There are no static destructors involved in Cyclone, nor atexit handling, nor anything really, other than the assumption that threads don’t just disappear. An assumption that is perfectly valid in all circumstances, except process termination on Windows. I have a problem with faulting Cyclone for this.

I also have a problem with hacks like recording thread handles in blocking calls to then check whether the thread perhaps has been killed. If there happened to be a wake-up of the thread in parallel (and it might, spurious wake ups and timeouts can and do happen), the thread may have already re-acquired the associated mutex by and some other thread would hang in another place after running into a locked mutex.

Perhaps you could use error checking mutexes that will give an error code in such case; but then there is the state that is protected by the mutex. That state will likely be in the process of being modified, and so continuing despite the locked mutex will likely mean working with states in which invariants no longer hold.

In other words, such tricks are not solutions to the problem, even if they hide the problem most of the time.

Rewriting the waitsets in the Cyclone RMW to not use a DDS waitset and instead use just a condition variable (I believe this is how rmw_fastrtps_cpp implemented waitsets) also would only reduce the likelihood of encountering the problem, because you’d still have the same small window where a spurious wakeup will result in a mutex being locked when it isn’t expected. The likelihood of ever encountering this problem again will be (vastly) smaller, but it will still not be eliminated.

Elimination of the risk quite simply requires cleanly shutting down all threads before leaving main if you want reliable and clean shutdown on Windows. I think strongly advising explicitly calling rclcpp::shutdown if the code is to be used on Windows would be the most practical solution.

It really is beyond me why Microsoft chose this inane design.

@ivanpauno
Copy link
Member

When it then tries to destroy the waitset, Cyclone notes that it is in use, interrupts the blocked operation and waits for the call to dds_waitset_wait made by the graph_listener to complete. But because the thread no longer exists (and only because it no longer exists), that never happens and the process hangs:

Thanks for the answer @eboasson !
That's interesting, so the hanging is completely generated in rclcpp and not in any global destructor of cyclone, and it doesn't happen in other rmw implementations because cyclone has the extra protection of not allowing you to remove an entity while you're using it in a wait set (which sounds like a reasonable thing).

Maybe, we could modify rclcpp so the graph listener thread is not always running, but it only runs while you have a node there (i.e. nodes retain shared ownership of the graph listener, and context only week ownership).
It doesn't sound ideal, but it's a fast workaround (and we don't need the graph listener running if there isn't any node).
Of course, creating nodes with static lifetimes would cause the same issue, but I think that's already not possible (?).


About what happens with mutex on Windows after threads are killed, it seems they start returning WAIT_ABANDONED (some sort of mutex poisoning in the windows kernel), but the windows stl will just throw an exception. But it seems that doesn't apply to condition variables, those just hang for ever 😮 .

@wjwwood
Copy link
Member

wjwwood commented Jan 14, 2021

There are no static destructors involved in Cyclone, nor atexit handling, nor anything really, other than the assumption that threads don’t just disappear. An assumption that is perfectly valid in all circumstances, except process termination on Windows. I have a problem with faulting Cyclone for this.

Ok, well I agree then it's not an issue in cyclone.

You do use static lifetime objects though? Is that for the domain participant factory? I would have assumed that it was both static and non-trivially destructed... but I'm guessing.

Though I don't 100% understand how using a condition variable in rmw_fastrtps_cpp is less likely to run into this problem. But I think that's just my limited context.

@wjwwood
Copy link
Member

wjwwood commented Jan 14, 2021

Maybe, we could modify rclcpp so the graph listener thread is not always running, but it only runs while you have a node there (i.e. nodes retain shared ownership of the graph listener, and context only week ownership).

Well, instead of changing the ownership mechanics, we could just change the run loop of graph listener to not wait on the wait set if there are no nodes. Instead using a condition variable to know when the graph listener should shutdown (due to sigint or context shutdown) and/or when a new has been added (and therefore it needs to wait on the wait set again).

@eboasson
Copy link
Contributor Author

You do use static lifetime objects though? Is that for the domain participant factory? I would have assumed that it was both static and non-trivially destructed... but I'm guessing.

It is pure C code so only the simplest of objects ... All I really have is a bit of zero-initialised statically allocated memory that gets initialised on first use (first entity created) and de-initialised on last use (last entity deleted), after which it is back in its initial state. Managing that is done with a small state machine using some atomic operations and a bit of synchronisation (a bit of polling with a sleep for the very first bit, with a condition variable and a mutex once the run-time layer is initialised).

Though I don't 100% understand how using a condition variable in rmw_fastrtps_cpp is less likely to run into this problem. But I think that's just my limited context

In rmw_fastrtps_cpp, rmw_wait is essentially implemented as:

  1. attach all specified objects
  2. check objects for trigger conditions
  3. if none triggered: lock mutex ; wait for condition variable ; unlock mutex
  4. detach the objects

Attaching is

  void
  attachCondition(std::mutex * conditionMutex, std::condition_variable * conditionVariable)
  {
    std::lock_guard<std::mutex> lock(internalMutex_);
    conditionMutex_ = conditionMutex;
    conditionVariable_ = conditionVariable;
  }

and detaching correspondingly simple.

So in a case like this, the thread typically gets killed while blocked on the condition variable, after which the state will be inconsistent only in that the conditionMutex_ and conditionVariable_ pointers will never be reset to null, but the destructors of the guard condition and the wait set don't even inspect those and so complete without issue.

@ivanpauno
Copy link
Member

ivanpauno commented Jan 15, 2021

Well, instead of changing the ownership mechanics, we could just change the run loop of graph listener to not wait on the wait set if there are no nodes. Instead using a condition variable to know when the graph listener should shutdown (due to sigint or context shutdown) and/or when a new has been added (and therefore it needs to wait on the wait set again).

The problem is that joining a thread in a static destructor on Windows seems to be broken (?).
Really, I don't understand Windows docs, but it sounds like that's either not allowed or leads to undefined behavior.

edit: I will give it a try to that approach, as after reading windows stl code I think that joining a thread in a static destructor is ok.
The issue is how you use synchronization primitives in that destructor, but let's see ...

ivanpauno added a commit that referenced this pull request Jan 15, 2021
@ivanpauno
Copy link
Member

edit: I will give it a try to that approach, as after reading windows stl code I think that joining a thread in a static destructor is ok.
The issue is how you use synchronization primitives in that destructor, but let's see ...

I tried, but I don't see how to avoid the problem.

When I managed to avoid the deadlock when the thread "disappears", the code was deadlocking when the thread exited normally.
When I managed to get both "working", there was still the chance of the graph listener destructor trying to take a "poisoned mutex" (in windows terminology, ABANDONED_WAIT mutex) that was going to throw an exception (this can already happen in rmw_fastrtps I think, as the mutex the waitset is using internally can enter the WAIT_ABANDONED state, but that is not too "likely" too happen).

+ the code was impossible to understand.

Karsten1987 pushed a commit that referenced this pull request Mar 2, 2021
The graph_listener thread is started in the background in some of the tests and
this thread is killed by Windows prior to executing global destructors if it is
still running when leaving main().  This then corrupts state because the RMW
layer is blocking in a waitset and causes Cyclone to hang trying to destroy the
waitset.

Signed-off-by: Erik Boasson <eb@ilities.com>
timonegk pushed a commit to timonegk/ros-rolling-rclcpp-release that referenced this pull request May 21, 2022
ros-rolling-rclcpp (16.0.1-1jammy) jammy; urgency=high
.
  * remove DEFINE_CONTENT_FILTER cmake option (#1914 <https://github.com/ros2/rclcpp/issues/1914>)
  * Contributors: Chen Lihui
.
ros-rolling-rclcpp (16.0.0-1jammy) jammy; urgency=high
.
  * remove things that were deprecated during galactic (#1913 <https://github.com/ros2/rclcpp/issues/1913>)
  * Contributors: William Woodall
.
ros-rolling-rclcpp (15.4.0-1jammy) jammy; urgency=high
.
  * add take_data_by_entity_id API to waitable (#1892 <https://github.com/ros2/rclcpp/issues/1892>)
  * add content-filtered-topic interfaces (#1561 <https://github.com/ros2/rclcpp/issues/1561>)
  * Contributors: Alberto Soragna, Chen Lihui
.
ros-rolling-rclcpp (15.3.0-1jammy) jammy; urgency=high
.
  * [NodeParameters] Set name in param info pre-check (#1908 <https://github.com/ros2/rclcpp/issues/1908>)
  * Add test-dep ament_cmake_google_benchmark (#1904 <https://github.com/ros2/rclcpp/issues/1904>)
  * Add publish by loaned message in GenericPublisher (#1856 <https://github.com/ros2/rclcpp/issues/1856>)
  * Contributors: Abrar Rahman Protyasha, Barry Xu, Gaël Écorchard
.
ros-rolling-rclcpp (15.2.0-1jammy) jammy; urgency=high
.
  * Add missing ament dependency on rcl_interfaces (#1903 <https://github.com/ros2/rclcpp/issues/1903>)
  * Update data callback tests to account for all published samples (#1900 <https://github.com/ros2/rclcpp/issues/1900>)
  * Increase timeout for acknowledgments to account for slower Connext settings (#1901 <https://github.com/ros2/rclcpp/issues/1901>)
  * clang-tidy: explicit constructors (#1782 <https://github.com/ros2/rclcpp/issues/1782>)
  * Add client/service QoS getters (#1784 <https://github.com/ros2/rclcpp/issues/1784>)
  * Fix a bunch more rosdoc2 issues in rclcpp. (#1897 <https://github.com/ros2/rclcpp/issues/1897>)
  * time_until_trigger returns max time if timer is cancelled (#1893 <https://github.com/ros2/rclcpp/issues/1893>)
  * Micro-optimizations in rclcpp (#1896 <https://github.com/ros2/rclcpp/issues/1896>)
  * Contributors: Andrea Sorbini, Chris Lalancette, Mauro Passerino, Scott K Logan, William Woodall
.
ros-rolling-rclcpp (15.1.0-1jammy) jammy; urgency=high
.
  * spin_all with a zero timeout. (#1878 <https://github.com/ros2/rclcpp/issues/1878>)
  * Add RMW listener APIs (#1579 <https://github.com/ros2/rclcpp/issues/1579>)
  * Remove fastrtps customization on tests (#1887 <https://github.com/ros2/rclcpp/issues/1887>)
  * Install headers to include/${PROJECT_NAME} (#1888 <https://github.com/ros2/rclcpp/issues/1888>)
  * Use ament_generate_version_header (#1886 <https://github.com/ros2/rclcpp/issues/1886>)
  * use universal reference to support rvalue. (#1883 <https://github.com/ros2/rclcpp/issues/1883>)
  * fix one subscription can wait_for_message twice (#1870 <https://github.com/ros2/rclcpp/issues/1870>)
  * Add return value version of get_parameter_or (#1813 <https://github.com/ros2/rclcpp/issues/1813>)
  * Cleanup time source object lifetimes (#1867 <https://github.com/ros2/rclcpp/issues/1867>)
  * add is_spinning() method to executor base class
  * Contributors: Alberto Soragna, Chen Lihui, Chris Lalancette, Kenji Miyake, Miguel Company, Shane Loretz, Tomoya Fujita, iRobot ROS
.
ros-rolling-rclcpp (15.0.0-1jammy) jammy; urgency=high
.
  * Cleanup the TypeAdapt tests (#1858 <https://github.com/ros2/rclcpp/issues/1858>)
  * Cleanup includes (#1857 <https://github.com/ros2/rclcpp/issues/1857>)
  * Fix include order and relative paths for cpplint (#1859 <https://github.com/ros2/rclcpp/issues/1859>)
  * Rename stringstream in macros to a more unique name (#1862 <https://github.com/ros2/rclcpp/issues/1862>)
  * Add non transform capabilities for intra-process (#1849 <https://github.com/ros2/rclcpp/issues/1849>)
  * Fix rclcpp documentation build (#1779 <https://github.com/ros2/rclcpp/issues/1779>)
  * Contributors: Chris Lalancette, Doug Smith, Gonzo, Jacob Perron, Michel Hidalgo
.
ros-rolling-rclcpp (14.1.0-1jammy) jammy; urgency=high
.
  * Use UninitializedStaticallyTypedParameterException (#1689 <https://github.com/ros2/rclcpp/issues/1689>)
  * Add wait_for_all_acked support (#1662 <https://github.com/ros2/rclcpp/issues/1662>)
  * Add tests for function templates of declare_parameter (#1747 <https://github.com/ros2/rclcpp/issues/1747>)
  * Contributors: Barry Xu, Bi0T1N, M. Mostafa Farzan
.
ros-rolling-rclcpp (14.0.0-1jammy) jammy; urgency=high
.
  * Fixes for uncrustify 0.72 (#1844 <https://github.com/ros2/rclcpp/issues/1844>)
  * use private member to keep the all reference underneath. (#1845 <https://github.com/ros2/rclcpp/issues/1845>)
  * Make node base sharable (#1832 <https://github.com/ros2/rclcpp/issues/1832>)
  * Add Clock::sleep_for() (#1828 <https://github.com/ros2/rclcpp/issues/1828>)
  * Synchronize rcl and std::chrono steady clocks in Clock::sleep_until (#1830 <https://github.com/ros2/rclcpp/issues/1830>)
  * Use rclcpp::guard_condition (#1612 <https://github.com/ros2/rclcpp/issues/1612>)
  * Call CMake function to generate version header (#1805 <https://github.com/ros2/rclcpp/issues/1805>)
  * Use parantheses around logging macro parameter (#1820 <https://github.com/ros2/rclcpp/issues/1820>)
  * Remove author by request (#1818 <https://github.com/ros2/rclcpp/issues/1818>)
  * Update maintainers (#1817 <https://github.com/ros2/rclcpp/issues/1817>)
  * min_forward & min_backward thresholds must not be disabled (#1815 <https://github.com/ros2/rclcpp/issues/1815>)
  * Re-add Clock::sleep_until (#1814 <https://github.com/ros2/rclcpp/issues/1814>)
  * Fix lifetime of context so it remains alive while its dependent node handles are still in use (#1754 <https://github.com/ros2/rclcpp/issues/1754>)
  * Add the interface for pre-shutdown callback (#1714 <https://github.com/ros2/rclcpp/issues/1714>)
  * Take message ownership from moved LoanedMessage (#1808 <https://github.com/ros2/rclcpp/issues/1808>)
  * Suppress clang dead-store warnings in the benchmarks. (#1802 <https://github.com/ros2/rclcpp/issues/1802>)
  * Wait for publisher and subscription to match (#1777 <https://github.com/ros2/rclcpp/issues/1777>)
  * Fix unused QoS profile for clock subscription and make ClockQoS the default (#1801 <https://github.com/ros2/rclcpp/issues/1801>)
  * Contributors: Abrar Rahman Protyasha, Barry Xu, Chen Lihui, Chris Lalancette, Grey, Jacob Perron, Nikolai Morin, Shane Loretz, Tomoya Fujita, mauropasse
.
ros-rolling-rclcpp (13.1.0-1jammy) jammy; urgency=high
.
  * Fix dangerous std::bind capture in TimeSource implementation. (#1768 <https://github.com/ros2/rclcpp/issues/1768>)
  * Fix dangerous std::bind capture in ParameterEventHandler implementation. (#1770 <https://github.com/ros2/rclcpp/issues/1770>)
  * Handle sigterm, in the same way sigint is being handled. (#1771 <https://github.com/ros2/rclcpp/issues/1771>)
  * rclcpp::Node copy constructor: make copy of node_waitables_ member. (#1799 <https://github.com/ros2/rclcpp/issues/1799>)
  * Extend NodeGraph to match what rcl provides. (#1484 <https://github.com/ros2/rclcpp/issues/1484>)
  * Context::sleep_for(): replace recursion with do-while to avoid potential stack-overflow. (#1765 <https://github.com/ros2/rclcpp/issues/1765>)
  * extend_sub_namespace(): Verify string::empty() before calling string::front(). (#1764 <https://github.com/ros2/rclcpp/issues/1764>)
  * Deprecate the void shared_ptr<MessageT> subscription callback signatures. (#1713 <https://github.com/ros2/rclcpp/issues/1713>)
  * Contributors: Abrar Rahman Protyasha, Chris Lalancette, Emerson Knapp, Geoffrey Biggs, Ivan Santiago Paunovic, Jorge Perez, Tomoya Fujita, William Woodall, Yong-Hao Zou, livanov93
.
ros-rolling-rclcpp (13.0.0-1jammy) jammy; urgency=high
.
  * Remove can_be_nullptr assignment check for QNX case. (#1752 <https://github.com/ros2/rclcpp/issues/1752>)
  * Update client API to be able to remove pending requests. (#1734 <https://github.com/ros2/rclcpp/issues/1734>)
  * Fix: Allow to add a node while spinning in the StaticSingleThreadedExecutor. (#1690 <https://github.com/ros2/rclcpp/issues/1690>)
  * Add tracing instrumentation for executor and message taking. (#1738 <https://github.com/ros2/rclcpp/issues/1738>)
  * Fix: Reset timer trigger time before execute in StaticSingleThreadedExecutor. (#1739 <https://github.com/ros2/rclcpp/issues/1739>)
  * Use FindPython3 and make python3 dependency explicit. (#1745 <https://github.com/ros2/rclcpp/issues/1745>)
  * Use rosidl_get_typesupport_target(). (#1729 <https://github.com/ros2/rclcpp/issues/1729>)
  * Fix returning invalid namespace if sub_namespace is empty. (#1658 <https://github.com/ros2/rclcpp/issues/1658>)
  * Add free function to wait for a subscription message. (#1705 <https://github.com/ros2/rclcpp/issues/1705>)
  * Use rcpputils/scope_exit.hpp and remove rclcpp/scope_exit.hpp. (#1727 <https://github.com/ros2/rclcpp/issues/1727>)
  * Contributors: Ahmed Sobhy, Christophe Bedard, Ivan Santiago Paunovic, Karsten Knese, M. Hofstätter, Mauro Passerino, Shane Loretz, mauropasse
.
ros-rolling-rclcpp (12.0.0-1jammy) jammy; urgency=high
.
  * Remove unsafe get_callback_groups API.
    Callers should change to using for_each_callback_group(), or
    store the callback groups they need internally.
  * Add in callback_groups_for_each.
    The main reason to add this method in is to make accesses to the
    callback_groups_ vector thread-safe.  By having a
    callback_groups_for_each that accepts a std::function, we can
    just have the callers give us the callback they are interested
    in, and we can take care of the locking.
    The rest of this fairly large PR is cleaning up all of the places
    that use get_callback_groups() to instead use
    callback_groups_for_each().
  * Use a different mechanism to avoid timers being scheduled multiple times by the MultiThreadedExecutor (#1692 <https://github.com/ros2/rclcpp/issues/1692>)
  * Fix windows CI (#1726 <https://github.com/ros2/rclcpp/issues/1726>)
    Fix bug in AnyServiceCallback introduced in #1709 <https://github.com/ros2/rclcpp/issues/1709>.
  * Contributors: Chris Lalancette, Ivan Santiago Paunovic
.
ros-rolling-rclcpp (11.2.0-1jammy) jammy; urgency=high
.
  * Support to defer to send a response in services. (#1709 <https://github.com/ros2/rclcpp/issues/1709>)
    Signed-off-by: Ivan Santiago Paunovic <mailto:ivanpauno@ekumenlabs.com>
  * Fix documentation bug. (#1719 <https://github.com/ros2/rclcpp/issues/1719>)
    Signed-off-by: William Woodall <mailto:william@osrfoundation.org>
  * Contributors: Ivan Santiago Paunovic, William Woodall
.
ros-rolling-rclcpp (11.1.0-1jammy) jammy; urgency=high
.
  * Removed left over ``is_initialized()`` implementation (#1711 <https://github.com/ros2/rclcpp/issues/1711>)
    Leftover from https://github.com/ros2/rclcpp/pull/1622
  * Fixed declare parameter methods for int and float vectors (#1696 <https://github.com/ros2/rclcpp/issues/1696>)
  * Cleaned up implementation of the intra-process manager (#1695 <https://github.com/ros2/rclcpp/issues/1695>)
  * Added the node name to an executor ``runtime_error`` (#1686 <https://github.com/ros2/rclcpp/issues/1686>)
  * Fixed a typo "Attack" -> "Attach" (#1687 <https://github.com/ros2/rclcpp/issues/1687>)
  * Removed use of std::allocator<>::rebind (#1678 <https://github.com/ros2/rclcpp/issues/1678>)
    rebind is deprecated in c++17 and removed in c++20
  * Contributors: Alberto Soragna, Chen Lihui, Chris Lalancette, Petter Nilsson, Steve Macenski, William Woodall
.
ros-rolling-rclcpp (11.0.0-1jammy) jammy; urgency=high
.
  * Allow declare uninitialized parameters (#1673 <https://github.com/ros2/rclcpp/issues/1673>)
  * Fix syntax issue with gcc (#1674 <https://github.com/ros2/rclcpp/issues/1674>)
  * [service] Don't use a weak_ptr to avoid leaking (#1668 <https://github.com/ros2/rclcpp/issues/1668>)
  * Contributors: Ivan Santiago Paunovic, Jacob Perron, William Woodall
.
ros-rolling-rclcpp (10.0.0-1jammy) jammy; urgency=high
.
  * Fix doc typo (#1663 <https://github.com/ros2/rclcpp/issues/1663>)
  * [rclcpp] Type Adaptation feature (#1557 <https://github.com/ros2/rclcpp/issues/1557>)
  * Do not attempt to use void allocators for memory allocation. (#1657 <https://github.com/ros2/rclcpp/issues/1657>)
  * Keep custom allocator in publisher and subscription options alive. (#1647 <https://github.com/ros2/rclcpp/issues/1647>)
  * Fix get_publishers_subscriptions_info_by_topic test in test_node.cpp (#1648 <https://github.com/ros2/rclcpp/issues/1648>)
  * Use OnShutdown callback handle instead of OnShutdown callback (#1639 <https://github.com/ros2/rclcpp/issues/1639>)
  * use dynamic_pointer_cast to detect allocator mismatch in intra process manager (#1643 <https://github.com/ros2/rclcpp/issues/1643>)
  * Increase cppcheck timeout to 500s (#1634 <https://github.com/ros2/rclcpp/issues/1634>)
  * Clarify node parameters docs (#1631 <https://github.com/ros2/rclcpp/issues/1631>)
  * Contributors: Audrow Nash, Barry Xu, Jacob Perron, Michel Hidalgo, Shane Loretz, William Woodall
.
ros-rolling-rclcpp (9.0.2-1jammy) jammy; urgency=high
.
  * Avoid returning loan when none was obtained. (#1629 <https://github.com/ros2/rclcpp/issues/1629>)
  * Use a different implementation of mutex two priorities (#1628 <https://github.com/ros2/rclcpp/issues/1628>)
  * Do not test the value of the history policy when testing the get_publishers/subscriptions_info_by_topic() methods (#1626 <https://github.com/ros2/rclcpp/issues/1626>)
  * Check first parameter type and range before calling the user validation callbacks (#1627 <https://github.com/ros2/rclcpp/issues/1627>)
  * Contributors: Ivan Santiago Paunovic, Miguel Company
.
ros-rolling-rclcpp (9.0.1-1jammy) jammy; urgency=high
.
  * Restore test exception for Connext (#1625 <https://github.com/ros2/rclcpp/issues/1625>)
  * Fix race condition in TimeSource clock thread setup (#1623 <https://github.com/ros2/rclcpp/issues/1623>)
  * Contributors: Andrea Sorbini, Michel Hidalgo
.
ros-rolling-rclcpp (9.0.0-1jammy) jammy; urgency=high
.
  * remove deprecated code which was deprecated in foxy and should be removed in galactic (#1622 <https://github.com/ros2/rclcpp/issues/1622>)
  * Change index.ros.org -> docs.ros.org. (#1620 <https://github.com/ros2/rclcpp/issues/1620>)
  * Unique network flows (#1496 <https://github.com/ros2/rclcpp/issues/1496>)
  * Add spin_some support to the StaticSingleThreadedExecutor (#1338 <https://github.com/ros2/rclcpp/issues/1338>)
  * Add publishing instrumentation (#1600 <https://github.com/ros2/rclcpp/issues/1600>)
  * Create load_parameters and delete_parameters methods (#1596 <https://github.com/ros2/rclcpp/issues/1596>)
  * refactor AnySubscriptionCallback and add/deprecate callback signatures (#1598 <https://github.com/ros2/rclcpp/issues/1598>)
  * Add generic publisher and generic subscription for serialized messages (#1452 <https://github.com/ros2/rclcpp/issues/1452>)
  * use context from node_base_ for clock executor. (#1617 <https://github.com/ros2/rclcpp/issues/1617>)
  * updating quality declaration links (re: ros2/docs.ros2.org#52 <https://github.com/ros2/docs.ros2.org/issues/52>) (#1615 <https://github.com/ros2/rclcpp/issues/1615>)
  * Contributors: Ananya Muddukrishna, BriceRenaudeau, Chris Lalancette, Christophe Bedard, Nikolai Morin, Tomoya Fujita, William Woodall, mauropasse, shonigmann
.
ros-rolling-rclcpp (8.2.0-1jammy) jammy; urgency=high
.
  * Initialize integers in test_parameter_event_handler.cpp to avoid undefined behavior (#1609 <https://github.com/ros2/rclcpp/issues/1609>)
  * Namespace tracetools C++ functions (#1608 <https://github.com/ros2/rclcpp/issues/1608>)
  * Revert "Namespace tracetools C++ functions (#1603 <https://github.com/ros2/rclcpp/issues/1603>)" (#1607 <https://github.com/ros2/rclcpp/issues/1607>)
  * Namespace tracetools C++ functions (#1603 <https://github.com/ros2/rclcpp/issues/1603>)
  * Clock subscription callback group spins in its own thread (#1556 <https://github.com/ros2/rclcpp/issues/1556>)
  * Contributors: Chris Lalancette, Christophe Bedard, Ivan Santiago Paunovic, anaelle-sw
.
ros-rolling-rclcpp (8.1.0-1jammy) jammy; urgency=high
.
  * Remove rmw_connext_cpp references. (#1595 <https://github.com/ros2/rclcpp/issues/1595>)
  * Add API for checking QoS profile compatibility (#1554 <https://github.com/ros2/rclcpp/issues/1554>)
  * Document misuse of parameters callback (#1590 <https://github.com/ros2/rclcpp/issues/1590>)
  * use const auto & to iterate over parameters (#1593 <https://github.com/ros2/rclcpp/issues/1593>)
  * Contributors: Chris Lalancette, Jacob Perron, Karsten Knese
.
ros-rolling-rclcpp (8.0.0-1jammy) jammy; urgency=high
.
  * Guard against integer overflow in duration conversion (#1584 <https://github.com/ros2/rclcpp/issues/1584>)
  * Contributors: Jacob Perron
.
ros-rolling-rclcpp (7.0.1-1jammy) jammy; urgency=high
.
  * get_parameters service should return empty if undeclared parameters are allowed (#1514 <https://github.com/ros2/rclcpp/issues/1514>)
  * Made 'Context::shutdown_reason' function a const function (#1578 <https://github.com/ros2/rclcpp/issues/1578>)
  * Contributors: Tomoya Fujita, suab321321
.
ros-rolling-rclcpp (7.0.0-1jammy) jammy; urgency=high
.
  * Document design decisions that were made for statically typed parameters (#1568 <https://github.com/ros2/rclcpp/issues/1568>)
  * Fix doc typo in CallbackGroup constructor (#1582 <https://github.com/ros2/rclcpp/issues/1582>)
  * Enable qos parameter overrides for the /parameter_events topic  (#1532 <https://github.com/ros2/rclcpp/issues/1532>)
  * Add support for rmw_connextdds (#1574 <https://github.com/ros2/rclcpp/issues/1574>)
  * Remove 'struct' from the rcl_time_jump_t. (#1577 <https://github.com/ros2/rclcpp/issues/1577>)
  * Add tests for declaring statically typed parameters when undeclared parameters are allowed (#1575 <https://github.com/ros2/rclcpp/issues/1575>)
  * Quiet clang memory leak warning on "DoNotOptimize". (#1571 <https://github.com/ros2/rclcpp/issues/1571>)
  * Add ParameterEventsSubscriber class (#829 <https://github.com/ros2/rclcpp/issues/829>)
  * When a parameter change is rejected, the parameters map shouldn't be updated. (#1567 <https://github.com/ros2/rclcpp/pull/1567>)
  * Fix when to throw the NoParameterOverrideProvided exception. (#1567 <https://github.com/ros2/rclcpp/pull/1567>)
  * Fix SEGV caused by order of destruction of Node sub-interfaces (#1469 <https://github.com/ros2/rclcpp/issues/1469>)
  * Fix benchmark test failure introduced in #1522 <https://github.com/ros2/rclcpp/issues/1522> (#1564 <https://github.com/ros2/rclcpp/issues/1564>)
  * Fix documented example in create_publisher (#1558 <https://github.com/ros2/rclcpp/issues/1558>)
  * Enforce static parameter types (#1522 <https://github.com/ros2/rclcpp/issues/1522>)
  * Allow timers to keep up the intended rate in MultiThreadedExecutor (#1516 <https://github.com/ros2/rclcpp/issues/1516>)
  * Fix UBSAN warnings in any_subscription_callback. (#1551 <https://github.com/ros2/rclcpp/issues/1551>)
  * Fix runtime error: reference binding to null pointer of type (#1547 <https://github.com/ros2/rclcpp/issues/1547>)
  * Contributors: Andrea Sorbini, Chris Lalancette, Colin MacKenzie, Ivan Santiago Paunovic, Jacob Perron, Steven! Ragnarök, bpwilcox, tomoya
.
ros-rolling-rclcpp (6.3.1-1jammy) jammy; urgency=high
.
  * Reference test resources directly from source tree (#1543 <https://github.com/ros2/rclcpp/issues/1543>)
  * clear statistics after window reset (#1531 <https://github.com/ros2/rclcpp/issues/1531>) (#1535 <https://github.com/ros2/rclcpp/issues/1535>)
  * Fix a minor string error in the topic_statistics test. (#1541 <https://github.com/ros2/rclcpp/issues/1541>)
  * Avoid Resource deadlock avoided if use intra_process_comms (#1530 <https://github.com/ros2/rclcpp/issues/1530>)
  * Avoid an object copy in parameter_value.cpp. (#1538 <https://github.com/ros2/rclcpp/issues/1538>)
  * Assert that the publisher_list size is 1. (#1537 <https://github.com/ros2/rclcpp/issues/1537>)
  * Don't access objects after they have been std::move (#1536 <https://github.com/ros2/rclcpp/issues/1536>)
  * Update for checking correct variable (#1534 <https://github.com/ros2/rclcpp/issues/1534>)
  * Destroy msg extracted from LoanedMessage. (#1305 <https://github.com/ros2/rclcpp/issues/1305>)
  * Contributors: Chen Lihui, Chris Lalancette, Ivan Santiago Paunovic, Miaofei Mei, Scott K Logan, William Woodall, hsgwa
.
ros-rolling-rclcpp (6.3.0-1jammy) jammy; urgency=high
.
  * Add instrumentation for linking a timer to a node (#1500 <https://github.com/ros2/rclcpp/issues/1500>)
  * Fix error when using IPC with StaticSingleThreadExecutor (#1520 <https://github.com/ros2/rclcpp/issues/1520>)
  * Change to using unique_ptrs for DummyExecutor. (#1517 <https://github.com/ros2/rclcpp/issues/1517>)
  * Allow reconfiguring 'clock' topic qos (#1512 <https://github.com/ros2/rclcpp/issues/1512>)
  * Allow to add/remove nodes thread safely in rclcpp::Executor  (#1505 <https://github.com/ros2/rclcpp/issues/1505>)
  * Call rclcpp::shutdown in test_node for clean shutdown on Windows (#1515 <https://github.com/ros2/rclcpp/issues/1515>)
  * Reapply "Add get_logging_directory method to rclcpp::Logger (#1509 <https://github.com/ros2/rclcpp/issues/1509>)" (#1513 <https://github.com/ros2/rclcpp/issues/1513>)
  * use describe_parameters of parameter client for test (#1499 <https://github.com/ros2/rclcpp/issues/1499>)
  * Revert "Add get_logging_directory method to rclcpp::Logger (#1509 <https://github.com/ros2/rclcpp/issues/1509>)" (#1511 <https://github.com/ros2/rclcpp/issues/1511>)
  * Add get_logging_directory method to rclcpp::Logger (#1509 <https://github.com/ros2/rclcpp/issues/1509>)
  * Contributors: Chris Lalancette, Christophe Bedard, Ivan Santiago Paunovic, eboasson, mauropasse, tomoya
.
ros-rolling-rclcpp (6.2.0-1jammy) jammy; urgency=high
.
  * Better documentation for the QoS class (#1508 <https://github.com/ros2/rclcpp/issues/1508>)
  * Modify excluding callback duration from topic statistics (#1492 <https://github.com/ros2/rclcpp/issues/1492>)
  * Make the test of graph users more robust. (#1504 <https://github.com/ros2/rclcpp/issues/1504>)
  * Make sure to wait for graph change events in test_node_graph. (#1503 <https://github.com/ros2/rclcpp/issues/1503>)
  * add timeout to SyncParametersClient methods (#1493 <https://github.com/ros2/rclcpp/issues/1493>)
  * Fix wrong test expectations (#1497 <https://github.com/ros2/rclcpp/issues/1497>)
  * Update create_publisher/subscription documentation, clarifying when a parameters interface is required (#1494 <https://github.com/ros2/rclcpp/issues/1494>)
  * Fix string literal warnings (#1442 <https://github.com/ros2/rclcpp/issues/1442>)
  * support describe_parameters methods to parameter client. (#1453 <https://github.com/ros2/rclcpp/issues/1453>)
  * Contributors: Audrow Nash, Chris Lalancette, Ivan Santiago Paunovic, Nikolai Morin, hsgwa, tomoya
.
ros-rolling-rclcpp (6.1.0-1jammy) jammy; urgency=high
.
  * Add getters to rclcpp::qos and rclcpp::Policy enum classes (#1467 <https://github.com/ros2/rclcpp/issues/1467>)
  * Change nullptr checks to use ASSERT_TRUE. (#1486 <https://github.com/ros2/rclcpp/issues/1486>)
  * Adjust logic around finding and erasing guard_condition (#1474 <https://github.com/ros2/rclcpp/issues/1474>)
  * Update QDs to QL 1 (#1477 <https://github.com/ros2/rclcpp/issues/1477>)
  * Add performance tests for parameter transport (#1463 <https://github.com/ros2/rclcpp/issues/1463>)
  * Contributors: Chris Lalancette, Ivan Santiago Paunovic, Scott K Logan, Stephen Brawner
.
ros-rolling-rclcpp (6.0.0-1jammy) jammy; urgency=high
.
  * Move ownership of shutdown_guard_condition to executors/graph_listener (#1404 <https://github.com/ros2/rclcpp/issues/1404>)
  * Add options to automatically declare qos parameters when creating a publisher/subscription (#1465 <https://github.com/ros2/rclcpp/issues/1465>)
  * Add take_data to Waitable and data to AnyExecutable (#1241 <https://github.com/ros2/rclcpp/issues/1241>)
  * Add benchmarks for node parameters interface (#1444 <https://github.com/ros2/rclcpp/issues/1444>)
  * Remove allocation from executor::remove_node() (#1448 <https://github.com/ros2/rclcpp/issues/1448>)
  * Fix test crashes on CentOS 7 (#1449 <https://github.com/ros2/rclcpp/issues/1449>)
  * Bump rclcpp packages to Quality Level 2 (#1445 <https://github.com/ros2/rclcpp/issues/1445>)
  * Added executor benchmark tests (#1413 <https://github.com/ros2/rclcpp/issues/1413>)
  * Add fully-qualified namespace to WeakCallbackGroupsToNodesMap (#1435 <https://github.com/ros2/rclcpp/issues/1435>)
  * Contributors: Alejandro Hernández Cordero, Audrow Nash, Chris Lalancette, Ivan Santiago Paunovic, Louise Poubel, Scott K Logan, brawner
.
ros-rolling-rclcpp (5.1.0-1jammy) jammy; urgency=high
.
  * Deprecate Duration(rcl_duration_value_t) in favor of static Duration::from_nanoseconds(rcl_duration_value_t) (#1432 <https://github.com/ros2/rclcpp/issues/1432>)
  * Avoid parsing arguments twice in rclcpp::init_and_remove_ros_arguments (#1415 <https://github.com/ros2/rclcpp/issues/1415>)
  * Add service and client benchmarks (#1425 <https://github.com/ros2/rclcpp/issues/1425>)
  * Set CMakeLists to only use default rmw for benchmarks (#1427 <https://github.com/ros2/rclcpp/issues/1427>)
  * Update tracetools' QL in rclcpp's QD (#1428 <https://github.com/ros2/rclcpp/issues/1428>)
  * Add missing locking to the rclcpp_action::ServerBase. (#1421 <https://github.com/ros2/rclcpp/issues/1421>)
  * Initial benchmark tests for rclcpp::init/shutdown create/destroy node (#1411 <https://github.com/ros2/rclcpp/issues/1411>)
  * Refactor test CMakeLists in prep for benchmarks (#1422 <https://github.com/ros2/rclcpp/issues/1422>)
  * Add methods in topic and service interface to resolve a name (#1410 <https://github.com/ros2/rclcpp/issues/1410>)
  * Update deprecated gtest macros (#1370 <https://github.com/ros2/rclcpp/issues/1370>)
  * Clear members for StaticExecutorEntitiesCollector to avoid shared_ptr dependency (#1303 <https://github.com/ros2/rclcpp/issues/1303>)
  * Increase test timeouts of slow running tests with rmw_connext_cpp (#1400 <https://github.com/ros2/rclcpp/issues/1400>)
  * Avoid self dependency that not destoryed (#1301 <https://github.com/ros2/rclcpp/issues/1301>)
  * Update maintainers (#1384 <https://github.com/ros2/rclcpp/issues/1384>)
  * Add clock qos to node options (#1375 <https://github.com/ros2/rclcpp/issues/1375>)
  * Fix NodeOptions copy constructor (#1376 <https://github.com/ros2/rclcpp/issues/1376>)
  * Make sure to clean the external client/service handle. (#1296 <https://github.com/ros2/rclcpp/issues/1296>)
  * Increase coverage of WaitSetTemplate (#1368 <https://github.com/ros2/rclcpp/issues/1368>)
  * Increase coverage of guard_condition.cpp to 100% (#1369 <https://github.com/ros2/rclcpp/issues/1369>)
  * Add coverage statement (#1367 <https://github.com/ros2/rclcpp/issues/1367>)
  * Tests for LoanedMessage with mocked loaned message publisher (#1366 <https://github.com/ros2/rclcpp/issues/1366>)
  * Add unit tests for qos and qos_event files (#1352 <https://github.com/ros2/rclcpp/issues/1352>)
  * Finish coverage of publisher API (#1365 <https://github.com/ros2/rclcpp/issues/1365>)
  * Finish API coverage on executors. (#1364 <https://github.com/ros2/rclcpp/issues/1364>)
  * Add test for ParameterService (#1355 <https://github.com/ros2/rclcpp/issues/1355>)
  * Add time API coverage tests (#1347 <https://github.com/ros2/rclcpp/issues/1347>)
  * Add timer coverage tests (#1363 <https://github.com/ros2/rclcpp/issues/1363>)
  * Add in additional tests for parameter_client.cpp coverage.
  * Minor fixes to the parameter_service.cpp file.
  * reset rcl_context shared_ptr after calling rcl_init sucessfully (#1357 <https://github.com/ros2/rclcpp/issues/1357>)
  * Improved test publisher - zero qos history depth value exception (#1360 <https://github.com/ros2/rclcpp/issues/1360>)
  * Covered resolve_use_intra_process (#1359 <https://github.com/ros2/rclcpp/issues/1359>)
  * Improve test_subscription_options (#1358 <https://github.com/ros2/rclcpp/issues/1358>)
  * Add in more tests for init_options coverage. (#1353 <https://github.com/ros2/rclcpp/issues/1353>)
  * Test the remaining node public API (#1342 <https://github.com/ros2/rclcpp/issues/1342>)
  * Complete coverage of Parameter and ParameterValue API (#1344 <https://github.com/ros2/rclcpp/issues/1344>)
  * Add in more tests for the utilities. (#1349 <https://github.com/ros2/rclcpp/issues/1349>)
  * Add in two more tests for expand_topic_or_service_name. (#1350 <https://github.com/ros2/rclcpp/issues/1350>)
  * Add tests for node_options API (#1343 <https://github.com/ros2/rclcpp/issues/1343>)
  * Add in more coverage for expand_topic_or_service_name. (#1346 <https://github.com/ros2/rclcpp/issues/1346>)
  * Test exception in spin_until_future_complete. (#1345 <https://github.com/ros2/rclcpp/issues/1345>)
  * Add coverage tests graph_listener (#1330 <https://github.com/ros2/rclcpp/issues/1330>)
  * Add in unit tests for the Executor class.
  * Allow mimick patching of methods with up to 9 arguments.
  * Improve the error messages in the Executor class.
  * Add coverage for client API (#1329 <https://github.com/ros2/rclcpp/issues/1329>)
  * Increase service coverage (#1332 <https://github.com/ros2/rclcpp/issues/1332>)
  * Make more of the static entity collector API private.
  * Const-ify more of the static executor.
  * Add more tests for the static single threaded executor.
  * Many more tests for the static_executor_entities_collector.
  * Get one more line of code coverage in memory_strategy.cpp
  * Bugfix when adding callback group.
  * Fix typos in comments.
  * Remove deprecated executor::FutureReturnCode APIs. (#1327 <https://github.com/ros2/rclcpp/issues/1327>)
  * Increase coverage of publisher/subscription API (#1325 <https://github.com/ros2/rclcpp/issues/1325>)
  * Not finalize guard condition while destructing SubscriptionIntraProcess (#1307 <https://github.com/ros2/rclcpp/issues/1307>)
  * Expose qos setting for /rosout (#1247 <https://github.com/ros2/rclcpp/issues/1247>)
  * Add coverage for missing API (except executors) (#1326 <https://github.com/ros2/rclcpp/issues/1326>)
  * Include topic name in QoS mismatch warning messages (#1286 <https://github.com/ros2/rclcpp/issues/1286>)
  * Add coverage tests context functions (#1321 <https://github.com/ros2/rclcpp/issues/1321>)
  * Increase coverage of node_interfaces, including with mocking rcl errors (#1322 <https://github.com/ros2/rclcpp/issues/1322>)
  * Contributors: Ada-King, Alejandro Hernández Cordero, Audrow Nash, Barry Xu, Chen Lihui, Chris Lalancette, Christophe Bedard, Ivan Santiago Paunovic, Jorge Perez, Morgan Quigley, brawner
.
ros-rolling-rclcpp (5.0.0-1jammy) jammy; urgency=high
.
  * Make node_graph::count_graph_users() const (#1320 <https://github.com/ros2/rclcpp/issues/1320>)
  * Add coverage for wait_set_policies (#1316 <https://github.com/ros2/rclcpp/issues/1316>)
  * Only exchange intra_process waitable if nonnull (#1317 <https://github.com/ros2/rclcpp/issues/1317>)
  * Check waitable for nullptr during constructor (#1315 <https://github.com/ros2/rclcpp/issues/1315>)
  * Call vector.erase with end iterator overload (#1314 <https://github.com/ros2/rclcpp/issues/1314>)
  * Use best effort, keep last, history depth 1 QoS Profile for '/clock' subscriptions (#1312 <https://github.com/ros2/rclcpp/issues/1312>)
  * Add tests type_support module (#1308 <https://github.com/ros2/rclcpp/issues/1308>)
  * Replace std_msgs with test_msgs in executors test (#1310 <https://github.com/ros2/rclcpp/issues/1310>)
  * Add set_level for rclcpp::Logger (#1284 <https://github.com/ros2/rclcpp/issues/1284>)
  * Remove unused private function (rclcpp::Node and rclcpp_lifecycle::Node) (#1294 <https://github.com/ros2/rclcpp/issues/1294>)
  * Adding tests basic getters (#1291 <https://github.com/ros2/rclcpp/issues/1291>)
  * Adding callback groups in executor (#1218 <https://github.com/ros2/rclcpp/issues/1218>)
  * Refactor Subscription Topic Statistics Tests (#1281 <https://github.com/ros2/rclcpp/issues/1281>)
  * Add operator!= for duration (#1236 <https://github.com/ros2/rclcpp/issues/1236>)
  * Fix clock thread issue (#1266 <https://github.com/ros2/rclcpp/issues/1266>) (#1267 <https://github.com/ros2/rclcpp/issues/1267>)
  * Fix topic stats test, wait for more messages, only check the ones with samples (#1274 <https://github.com/ros2/rclcpp/issues/1274>)
  * Add get_domain_id method to rclcpp::Context (#1271 <https://github.com/ros2/rclcpp/issues/1271>)
  * Fixes for unit tests that fail under cyclonedds (#1270 <https://github.com/ros2/rclcpp/issues/1270>)
  * initialize_logging_ should be copied (#1272 <https://github.com/ros2/rclcpp/issues/1272>)
  * Use static_cast instead of C-style cast for instrumentation (#1263 <https://github.com/ros2/rclcpp/issues/1263>)
  * Make parameter clients use template constructors (#1249 <https://github.com/ros2/rclcpp/issues/1249>)
  * Ability to configure domain_id via InitOptions. (#1165 <https://github.com/ros2/rclcpp/issues/1165>)
  * Simplify and fix allocator memory strategy unit test for connext (#1252 <https://github.com/ros2/rclcpp/issues/1252>)
  * Use global namespace for parameter events subscription topic (#1257 <https://github.com/ros2/rclcpp/issues/1257>)
  * Increase timeouts for connext for long tests (#1253 <https://github.com/ros2/rclcpp/issues/1253>)
  * Adjust test_static_executor_entities_collector for rmw_connext_cpp (#1251 <https://github.com/ros2/rclcpp/issues/1251>)
  * Fix failing test with Connext since it doesn't wait for discovery (#1246 <https://github.com/ros2/rclcpp/issues/1246>)
  * Fix node graph test with Connext and CycloneDDS returning actual data (#1245 <https://github.com/ros2/rclcpp/issues/1245>)
  * Warn about unused result of add_on_set_parameters_callback (#1238 <https://github.com/ros2/rclcpp/issues/1238>)
  * Unittests for memory strategy files, except allocator_memory_strategy (#1189 <https://github.com/ros2/rclcpp/issues/1189>)
  * EXPECT_THROW_EQ and ASSERT_THROW_EQ macros for unittests (#1232 <https://github.com/ros2/rclcpp/issues/1232>)
  * Add unit test for static_executor_entities_collector (#1221 <https://github.com/ros2/rclcpp/issues/1221>)
  * Parameterize test executors for all executor types (#1222 <https://github.com/ros2/rclcpp/issues/1222>)
  * Unit tests for allocator_memory_strategy.cpp part 2 (#1198 <https://github.com/ros2/rclcpp/issues/1198>)
  * Unit tests for allocator_memory_strategy.hpp (#1197 <https://github.com/ros2/rclcpp/issues/1197>)
  * Derive and throw exception in spin_some spin_all for StaticSingleThreadedExecutor (#1220 <https://github.com/ros2/rclcpp/issues/1220>)
  * Make ring buffer thread-safe (#1213 <https://github.com/ros2/rclcpp/issues/1213>)
  * Add missing RCLCPP_PUBLIC to ~StaticExecutorEntitiesCollector (#1227 <https://github.com/ros2/rclcpp/issues/1227>)
  * Document graph functions don't apply remap rules (#1225 <https://github.com/ros2/rclcpp/issues/1225>)
  * Remove recreation of entities_collector (#1217 <https://github.com/ros2/rclcpp/issues/1217>)
  * Contributors: Audrow Nash, Chen Lihui, Christophe Bedard, Daisuke Sato, Devin Bonnie, Dirk Thomas, Ivan Santiago Paunovic, Jacob Perron, Jannik Abbenseth, Jorge Perez, Pedro Pena, Shane Loretz, Stephen Brawner, Tomoya Fujita
.
ros-rolling-rclcpp (4.0.0-1jammy) jammy; urgency=high
.
  * Fix rclcpp::NodeOptions::operator= (#1211 <https://github.com/ros2/rclcpp/issues/1211>)
  * Link against thread library where necessary (#1210 <https://github.com/ros2/rclcpp/issues/1210>)
  * Unit tests for node interfaces (#1202 <https://github.com/ros2/rclcpp/issues/1202>)
  * Remove usage of domain id in node options (#1205 <https://github.com/ros2/rclcpp/issues/1205>)
  * Remove deprecated set_on_parameters_set_callback function (#1199 <https://github.com/ros2/rclcpp/issues/1199>)
  * Fix conversion of negative durations to messages (#1188 <https://github.com/ros2/rclcpp/issues/1188>)
  * Fix implementation of NodeOptions::use_global_arguments() (#1176 <https://github.com/ros2/rclcpp/issues/1176>)
  * Bump to QD to level 3 and fixed links (#1158 <https://github.com/ros2/rclcpp/issues/1158>)
  * Fix pub/sub count API tests (#1203 <https://github.com/ros2/rclcpp/issues/1203>)
  * Update tracetools' QL to 2 in rclcpp's QD (#1187 <https://github.com/ros2/rclcpp/issues/1187>)
  * Fix exception message on rcl_clock_init (#1182 <https://github.com/ros2/rclcpp/issues/1182>)
  * Throw exception if rcl_timer_init fails (#1179 <https://github.com/ros2/rclcpp/issues/1179>)
  * Unit tests for some header-only functions/classes (#1181 <https://github.com/ros2/rclcpp/issues/1181>)
  * Callback should be perfectly-forwarded (#1183 <https://github.com/ros2/rclcpp/issues/1183>)
  * Add unit tests for logging functionality (#1184 <https://github.com/ros2/rclcpp/issues/1184>)
  * Add create_publisher include to create_subscription (#1180 <https://github.com/ros2/rclcpp/issues/1180>)
  * Contributors: Alejandro Hernández Cordero, Christophe Bedard, Claire Wang, Dirk Thomas, Ivan Santiago Paunovic, Johannes Meyer, Michel Hidalgo, Stephen Brawner, tomoya
.
ros-rolling-rclcpp (3.0.0-1jammy) jammy; urgency=high
.
  * Check period duration in create_wall_timer (#1178 <https://github.com/ros2/rclcpp/issues/1178>)
  * Fix get_node_time_source_interface() docstring (#988 <https://github.com/ros2/rclcpp/issues/988>)
  * Add message lost subscription event (#1164 <https://github.com/ros2/rclcpp/issues/1164>)
  * Add spin_all method to Executor (#1156 <https://github.com/ros2/rclcpp/issues/1156>)
  * Reorganize test directory and split CMakeLists.txt (#1173 <https://github.com/ros2/rclcpp/issues/1173>)
  * Check if context is valid when looping in spin_some (#1167 <https://github.com/ros2/rclcpp/issues/1167>)
  * Add check for invalid topic statistics publish period (#1151 <https://github.com/ros2/rclcpp/issues/1151>)
  * Fix spin_until_future_complete: check spinning value (#1023 <https://github.com/ros2/rclcpp/issues/1023>)
  * Fix doxygen warnings (#1163 <https://github.com/ros2/rclcpp/issues/1163>)
  * Fix reference to rclcpp in its Quality declaration (#1161 <https://github.com/ros2/rclcpp/issues/1161>)
  * Allow spin_until_future_complete to accept any future like object (#1113 <https://github.com/ros2/rclcpp/issues/1113>)
  * Contributors: Alejandro Hernández Cordero, Christophe Bedard, Devin Bonnie, Dirk Thomas, DongheeYe, Ivan Santiago Paunovic, Jacob Perron, Sarthak Mittal, brawner, tomoya
.
ros-rolling-rclcpp (2.0.0-1jammy) jammy; urgency=high
.
  * Added missing virtual destructors. (#1149 <https://github.com/ros2/rclcpp/issues/1149>)
  * Fixed a test which was using different types on the same topic. (#1150 <https://github.com/ros2/rclcpp/issues/1150>)
  * Made ``test_rate`` more reliable on Windows and improve error output when it fails (#1146 <https://github.com/ros2/rclcpp/issues/1146>)
  * Added Security Vulnerability Policy pointing to REP-2006. (#1130 <https://github.com/ros2/rclcpp/issues/1130>)
  * Added missing header in ``logging_mutex.cpp``. (#1145 <https://github.com/ros2/rclcpp/issues/1145>)
  * Changed the WaitSet API to pass a shared pointer by value instead than by const reference when possible. (#1141 <https://github.com/ros2/rclcpp/issues/1141>)
  * Changed ``SubscriptionBase::get_subscription_handle() const`` to return a shared pointer to const value. (#1140 <https://github.com/ros2/rclcpp/issues/1140>)
  * Extended the lifetime of ``rcl_publisher_t`` by holding onto the shared pointer in order to avoid a use after free situation. (#1119 <https://github.com/ros2/rclcpp/issues/1119>)
  * Improved some docblocks (#1127 <https://github.com/ros2/rclcpp/issues/1127>)
  * Fixed a lock-order-inversion (potential deadlock) (#1135 <https://github.com/ros2/rclcpp/issues/1135>)
  * Fixed a potential Construction/Destruction order problem between global contexts vector and Context of static lifetime (#1132 <https://github.com/ros2/rclcpp/issues/1132>)
  * Contributors: Alejandro Hernández Cordero, Chris Lalancette, Ivan Santiago Paunovic, Michel Hidalgo, tomoya
.
ros-rolling-rclcpp (1.1.0-1jammy) jammy; urgency=high
.
  * Deprecate set_on_parameters_set_callback (#1123 <https://github.com/ros2/rclcpp/issues/1123>)
  * Expose get_service_names_and_types_by_node from rcl in rclcpp (#1131 <https://github.com/ros2/rclcpp/issues/1131>)
  * Fix thread safety issues related to logging (#1125 <https://github.com/ros2/rclcpp/issues/1125>)
  * Make sure rmw_publisher_options is initialized in to_rcl_publisher_options (#1099 <https://github.com/ros2/rclcpp/issues/1099>)
  * Remove empty lines within method signatures (#1128 <https://github.com/ros2/rclcpp/issues/1128>)
  * Add API review March 2020 document (#1031 <https://github.com/ros2/rclcpp/issues/1031>)
  * Improve documentation (#1106 <https://github.com/ros2/rclcpp/issues/1106>)
  * Make test multi threaded executor more reliable (#1105 <https://github.com/ros2/rclcpp/issues/1105>)
  * Fixed rep links and added more details to dependencies in quality declaration (#1116 <https://github.com/ros2/rclcpp/issues/1116>)
  * Update quality declarations to reflect version 1.0 (#1115 <https://github.com/ros2/rclcpp/issues/1115>)
  * Contributors: Alejandro Hernández Cordero, ChenYing Kuo, Claire Wang, Dirk Thomas, Ivan Santiago Paunovic, William Woodall, Stephen Brawner
.
ros-rolling-rclcpp (1.0.0-1jammy) jammy; urgency=high
.
  * Remove MANUAL_BY_NODE liveliness API (#1107 <https://github.com/ros2/rclcpp/issues/1107>)
  * Use rosidl_default_generators dependency in test (#1114 <https://github.com/ros2/rclcpp/issues/1114>)
  * Make sure to include what you use (#1112 <https://github.com/ros2/rclcpp/issues/1112>)
  * Mark flaky test with xfail: TestMultiThreadedExecutor (#1109 <https://github.com/ros2/rclcpp/issues/1109>)
  * Contributors: Chris Lalancette, Ivan Santiago Paunovic, Karsten Knese, Louise Poubel
.
ros-rolling-rclcpp (0.9.1-1jammy) jammy; urgency=high
.
  * Fix tests that were not properly torn down (#1073 <https://github.com/ros2/rclcpp/issues/1073>)
  * Added docblock in rclcpp (#1103 <https://github.com/ros2/rclcpp/issues/1103>)
  * Added Quality declaration: rclcpp, rclpp_action, rclcpp_components andrclcpp_lifecycle (#1100 <https://github.com/ros2/rclcpp/issues/1100>)
  * Use RCL_RET_SERVICE_TAKE_FAILED and not RCL_RET_CLIENT_TAKE_FAILED when checking a request take (#1101 <https://github.com/ros2/rclcpp/issues/1101>)
  * Update comment about return value in Executor::get_next_ready_executable (#1085 <https://github.com/ros2/rclcpp/issues/1085>)
  * Contributors: Alejandro Hernández Cordero, Christophe Bedard, Devin Bonnie, Ivan Santiago Paunovic
.
ros-rolling-rclcpp (0.9.0-1jammy) jammy; urgency=high
.
  * Serialized message move constructor (#1097 <https://github.com/ros2/rclcpp/issues/1097>)
  * Enforce a precedence for wildcard matching in parameter overrides. (#1094 <https://github.com/ros2/rclcpp/issues/1094>)
  * Add serialized_message.hpp header (#1095 <https://github.com/ros2/rclcpp/issues/1095>)
  * Add received message age metric to topic statistics (#1080 <https://github.com/ros2/rclcpp/issues/1080>)
  * Deprecate redundant namespaces (#1083 <https://github.com/ros2/rclcpp/issues/1083>)
  * Export targets in addition to include directories / libraries (#1088 <https://github.com/ros2/rclcpp/issues/1088>)
  * Ensure logging is initialized just once (#998 <https://github.com/ros2/rclcpp/issues/998>)
  * Adapt subscription traits to rclcpp::SerializedMessage (#1092 <https://github.com/ros2/rclcpp/issues/1092>)
  * Protect subscriber_statistics_collectors_ with a mutex (#1084 <https://github.com/ros2/rclcpp/issues/1084>)
  * Remove unused test variable (#1087 <https://github.com/ros2/rclcpp/issues/1087>)
  * Use serialized message (#1081 <https://github.com/ros2/rclcpp/issues/1081>)
  * Integrate topic statistics (#1072 <https://github.com/ros2/rclcpp/issues/1072>)
  * Fix rclcpp interface traits test (#1086 <https://github.com/ros2/rclcpp/issues/1086>)
  * Generate node interfaces' getters and traits (#1069 <https://github.com/ros2/rclcpp/issues/1069>)
  * Use composition for serialized message (#1082 <https://github.com/ros2/rclcpp/issues/1082>)
  * Dnae adas/serialized message (#1075 <https://github.com/ros2/rclcpp/issues/1075>)
  * Reflect changes in rclcpp API (#1079 <https://github.com/ros2/rclcpp/issues/1079>)
  * Fix build regression (#1078 <https://github.com/ros2/rclcpp/issues/1078>)
  * Add NodeDefault option for enabling topic statistics (#1074 <https://github.com/ros2/rclcpp/issues/1074>)
  * Topic Statistics: Add SubscriptionTopicStatistics class (#1050 <https://github.com/ros2/rclcpp/issues/1050>)
  * Add SubscriptionOptions for topic statistics (#1057 <https://github.com/ros2/rclcpp/issues/1057>)
  * Remove warning message from failing to register default callback (#1067 <https://github.com/ros2/rclcpp/issues/1067>)
  * Create a default warning for qos incompatibility (#1051 <https://github.com/ros2/rclcpp/issues/1051>)
  * Add WaitSet class and modify entities to work without executor (#1047 <https://github.com/ros2/rclcpp/issues/1047>)
  * Include what you use (#1059 <https://github.com/ros2/rclcpp/issues/1059>)
  * Rename rosidl_generator_cpp namespace to rosidl_runtime_cpp (#1060 <https://github.com/ros2/rclcpp/issues/1060>)
  * Changed rosidl_generator_c/cpp to rosidl_runtime_c/cpp (#1014 <https://github.com/ros2/rclcpp/issues/1014>)
  * Use constexpr for endpoint type name (#1055 <https://github.com/ros2/rclcpp/issues/1055>)
  * Add InvalidParameterTypeException (#1027 <https://github.com/ros2/rclcpp/issues/1027>)
  * Support for ON_REQUESTED_INCOMPATIBLE_QOS and ON_OFFERED_INCOMPATIBLE_QOS events (#924 <https://github.com/ros2/rclcpp/issues/924>)
  * Fixup clang warning (#1040 <https://github.com/ros2/rclcpp/issues/1040>)
  * Adding a "static" single threaded executor (#1034 <https://github.com/ros2/rclcpp/issues/1034>)
  * Add equality operators for QoS profile (#1032 <https://github.com/ros2/rclcpp/issues/1032>)
  * Remove extra vertical whitespace (#1030 <https://github.com/ros2/rclcpp/issues/1030>)
  * Switch IntraProcessMessage to test_msgs/Empty (#1017 <https://github.com/ros2/rclcpp/issues/1017>)
  * Add new type of exception that may be thrown during creation of publisher/subscription (#1026 <https://github.com/ros2/rclcpp/issues/1026>)
  * Don't check lifespan on publisher QoS (#1002 <https://github.com/ros2/rclcpp/issues/1002>)
  * Fix get_parameter_tyeps of AsyncPrameterClient results are always empty (#1019 <https://github.com/ros2/rclcpp/issues/1019>)
  * Cleanup node interfaces includes (#1016 <https://github.com/ros2/rclcpp/issues/1016>)
  * Add ifdefs to remove tracing-related calls if tracing is disabled (#1001 <https://github.com/ros2/rclcpp/issues/1001>)
  * Include missing header in node_graph.cpp (#994 <https://github.com/ros2/rclcpp/issues/994>)
  * Add missing includes of logging.hpp (#995 <https://github.com/ros2/rclcpp/issues/995>)
  * Zero initialize publisher GID in subscription intra process callback (#1011 <https://github.com/ros2/rclcpp/issues/1011>)
  * Removed ament_cmake dependency (#989 <https://github.com/ros2/rclcpp/issues/989>)
  * Switch to using new rcutils_strerror (#993 <https://github.com/ros2/rclcpp/issues/993>)
  * Ensure all rclcpp::Clock accesses are thread-safe
  * Use a PIMPL for rclcpp::Clock implementation
  * Replace rmw_implementation for rmw dependency in package.xml (#990 <https://github.com/ros2/rclcpp/issues/990>)
  * Add missing service callback registration tracepoint (#986 <https://github.com/ros2/rclcpp/issues/986>)
  * Rename rmw_topic_endpoint_info_array count to size (#996 <https://github.com/ros2/rclcpp/issues/996>)
  * Implement functions to get publisher and subcription informations like QoS policies from topic name (#960 <https://github.com/ros2/rclcpp/issues/960>)
  * Code style only: wrap after open parenthesis if not in one line (#977 <https://github.com/ros2/rclcpp/issues/977>)
  * Accept taking an rvalue ref future in spin_until_future_complete (#971 <https://github.com/ros2/rclcpp/issues/971>)
  * Allow node clock use in logging macros (#969 <https://github.com/ros2/rclcpp/issues/969>) (#970 <https://github.com/ros2/rclcpp/issues/970>)
  * Change order of deprecated and visibility attributes (#968 <https://github.com/ros2/rclcpp/issues/968>)
  * Deprecated is_initialized() (#967 <https://github.com/ros2/rclcpp/issues/967>)
  * Don't specify calling convention in std::_Binder template (#952 <https://github.com/ros2/rclcpp/issues/952>)
  * Added missing include to logging.hpp (#964 <https://github.com/ros2/rclcpp/issues/964>)
  * Assigning make_shared result to variables in test (#963 <https://github.com/ros2/rclcpp/issues/963>)
  * Fix unused parameter warning (#962 <https://github.com/ros2/rclcpp/issues/962>)
  * Stop retaining ownership of the rcl context in GraphListener (#946 <https://github.com/ros2/rclcpp/issues/946>)
  * Clear sub contexts when starting another init-shutdown cycle (#947 <https://github.com/ros2/rclcpp/issues/947>)
  * Avoid possible UB in Clock jump callbacks (#954 <https://github.com/ros2/rclcpp/issues/954>)
  * Handle unknown global ROS arguments (#951 <https://github.com/ros2/rclcpp/issues/951>)
  * Mark get_clock() as override to fix clang warnings (#939 <https://github.com/ros2/rclcpp/issues/939>)
  * Create node clock calls const (try 2) (#922 <https://github.com/ros2/rclcpp/issues/922>)
  * Fix asserts on shared_ptr::use_count; expects long, got uint32 (#936 <https://github.com/ros2/rclcpp/issues/936>)
  * Use absolute topic name for parameter events (#929 <https://github.com/ros2/rclcpp/issues/929>)
  * Add enable_rosout into NodeOptions. (#900 <https://github.com/ros2/rclcpp/issues/900>)
  * Removing "virtual", adding "override" keywords (#897 <https://github.com/ros2/rclcpp/issues/897>)
  * Use weak_ptr to store context in GraphListener (#906 <https://github.com/ros2/rclcpp/issues/906>)
  * Complete published event message when declaring a parameter (#928 <https://github.com/ros2/rclcpp/issues/928>)
  * Fix duration.cpp lint error (#930 <https://github.com/ros2/rclcpp/issues/930>)
  * Intra-process subscriber should use RMW actual qos. (ros2`#913 <https://github.com/ros2/rclcpp/issues/913>`_) (#914 <https://github.com/ros2/rclcpp/issues/914>)
  * Type conversions fixes (#901 <https://github.com/ros2/rclcpp/issues/901>)
  * Add override keyword to functions
  * Remove unnecessary virtual keywords
  * Only check for new work once in spin_some (#471 <https://github.com/ros2/rclcpp/issues/471>) (#844 <https://github.com/ros2/rclcpp/issues/844>)
  * Add addition/subtraction assignment operators to Time (#748 <https://github.com/ros2/rclcpp/issues/748>)
  * Contributors: Alberto Soragna, Alejandro Hernández Cordero, Barry Xu, Chris Lalancette, Christophe Bedard, Claire Wang, Dan Rose, DensoADAS, Devin Bonnie, Dino Hüllmann, Dirk Thomas, DongheeYe, Emerson Knapp, Ivan Santiago Paunovic, Jacob Perron, Jaison Titus, Karsten Knese, Matt Schickler, Miaofei Mei, Michel Hidalgo, Mikael Arguedas, Monika Idzik, Prajakta Gokhale, Roger Strain, Scott K Logan, Sean Kelly, Stephen Brawner, Steven Macenski, Steven! Ragnarök, Todd Malsbary, Tomoya Fujita, William Woodall, Zachary Michaels
.
ros-rolling-rclcpp (0.8.3-1jammy) jammy; urgency=high
.
.
.
ros-rolling-rclcpp (0.8.2-1jammy) jammy; urgency=high
.
  * Updated tracing logic to match changes in rclcpp's intra-process system (#918 <https://github.com/ros2/rclcpp/issues/918>)
  * Fixed a bug that prevented the ``shutdown_on_sigint`` option to not work correctly (#850 <https://github.com/ros2/rclcpp/issues/850>)
  * Added support for STREAM logging macros (#926 <https://github.com/ros2/rclcpp/issues/926>)
  * Relaxed multithreaded test constraint (#907 <https://github.com/ros2/rclcpp/issues/907>)
  * Contributors: Anas Abou Allaban, Christophe Bedard, Dirk Thomas, alexfneves
.
ros-rolling-rclcpp (0.8.1-1jammy) jammy; urgency=high
.
  * De-flake tests for rmw_connext (#899 <https://github.com/ros2/rclcpp/issues/899>)
  * rename return functions for loaned messages (#896 <https://github.com/ros2/rclcpp/issues/896>)
  * Enable throttling logs (#879 <https://github.com/ros2/rclcpp/issues/879>)
  * New Intra-Process Communication (#778 <https://github.com/ros2/rclcpp/issues/778>)
  * Instrumentation update (#789 <https://github.com/ros2/rclcpp/issues/789>)
  * Zero copy api (#864 <https://github.com/ros2/rclcpp/issues/864>)
  * Drop rclcpp remove_ros_arguments_null test case. (#894 <https://github.com/ros2/rclcpp/issues/894>)
  * add mechanism to pass rmw impl specific payloads during pub/sub creation (#882 <https://github.com/ros2/rclcpp/issues/882>)
  * make get_actual_qos return a rclcpp::QoS (#883 <https://github.com/ros2/rclcpp/issues/883>)
  * Fix Compiler Warning (#881 <https://github.com/ros2/rclcpp/issues/881>)
  * Add callback handler for use_sim_time parameter #802 <https://github.com/ros2/rclcpp/issues/802> (#875 <https://github.com/ros2/rclcpp/issues/875>)
  * Contributors: Alberto Soragna, Brian Marchi, Hunter L. Allen, Ingo Lütkebohle, Karsten Knese, Michael Carroll, Michel Hidalgo, William Woodall
.
ros-rolling-rclcpp (0.8.0-1jammy) jammy; urgency=high
.
  * clean up publisher and subscription creation logic (#867 <https://github.com/ros2/rclcpp/issues/867>)
  * Take parameter overrides provided through the CLI. (#865 <https://github.com/ros2/rclcpp/issues/865>)
  * add more context to exception message (#858 <https://github.com/ros2/rclcpp/issues/858>)
  * remove features and related code which were deprecated in dashing (#852 <https://github.com/ros2/rclcpp/issues/852>)
  * check valid timer handler 1st to reduce the time window for scan. (#841 <https://github.com/ros2/rclcpp/issues/841>)
  * Add throwing parameter name if parameter is not set (#833 <https://github.com/ros2/rclcpp/issues/833>)
  * Fix typo in deprecated warning. (#848 <https://github.com/ros2/rclcpp/issues/848>)
  * Fail on invalid and unknown ROS specific arguments (#842 <https://github.com/ros2/rclcpp/issues/842>)
  * Force explicit --ros-args in NodeOptions::arguments(). (#845 <https://github.com/ros2/rclcpp/issues/845>)
  * Use of -r/--remap flags where appropriate. (#834 <https://github.com/ros2/rclcpp/issues/834>)
  * Fix hang with timers in MultiThreadedExecutor (#835 <https://github.com/ros2/rclcpp/issues/835>) (#836 <https://github.com/ros2/rclcpp/issues/836>)
  * add mutex in add/remove_node and wait_for_work to protect concurrent use/change of memory_strategy_ (#837 <https://github.com/ros2/rclcpp/issues/837>)
  * Crash in callback group pointer vector iterator (#814 <https://github.com/ros2/rclcpp/issues/814>)
  * Wrap documentation examples in code blocks (#830 <https://github.com/ros2/rclcpp/issues/830>)
  * add callback group as member variable and constructor arg (#811 <https://github.com/ros2/rclcpp/issues/811>)
  * Fix get_node_interfaces functions taking a pointer (#821 <https://github.com/ros2/rclcpp/issues/821>)
  * Delete unnecessary call for get_node_by_group (#823 <https://github.com/ros2/rclcpp/issues/823>)
  * Allow passing logger by const ref (#820 <https://github.com/ros2/rclcpp/issues/820>)
  * Explain return value of spin_until_future_complete (#792 <https://github.com/ros2/rclcpp/issues/792>)
  * Adapt to '--ros-args ... [--]'-based ROS args extraction (#816 <https://github.com/ros2/rclcpp/issues/816>)
  * Add line break after first open paren in multiline function call (#785 <https://github.com/ros2/rclcpp/issues/785>)
  * remove mock msgs from rclcpp (#800 <https://github.com/ros2/rclcpp/issues/800>)
  * Make TimeSource ignore use_sim_time events coming from other nodes. (#799 <https://github.com/ros2/rclcpp/issues/799>)
  * Allow registering multiple on_parameters_set_callback (#772 <https://github.com/ros2/rclcpp/issues/772>)
  * Add free function for creating service clients (#788 <https://github.com/ros2/rclcpp/issues/788>)
  * Include missing rcl headers in use. (#782 <https://github.com/ros2/rclcpp/issues/782>)
  * Switch the NodeParameters lock to recursive. (#781 <https://github.com/ros2/rclcpp/issues/781>)
  * changed on_parameter_event qos profile to rmw_qos_profile_parameter_events (#774 <https://github.com/ros2/rclcpp/issues/774>)
  * Adding a factory method to create a Duration from seconds (#567 <https://github.com/ros2/rclcpp/issues/567>)
  * Fix a comparison with a sign mismatch (#771 <https://github.com/ros2/rclcpp/issues/771>)
  * delete superfluous spaces (#770 <https://github.com/ros2/rclcpp/issues/770>)
  * Use params from node '/**' from parameter YAML file (#762 <https://github.com/ros2/rclcpp/issues/762>)
  * Add ignore override argument to declare parameter (#767 <https://github.com/ros2/rclcpp/issues/767>)
  * use default parameter descriptor in parameters interface (#765 <https://github.com/ros2/rclcpp/issues/765>)
  * Added support for const member functions (#763 <https://github.com/ros2/rclcpp/issues/763>)
  * add get_actual_qos() feature to subscriptions (#754 <https://github.com/ros2/rclcpp/issues/754>)
  * Ignore parameters overrides in set parameter methods when allowing undeclared parameters (#756 <https://github.com/ros2/rclcpp/issues/756>)
  * Add rclcpp::create_timer() (#757 <https://github.com/ros2/rclcpp/issues/757>)
  * checking origin of intra-process msg before taking them (#753 <https://github.com/ros2/rclcpp/issues/753>)
  * Contributors: Alberto Soragna, Carl Delsey, Chris Lalancette, Dan Rose, Dirk Thomas, Esteve Fernandez, Guillaume Autran, Jacob Perron, Karsten Knese, Luca Della Vedova, M. M, Michel Hidalgo, Scott K Logan, Shane Loretz, Todd Malsbary, William Woodall, bpwilcox, fujitatomoya, ivanpauno
.
ros-rolling-rclcpp (0.7.5-1jammy) jammy; urgency=high
.
  * Avoid 'Intra process message no longer being stored when trying to handle it' warning (#749 <https://github.com/ros2/rclcpp/issues/749>)
  * Contributors: ivanpauno
.
ros-rolling-rclcpp (0.7.4-1jammy) jammy; urgency=high
.
  * Rename parameter options (#745 <https://github.com/ros2/rclcpp/issues/745>)
  * Bionic use of strerror_r (#742 <https://github.com/ros2/rclcpp/issues/742>)
  * Enforce parameter ranges (#735 <https://github.com/ros2/rclcpp/issues/735>)
  * removed not used parameter client (#740 <https://github.com/ros2/rclcpp/issues/740>)
  * ensure removal of guard conditions of expired nodes from memory strategy (#741 <https://github.com/ros2/rclcpp/issues/741>)
  * Fix typo in log warning message (#737 <https://github.com/ros2/rclcpp/issues/737>)
  * Throw nice errors when creating a publisher with intraprocess communication and incompatible qos policy (#729 <https://github.com/ros2/rclcpp/issues/729>)
  * Contributors: Alberto Soragna, Dirk Thomas, Jacob Perron, William Woodall, ivanpauno, roderick-koehle
.
ros-rolling-rclcpp (0.7.3-1jammy) jammy; urgency=high
.
  * Fixed misspelling, volitile -> volatile (#724 <https://github.com/ros2/rclcpp/issues/724>), and then fixed that since it is a C++ keyword to be ``durability_volatile`` (#725 <https://github.com/ros2/rclcpp/issues/725>)
  * Fixed a clang warning (#723 <https://github.com/ros2/rclcpp/issues/723>)
  * Added ``on_parameter_event`` static method to the ``AsyncParametersClient`` (#688 <https://github.com/ros2/rclcpp/issues/688>)
  * Added a guard against ``ParameterNotDeclaredException`` throwing from within the parameter service callbacks. (#718 <https://github.com/ros2/rclcpp/issues/718>)
  * Added missing template functionality to lifecycle_node. (#707 <https://github.com/ros2/rclcpp/issues/707>)
  * Fixed heap-use-after-free and memory leaks reported from ``test_node.cpp`` (#719 <https://github.com/ros2/rclcpp/issues/719>)
  * Contributors: Alberto Soragna, Dirk Thomas, Emerson Knapp, Jacob Perron, Michael Jeronimo, Prajakta Gokhale
.
ros-rolling-rclcpp (0.7.2-1jammy) jammy; urgency=high
.
  * Added new way to specify QoS settings for publishers and subscriptions. (#713 <https://github.com/ros2/rclcpp/issues/713>)
    * The new way requires that you specify a history depth when creating a publisher or subscription.
    * In the past it was possible to create one without specifying any history depth, but these signatures have been deprecated.
  * Deprecated ``shared_ptr`` and raw pointer versions of ``Publisher<T>::publish()``. (#709 <https://github.com/ros2/rclcpp/issues/709>)
  * Implemented API to set callbacks for liveliness and deadline QoS events for publishers and subscriptions. (#695 <https://github.com/ros2/rclcpp/issues/695>)
  * Fixed a segmentation fault when publishing a parameter event when they ought to be disabled. (#714 <https://github.com/ros2/rclcpp/issues/714>)
  * Changes required for upcoming pre-allocation API. (#711 <https://github.com/ros2/rclcpp/issues/711>)
  * Changed ``Node::get_node_names()`` to return the full node names rather than just the base name. (#698 <https://github.com/ros2/rclcpp/issues/698>)
  * Remove logic made redundant by the ros2/rcl#255 <https://github.com/ros2/rcl/issues/255> pull request. (#712 <https://github.com/ros2/rclcpp/issues/712>)
  * Various improvements for ``rclcpp::Clock``. (#696 <https://github.com/ros2/rclcpp/issues/696>)
    * Fixed uninitialized bool in ``clock.cpp``.
    * Fixed up includes of ``clock.hpp/cpp``.
    * Added documentation for exceptions to ``clock.hpp``.
    * Adjusted function signature of getters of ``clock.hpp/cpp``.
    * Removed raw pointers to ``Clock::create_jump_callback``.
    * Removed unnecessary ``rclcpp`` namespace reference from ``clock.cpp``.
    * Changed exception to ``bad_alloc`` on ``JumpHandler`` allocation failure.
    * Fixed missing ``nullptr`` check in ``Clock::on_time_jump``.
    * Added ``JumpHandler::callback`` types.
    * Added warning for lifetime of Clock and JumpHandler
  * Fixed bug left over from the pull request #495 <https://github.com/ros2/rclcpp/pull/495>. (#708 <https://github.com/ros2/rclcpp/issues/708>)
  * Changed the ``IntraProcessManager`` to be capable of storing ``shared_ptr<const T>`` in addition to ``unique_ptr<T>``. (#690 <https://github.com/ros2/rclcpp/issues/690>)
  * Contributors: Alberto Soragna, Dima Dorezyuk, M. M, Michael Carroll, Michael Jeronimo, Tully Foote, William Woodall, ivanpauno, jhdcs
.
ros-rolling-rclcpp (0.7.1-1jammy) jammy; urgency=high
.
  * Added read only parameters. (#495 <https://github.com/ros2/rclcpp/issues/495>)
  * Fixed a concurrency problem in the multithreaded executor. (#703 <https://github.com/ros2/rclcpp/issues/703>)
  * Fixup utilities. (#692 <https://github.com/ros2/rclcpp/issues/692>)
  * Added method to read timer cancellation. (#697 <https://github.com/ros2/rclcpp/issues/697>)
  * Added Exception Generator function for implementing "from_rcl_error". (#678 <https://github.com/ros2/rclcpp/issues/678>)
  * Updated initialization of rmw_qos_profile_t struct instances. (#691 <https://github.com/ros2/rclcpp/issues/691>)
  * Removed the const value from the logger before comparison. (#680 <https://github.com/ros2/rclcpp/issues/680>)
  * Contributors: Devin Bonnie, Dima Dorezyuk, Guillaume Autran, M. M, Shane Loretz, Víctor Mayoral Vilches, William Woodall, jhdcs
.
ros-rolling-rclcpp (0.7.0-1jammy) jammy; urgency=high
.
  * Added Options-struct interfaces for creating publishers/subscribers (pre-QoS, standalone). (#673 <https://github.com/ros2/rclcpp/issues/673>)
  * Replaced strncpy with memcpy. (#684 <https://github.com/ros2/rclcpp/issues/684>)
  * Replaced const char * with a std::array<char, TOPIC_NAME_LENGTH> as the key of IPM IDTopicMap. (#671 <https://github.com/ros2/rclcpp/issues/671>)
  * Refactored SignalHandler logger to avoid race during destruction. (#682 <https://github.com/ros2/rclcpp/issues/682>)
  * Introduce rclcpp_components to implement composition. (#665 <https://github.com/ros2/rclcpp/issues/665>)
  * Added QoS policy check when configuring intraprocess, skip interprocess publish when possible. (#674 <https://github.com/ros2/rclcpp/issues/674>)
  * Updated to use do { .. } while(0) around content of logging macros. (#681 <https://github.com/ros2/rclcpp/issues/681>)
  * Added function to get publisher's actual QoS settings. (#667 <https://github.com/ros2/rclcpp/issues/667>)
  * Updated to avoid race that triggers timer too often. (#621 <https://github.com/ros2/rclcpp/issues/621>)
  * Exposed get_fully_qualified_name in NodeBase API. (#662 <https://github.com/ros2/rclcpp/issues/662>)
  * Updated to use ament_target_dependencies where possible. (#659 <https://github.com/ros2/rclcpp/issues/659>)
  * Fixed wait for service memory leak bug. (#656 <https://github.com/ros2/rclcpp/issues/656>)
  * Fixed test_time_source test. (#639 <https://github.com/ros2/rclcpp/issues/639>)
  * Fixed hard-coded duration type representation so int64_t isn't assumed. (#648 <https://github.com/ros2/rclcpp/issues/648>)
  * Fixed cppcheck warning. (#646 <https://github.com/ros2/rclcpp/issues/646>)
  * Added count matching api and intra-process subscriber count. (#628 <https://github.com/ros2/rclcpp/issues/628>)
  * Added Sub Node alternative. (#581 <https://github.com/ros2/rclcpp/issues/581>)
  * Replaced 'auto' with 'const auto &'. (#630 <https://github.com/ros2/rclcpp/issues/630>)
  * Se…
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.

4 participants