├── README.md ├── ROS2_core ├── ROS2_services.md └── ROS2_logging.md ├── LICENSE └── SMACC2 └── README.md /README.md: -------------------------------------------------------------------------------- 1 | # ROS2_assorted_docs 2 | 3 | This repository groups some assorted ROS 2 documentation notes. 4 | -------------------------------------------------------------------------------- /ROS2_core/ROS2_services.md: -------------------------------------------------------------------------------- 1 | # Study of services wrt realtime-compliance 2 | 3 | ## Sending service requests 4 | 5 | `client::async_send_request(request)`
6 | `client::async_send_request(SharedRequest request, CallbackT && cb)`
7 | `client::async_send_request(SharedRequest request, CallbackT && cb)`
8 | - Call `async_send_request_impl()`, wich: 9 | - Does `pending_requests_.try_emplace()` 10 | - With `pending_requests_` a `std::unordered_map`
11 | **--> potential memory allocation – not realtime-compliant** 12 | 13 |
14 |
15 | 16 | 17 | ## Handling service requests 18 | 19 | I assume that service requests are ultimately handled by a call to `Service::handle_request()`. 20 | This calls `AnyServiceCallback::dispatch()`, followed by `Service::send_reponse()`. 21 | 22 |
23 | 24 | ### `AnyServiceCallback::dispatch()` 25 | 26 | `AnyServiceCallback` emplaces callback functions in an `std::variant`, on call of `AnyServiceCallback::set()`.
27 | **According to** [this post](https://stackoverflow.com/questions/47876022/is-stdvariant-allowed-to-allocate-memory-for-its-members) **an std::variant does not allocate memory on emplace --> the use of an std::variant itself is realtime-compliant.** 28 | 29 | The variant is either of following types of callback function (or `std::monostate` if uninitialized), 30 | that return `void` and take following arguments (as an `std::shared_ptr`): 31 | 32 | 1. `std::monostate`: this is the 'empty' state (i.e. not initialized)
33 |
34 | 35 | 2. `SharedPtrCallback`, with arguments: 36 | - `ServiceT::Request` 37 | - `ServiceT::Response`
38 |
39 | 3. `SharedPtrWithRequestHeaderCallback`, with arguments: 40 | - `rmw_request_id_t` 41 | - `ServiceT::Request` 42 | - `ServiceT::Response`
43 |
44 | 45 | 4. `SharedPtrDeferResponseCallback`, with arguments: 46 | - `rmw_request_id_t` 47 | - `ServiceT::Request`
48 |
49 | 50 | 5. `SharedPtrDeferResponseCallbackWithServiceHandle`, with arguments: 51 | - `rmw_request_id_t` 52 | - `rclcpp::Service` 53 | - `ServiceT::Request` 54 | 55 |
56 | 57 | The 'deferring' functions have an extra callback instead of the response, see following issues/PR: 58 | - [Service server: Extend API to be able to defer a response #1707](https://github.com/ros2/rclcpp/issues/1707) 59 | - [Add the ability to have asynchronous service callbacks #491](https://github.com/ros2/rclcpp/issues/491) 60 | - [Corresponding pull request](https://github.com/ros2/rclcpp/pull/1709) 61 | 62 |
63 |
64 | 65 | 66 | `AnyServiceCallback::dispatch()` 67 | 68 | - In case of a `SharedPtrDeferResponseCallback` or `SharedPtrDeferResponseCallbackWithServiceHandle`: 69 | - Call the callback and return `nullptr`, 70 | - In case of a `SharedPtrCallback` or `SharedPtrWithRequestHeaderCallback`: 71 | - Allocate a response, 72 | - Call the callback, 73 | - Return the response.
74 | **Heap allocation, no support for a custom allocator -- not realtime-compliant** 75 | 76 |
77 | 78 | ### `Service::send_response()` 79 | 80 | This calls `rcl_send_response()` which, according to the code documentation, does not allocate memory and is lock-free. 81 | 82 |
83 |
84 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Attribution 4.0 International 2 | 3 | ======================================================================= 4 | 5 | Creative Commons Corporation ("Creative Commons") is not a law firm and 6 | does not provide legal services or legal advice. Distribution of 7 | Creative Commons public licenses does not create a lawyer-client or 8 | other relationship. Creative Commons makes its licenses and related 9 | information available on an "as-is" basis. Creative Commons gives no 10 | warranties regarding its licenses, any material licensed under their 11 | terms and conditions, or any related information. Creative Commons 12 | disclaims all liability for damages resulting from their use to the 13 | fullest extent possible. 14 | 15 | Using Creative Commons Public Licenses 16 | 17 | Creative Commons public licenses provide a standard set of terms and 18 | conditions that creators and other rights holders may use to share 19 | original works of authorship and other material subject to copyright 20 | and certain other rights specified in the public license below. The 21 | following considerations are for informational purposes only, are not 22 | exhaustive, and do not form part of our licenses. 23 | 24 | Considerations for licensors: Our public licenses are 25 | intended for use by those authorized to give the public 26 | permission to use material in ways otherwise restricted by 27 | copyright and certain other rights. Our licenses are 28 | irrevocable. Licensors should read and understand the terms 29 | and conditions of the license they choose before applying it. 30 | Licensors should also secure all rights necessary before 31 | applying our licenses so that the public can reuse the 32 | material as expected. Licensors should clearly mark any 33 | material not subject to the license. This includes other CC- 34 | licensed material, or material used under an exception or 35 | limitation to copyright. More considerations for licensors: 36 | wiki.creativecommons.org/Considerations_for_licensors 37 | 38 | Considerations for the public: By using one of our public 39 | licenses, a licensor grants the public permission to use the 40 | licensed material under specified terms and conditions. If 41 | the licensor's permission is not necessary for any reason--for 42 | example, because of any applicable exception or limitation to 43 | copyright--then that use is not regulated by the license. Our 44 | licenses grant only permissions under copyright and certain 45 | other rights that a licensor has authority to grant. Use of 46 | the licensed material may still be restricted for other 47 | reasons, including because others have copyright or other 48 | rights in the material. A licensor may make special requests, 49 | such as asking that all changes be marked or described. 50 | Although not required by our licenses, you are encouraged to 51 | respect those requests where reasonable. More considerations 52 | for the public: 53 | wiki.creativecommons.org/Considerations_for_licensees 54 | 55 | ======================================================================= 56 | 57 | Creative Commons Attribution 4.0 International Public License 58 | 59 | By exercising the Licensed Rights (defined below), You accept and agree 60 | to be bound by the terms and conditions of this Creative Commons 61 | Attribution 4.0 International Public License ("Public License"). To the 62 | extent this Public License may be interpreted as a contract, You are 63 | granted the Licensed Rights in consideration of Your acceptance of 64 | these terms and conditions, and the Licensor grants You such rights in 65 | consideration of benefits the Licensor receives from making the 66 | Licensed Material available under these terms and conditions. 67 | 68 | 69 | Section 1 -- Definitions. 70 | 71 | a. Adapted Material means material subject to Copyright and Similar 72 | Rights that is derived from or based upon the Licensed Material 73 | and in which the Licensed Material is translated, altered, 74 | arranged, transformed, or otherwise modified in a manner requiring 75 | permission under the Copyright and Similar Rights held by the 76 | Licensor. For purposes of this Public License, where the Licensed 77 | Material is a musical work, performance, or sound recording, 78 | Adapted Material is always produced where the Licensed Material is 79 | synched in timed relation with a moving image. 80 | 81 | b. Adapter's License means the license You apply to Your Copyright 82 | and Similar Rights in Your contributions to Adapted Material in 83 | accordance with the terms and conditions of this Public License. 84 | 85 | c. Copyright and Similar Rights means copyright and/or similar rights 86 | closely related to copyright including, without limitation, 87 | performance, broadcast, sound recording, and Sui Generis Database 88 | Rights, without regard to how the rights are labeled or 89 | categorized. For purposes of this Public License, the rights 90 | specified in Section 2(b)(1)-(2) are not Copyright and Similar 91 | Rights. 92 | 93 | d. Effective Technological Measures means those measures that, in the 94 | absence of proper authority, may not be circumvented under laws 95 | fulfilling obligations under Article 11 of the WIPO Copyright 96 | Treaty adopted on December 20, 1996, and/or similar international 97 | agreements. 98 | 99 | e. Exceptions and Limitations means fair use, fair dealing, and/or 100 | any other exception or limitation to Copyright and Similar Rights 101 | that applies to Your use of the Licensed Material. 102 | 103 | f. Licensed Material means the artistic or literary work, database, 104 | or other material to which the Licensor applied this Public 105 | License. 106 | 107 | g. Licensed Rights means the rights granted to You subject to the 108 | terms and conditions of this Public License, which are limited to 109 | all Copyright and Similar Rights that apply to Your use of the 110 | Licensed Material and that the Licensor has authority to license. 111 | 112 | h. Licensor means the individual(s) or entity(ies) granting rights 113 | under this Public License. 114 | 115 | i. Share means to provide material to the public by any means or 116 | process that requires permission under the Licensed Rights, such 117 | as reproduction, public display, public performance, distribution, 118 | dissemination, communication, or importation, and to make material 119 | available to the public including in ways that members of the 120 | public may access the material from a place and at a time 121 | individually chosen by them. 122 | 123 | j. Sui Generis Database Rights means rights other than copyright 124 | resulting from Directive 96/9/EC of the European Parliament and of 125 | the Council of 11 March 1996 on the legal protection of databases, 126 | as amended and/or succeeded, as well as other essentially 127 | equivalent rights anywhere in the world. 128 | 129 | k. You means the individual or entity exercising the Licensed Rights 130 | under this Public License. Your has a corresponding meaning. 131 | 132 | 133 | Section 2 -- Scope. 134 | 135 | a. License grant. 136 | 137 | 1. Subject to the terms and conditions of this Public License, 138 | the Licensor hereby grants You a worldwide, royalty-free, 139 | non-sublicensable, non-exclusive, irrevocable license to 140 | exercise the Licensed Rights in the Licensed Material to: 141 | 142 | a. reproduce and Share the Licensed Material, in whole or 143 | in part; and 144 | 145 | b. produce, reproduce, and Share Adapted Material. 146 | 147 | 2. Exceptions and Limitations. For the avoidance of doubt, where 148 | Exceptions and Limitations apply to Your use, this Public 149 | License does not apply, and You do not need to comply with 150 | its terms and conditions. 151 | 152 | 3. Term. The term of this Public License is specified in Section 153 | 6(a). 154 | 155 | 4. Media and formats; technical modifications allowed. The 156 | Licensor authorizes You to exercise the Licensed Rights in 157 | all media and formats whether now known or hereafter created, 158 | and to make technical modifications necessary to do so. The 159 | Licensor waives and/or agrees not to assert any right or 160 | authority to forbid You from making technical modifications 161 | necessary to exercise the Licensed Rights, including 162 | technical modifications necessary to circumvent Effective 163 | Technological Measures. For purposes of this Public License, 164 | simply making modifications authorized by this Section 2(a) 165 | (4) never produces Adapted Material. 166 | 167 | 5. Downstream recipients. 168 | 169 | a. Offer from the Licensor -- Licensed Material. Every 170 | recipient of the Licensed Material automatically 171 | receives an offer from the Licensor to exercise the 172 | Licensed Rights under the terms and conditions of this 173 | Public License. 174 | 175 | b. No downstream restrictions. You may not offer or impose 176 | any additional or different terms or conditions on, or 177 | apply any Effective Technological Measures to, the 178 | Licensed Material if doing so restricts exercise of the 179 | Licensed Rights by any recipient of the Licensed 180 | Material. 181 | 182 | 6. No endorsement. Nothing in this Public License constitutes or 183 | may be construed as permission to assert or imply that You 184 | are, or that Your use of the Licensed Material is, connected 185 | with, or sponsored, endorsed, or granted official status by, 186 | the Licensor or others designated to receive attribution as 187 | provided in Section 3(a)(1)(A)(i). 188 | 189 | b. Other rights. 190 | 191 | 1. Moral rights, such as the right of integrity, are not 192 | licensed under this Public License, nor are publicity, 193 | privacy, and/or other similar personality rights; however, to 194 | the extent possible, the Licensor waives and/or agrees not to 195 | assert any such rights held by the Licensor to the limited 196 | extent necessary to allow You to exercise the Licensed 197 | Rights, but not otherwise. 198 | 199 | 2. Patent and trademark rights are not licensed under this 200 | Public License. 201 | 202 | 3. To the extent possible, the Licensor waives any right to 203 | collect royalties from You for the exercise of the Licensed 204 | Rights, whether directly or through a collecting society 205 | under any voluntary or waivable statutory or compulsory 206 | licensing scheme. In all other cases the Licensor expressly 207 | reserves any right to collect such royalties. 208 | 209 | 210 | Section 3 -- License Conditions. 211 | 212 | Your exercise of the Licensed Rights is expressly made subject to the 213 | following conditions. 214 | 215 | a. Attribution. 216 | 217 | 1. If You Share the Licensed Material (including in modified 218 | form), You must: 219 | 220 | a. retain the following if it is supplied by the Licensor 221 | with the Licensed Material: 222 | 223 | i. identification of the creator(s) of the Licensed 224 | Material and any others designated to receive 225 | attribution, in any reasonable manner requested by 226 | the Licensor (including by pseudonym if 227 | designated); 228 | 229 | ii. a copyright notice; 230 | 231 | iii. a notice that refers to this Public License; 232 | 233 | iv. a notice that refers to the disclaimer of 234 | warranties; 235 | 236 | v. a URI or hyperlink to the Licensed Material to the 237 | extent reasonably practicable; 238 | 239 | b. indicate if You modified the Licensed Material and 240 | retain an indication of any previous modifications; and 241 | 242 | c. indicate the Licensed Material is licensed under this 243 | Public License, and include the text of, or the URI or 244 | hyperlink to, this Public License. 245 | 246 | 2. You may satisfy the conditions in Section 3(a)(1) in any 247 | reasonable manner based on the medium, means, and context in 248 | which You Share the Licensed Material. For example, it may be 249 | reasonable to satisfy the conditions by providing a URI or 250 | hyperlink to a resource that includes the required 251 | information. 252 | 253 | 3. If requested by the Licensor, You must remove any of the 254 | information required by Section 3(a)(1)(A) to the extent 255 | reasonably practicable. 256 | 257 | 4. If You Share Adapted Material You produce, the Adapter's 258 | License You apply must not prevent recipients of the Adapted 259 | Material from complying with this Public License. 260 | 261 | 262 | Section 4 -- Sui Generis Database Rights. 263 | 264 | Where the Licensed Rights include Sui Generis Database Rights that 265 | apply to Your use of the Licensed Material: 266 | 267 | a. for the avoidance of doubt, Section 2(a)(1) grants You the right 268 | to extract, reuse, reproduce, and Share all or a substantial 269 | portion of the contents of the database; 270 | 271 | b. if You include all or a substantial portion of the database 272 | contents in a database in which You have Sui Generis Database 273 | Rights, then the database in which You have Sui Generis Database 274 | Rights (but not its individual contents) is Adapted Material; and 275 | 276 | c. You must comply with the conditions in Section 3(a) if You Share 277 | all or a substantial portion of the contents of the database. 278 | 279 | For the avoidance of doubt, this Section 4 supplements and does not 280 | replace Your obligations under this Public License where the Licensed 281 | Rights include other Copyright and Similar Rights. 282 | 283 | 284 | Section 5 -- Disclaimer of Warranties and Limitation of Liability. 285 | 286 | a. UNLESS OTHERWISE SEPARATELY UNDERTAKEN BY THE LICENSOR, TO THE 287 | EXTENT POSSIBLE, THE LICENSOR OFFERS THE LICENSED MATERIAL AS-IS 288 | AND AS-AVAILABLE, AND MAKES NO REPRESENTATIONS OR WARRANTIES OF 289 | ANY KIND CONCERNING THE LICENSED MATERIAL, WHETHER EXPRESS, 290 | IMPLIED, STATUTORY, OR OTHER. THIS INCLUDES, WITHOUT LIMITATION, 291 | WARRANTIES OF TITLE, MERCHANTABILITY, FITNESS FOR A PARTICULAR 292 | PURPOSE, NON-INFRINGEMENT, ABSENCE OF LATENT OR OTHER DEFECTS, 293 | ACCURACY, OR THE PRESENCE OR ABSENCE OF ERRORS, WHETHER OR NOT 294 | KNOWN OR DISCOVERABLE. WHERE DISCLAIMERS OF WARRANTIES ARE NOT 295 | ALLOWED IN FULL OR IN PART, THIS DISCLAIMER MAY NOT APPLY TO YOU. 296 | 297 | b. TO THE EXTENT POSSIBLE, IN NO EVENT WILL THE LICENSOR BE LIABLE 298 | TO YOU ON ANY LEGAL THEORY (INCLUDING, WITHOUT LIMITATION, 299 | NEGLIGENCE) OR OTHERWISE FOR ANY DIRECT, SPECIAL, INDIRECT, 300 | INCIDENTAL, CONSEQUENTIAL, PUNITIVE, EXEMPLARY, OR OTHER LOSSES, 301 | COSTS, EXPENSES, OR DAMAGES ARISING OUT OF THIS PUBLIC LICENSE OR 302 | USE OF THE LICENSED MATERIAL, EVEN IF THE LICENSOR HAS BEEN 303 | ADVISED OF THE POSSIBILITY OF SUCH LOSSES, COSTS, EXPENSES, OR 304 | DAMAGES. WHERE A LIMITATION OF LIABILITY IS NOT ALLOWED IN FULL OR 305 | IN PART, THIS LIMITATION MAY NOT APPLY TO YOU. 306 | 307 | c. The disclaimer of warranties and limitation of liability provided 308 | above shall be interpreted in a manner that, to the extent 309 | possible, most closely approximates an absolute disclaimer and 310 | waiver of all liability. 311 | 312 | 313 | Section 6 -- Term and Termination. 314 | 315 | a. This Public License applies for the term of the Copyright and 316 | Similar Rights licensed here. However, if You fail to comply with 317 | this Public License, then Your rights under this Public License 318 | terminate automatically. 319 | 320 | b. Where Your right to use the Licensed Material has terminated under 321 | Section 6(a), it reinstates: 322 | 323 | 1. automatically as of the date the violation is cured, provided 324 | it is cured within 30 days of Your discovery of the 325 | violation; or 326 | 327 | 2. upon express reinstatement by the Licensor. 328 | 329 | For the avoidance of doubt, this Section 6(b) does not affect any 330 | right the Licensor may have to seek remedies for Your violations 331 | of this Public License. 332 | 333 | c. For the avoidance of doubt, the Licensor may also offer the 334 | Licensed Material under separate terms or conditions or stop 335 | distributing the Licensed Material at any time; however, doing so 336 | will not terminate this Public License. 337 | 338 | d. Sections 1, 5, 6, 7, and 8 survive termination of this Public 339 | License. 340 | 341 | 342 | Section 7 -- Other Terms and Conditions. 343 | 344 | a. The Licensor shall not be bound by any additional or different 345 | terms or conditions communicated by You unless expressly agreed. 346 | 347 | b. Any arrangements, understandings, or agreements regarding the 348 | Licensed Material not stated herein are separate from and 349 | independent of the terms and conditions of this Public License. 350 | 351 | 352 | Section 8 -- Interpretation. 353 | 354 | a. For the avoidance of doubt, this Public License does not, and 355 | shall not be interpreted to, reduce, limit, restrict, or impose 356 | conditions on any use of the Licensed Material that could lawfully 357 | be made without permission under this Public License. 358 | 359 | b. To the extent possible, if any provision of this Public License is 360 | deemed unenforceable, it shall be automatically reformed to the 361 | minimum extent necessary to make it enforceable. If the provision 362 | cannot be reformed, it shall be severed from this Public License 363 | without affecting the enforceability of the remaining terms and 364 | conditions. 365 | 366 | c. No term or condition of this Public License will be waived and no 367 | failure to comply consented to unless expressly agreed to by the 368 | Licensor. 369 | 370 | d. Nothing in this Public License constitutes or may be interpreted 371 | as a limitation upon, or waiver of, any privileges and immunities 372 | that apply to the Licensor or You, including from the legal 373 | processes of any jurisdiction or authority. 374 | 375 | 376 | ======================================================================= 377 | 378 | Creative Commons is not a party to its public 379 | licenses. Notwithstanding, Creative Commons may elect to apply one of 380 | its public licenses to material it publishes and in those instances 381 | will be considered the “Licensor.” The text of the Creative Commons 382 | public licenses is dedicated to the public domain under the CC0 Public 383 | Domain Dedication. Except for the limited purpose of indicating that 384 | material is shared under a Creative Commons public license or as 385 | otherwise permitted by the Creative Commons policies published at 386 | creativecommons.org/policies, Creative Commons does not authorize the 387 | use of the trademark "Creative Commons" or any other trademark or logo 388 | of Creative Commons without its prior written consent including, 389 | without limitation, in connection with any unauthorized modifications 390 | to any of its public licenses or any other arrangements, 391 | understandings, or agreements concerning use of licensed material. For 392 | the avoidance of doubt, this paragraph does not form part of the 393 | public licenses. 394 | 395 | Creative Commons may be contacted at creativecommons.org. 396 | 397 | -------------------------------------------------------------------------------- /SMACC2/README.md: -------------------------------------------------------------------------------- 1 | ## Introduction 2 | 3 | This is a mostly chronological writing of my learing process of [SMACC2](https://github.com/robosoft-ai/SMACC2). It is only slightly redacted and hence by no means an ideal guideline to learning SMACC2, and it is **unfinished**, as time constraints forced me to stop and focus on other priorities. Yet I decided to release this file, as I think it can be valuable to anyone new to SMACC2 / Boost Statechart, and hopefully significantly accelerate their (initial) learning process. The text is structured in sections that describe a part of the code, each followed by 'Intermediate conclusions' that give a concise resume of that part of the code. 4 | 5 | Feel free to correct me on topics that I might have misunderstood, or to elaborate on topics that might benefit from further clarification. 6 |
7 |
8 | 9 | 10 | ## Boost Statechart 11 | 12 | In order to understand SMACC2, you need to have a thorough understanding of the Boost Statechart library. 13 | 14 | At the bare minimum, read through [these tutorials](https://www.boost.org/doc/libs/1_81_0/libs/statechart/doc/tutorial.html).
15 | [This eBook](https://github.com/CodeSports/State-Machine-Using-Boost-Statechart) is also a good resource. 16 |
17 |
18 | The source code for the Boost Statechart tutorial examples can be found by [downloading Boost](https://www.boost.org/users/download/) or on [github](https://github.com/boostorg/statechart/tree/master/example). 19 | 20 | 21 |
22 | 23 | ### Some concepts worth repeating for reference: 24 | 25 | But seriously: **[read those tutorials first!](https://www.boost.org/doc/libs/1_81_0/libs/statechart/doc/tutorial.html)** 26 |
27 |
28 | - Boost Statechart extensively uses **`structs`**. There is no functional difference between a `struct` and a `class`. Structs can also have constructors, destructors, public and private member variables or functions, etc. And structs can also inherit from other classes or structs. The only functional difference between a struct and a class is the following: if no access specifiers (public/private/protected) are specified, classes will default to `private`, whereas structs will default to `public`. For instance: 29 | 30 | ```c++ 31 | struct MyStruct : BaseClass { ... }; // identical to "struct MyStruct : public BaseClass { ... };" 32 | class MyClass : BaseClass { ... }; // identical to "class MyClass : private BaseClass { ... };" 33 | ``` 34 | 35 |
36 | - Boost Statechart extensively uses the **curiously recurring template pattern** (CRTP), which means that a derived class/struct inherits from a templated class/struct that has the derived class/struct as its first template parameter. E.g.: 37 | 38 | ```c++ 39 | struct Mystruct : TemplateBaseClass< MyStruct > 40 | ``` 41 | This is curious indeed! ;-)/br> 42 | Wrt. the use of SMACC2 / Boost Statechart, there is no need to further study this design pattern; just accept it for what it is and get used to the notation. 43 | 44 |
45 | - Typically, the **namespace** `sc` is defined for easier readability: 46 | 47 | ```c++ 48 | namespace sc = boost::statechart; 49 | ``` 50 | 51 |
52 | - A Boost Statechart **state machine** inherits from `sc::state_machine` (synchronous state machine), or from `sc::asynchronous_state_machine` e.g.: 53 | 54 | ```c++ 55 | struct ActiveState; 56 | struct SyncStateMachine : sc::state_machine 57 | struct AsyncStateMachine : sc::asynchronous_state_machine 58 | ``` 59 | 60 | In this, `ActiveState` is forward declared, as it is needed in the declaration of the state machines.
61 | Re. the state machine declarations: according to the CRTP, the first template parameter in the state machine declaration is the derived type. The second template parameter is the (type of) state which will be activated upon entering the state machine.
62 | 63 | 64 | — A Smacc2 state machine inherits from `SmaccStateMachineBase`, which is derived from `sc::asynchronous_state_machine`. 65 |
66 |
67 | 68 | - A Boost Statechart **state** inherits from `sc::simple_state` (or `sc::state`), e.g.: 69 | ```c++ 70 | struct ActiveState : sc::simple_state // ActiveState is a toplevel state in StateMachine 71 | struct InternalState : sc::simple_state // InternalState is a substate of ActiveState 72 | struct InternalState2 : sc::simple_state // InternalState2 is another substate of ActiveState 73 | ``` 74 | — A SMACC2 state inherits from `SmaccState`, which is derived from `sc::simple_state`. 75 |
76 |
77 | 78 | 79 | - State transitions are triggered by **events**: `struct MyEvent : sc::event {};`
80 | Events can be deferred or forwarded, see [chapter 5](https://github.com/CodeSports/State-Machine-Using-Boost-Statechart/tree/master/Chapter-5) and [chapter 6](https://github.com/CodeSports/State-Machine-Using-Boost-Statechart/tree/master/Chapter-6) of the eBook.
81 | 82 | Event reactions (to specify in the `reactions` typedef of a state):
83 | ```c++ 84 | sc::transition< event, target_state > // without transition action 85 | sc::transition< event, target_state, common_context , transition_action > // with transition action 86 | sc::custom_reaction< event > // with react function sc::result react( const event & ); 87 | sc::deferral< event > // deferred events are stored in a separate queue, which is emptied into the main queue when this state is exited. 88 | ``` 89 | 90 | 91 | Custom event reaction, to use in the `react()` function for a `custom_reaction`:
92 | ```c++ 93 | return transit< state >(); // without transition action 94 | return transit< state >( transition_action, event ); // with transition action 95 | return terminate(); 96 | return forward_event(); // forward event to the outer state 97 | return discard_event(); 98 | ``` 99 | See [this tutorial paragraph](https://www.boost.org/doc/libs/1_81_0/libs/statechart/doc/tutorial.html#TransitionActions) for more info on transition actions. 100 | 101 |
102 | - Note that the [Boost Statechart tutorials](https://www.boost.org/doc/libs/1_81_0/libs/statechart/doc/tutorial.html) discuss the use of multiple inheritance as a design pattern to retrieve information from the states: 103 | 104 | ```c++ 105 | struct Running : IElapsedTime, sc::simple_state< Running, Active > 106 | ``` 107 | 108 | The state `Running` is derived from `sc::simple_state` and from the interface class `IElapsedTime`. This interface class defines common methods to be implemented by each state.
109 |
110 | Similarly (though not necessarily exactly for the same reason): 111 | - A `smacc2::SmaccState` inherits from `sc::simple_state` and from `smacc2::ISmaccState`.
112 | - A `smacc2::SmaccStateMachineBase` inherits from `sc::asynchronous_state_machine` and from `smacc2::ISmaccStateMachine`. 113 |
114 |
115 | 116 | - In Boost Statechart, **orthogonal states** are states that have multiple active substates at once.
117 | In SMACC2 the word `orthogonal` is also used, but it has a very different meaning. See further down for more info on SMACC2 orthogonals. 118 | 119 |
120 |
121 | 122 | 123 | ## Asynchronous state machines 124 | 125 | Given that the SMACC2 `SmaccStateMachineBase` is an `sc::asynchronous_state_machine`, and given that asynchronous state machines are not necessarily straighforward to understand upon a first read of the Boost Statechart [tutorials](https://www.boost.org/doc/libs/1_81_0/libs/statechart/doc/tutorial.html), this paragraph elaborates on this topic. 126 |
127 |
128 | 129 | ### What is the issue? 130 | 131 | A **non-asynchronous** state machine (`sc::state_machine`) is instantiated, initiated, and then processes events, e.g.: 132 | 133 | ```c++ 134 | int main() 135 | { 136 | StopWatch myWatch; 137 | myWatch.initiate(); 138 | myWatch.process_event( EvStartStop() ); 139 | myWatch.process_event( EvStartStop() ); 140 | myWatch.process_event( EvReset() ); 141 | return 0; 142 | } 143 | ``` 144 | 145 | Each `process_event()` call takes a certain amount of time. This could be very little (e.g. processing an event that is simply discarded), but could also be significant (e.g. a multitude of state instances that need to be destructed/constructed upon a state change). 146 | 147 | In above example, each `process_event()` is called consecutively, so it is impossible that a `process_event()` call is made while a previous one is still running. 148 | 149 | In a multithreaded program however, with multiple sources of events, it could be possible that one thread's `process_event()` is preempted by another thread that also calls `process_event()`. This would obviously lead to erratic behavior.
150 | (Note that this is in fact irrespective of whether `process_events()` takes a long time or not, though obviously more likely in the former case.)
151 | In other words: unless you'd implement your own solution, synchronous Boost Statechart state machines are not thread safe: it is not allowed to call `process_events()` from multiple threads. 152 | 153 |
154 | 155 | As a side note: the Boost Statechart [tutorials](https://www.boost.org/doc/libs/1_81_0/libs/statechart/doc/tutorial.html) show a similar issue for the singlethreaded case, but this is not of particular relevance for now. 156 | 157 |
158 | 159 | ### So... asynchronous state machines? 160 | 161 | The solution to above issue is to use an asynchronous state machine. The processing of an asynchronous state machine is split into: 162 | - A `scheduler`, which receives events and stores them into a queue, and 163 | - A `processor`, which sequentially gets an event from the scheduler and processes it in the state machine. 164 | 165 | Boost Statechart provides one type of scheduler: the `sc::fifo_scheduler`, which feeds the events to the processor in a 'First In First Out' fashion.
166 | Other types of schedulers are possible (e.g. priority- or deadline-based schedulers) but as of yet are not part of Boost Statechart. 167 | 168 | The syntax is as follows: 169 | 170 | ```c++ 171 | int main() 172 | { 173 | // Create a scheduler 174 | sc::fifo_scheduler<> my_scheduler( bool waitOnEmptyQueue ); 175 | 176 | // Create a processor from the scheduler 177 | // This call instantiates the state machine 178 | auto my_processor_handle = my_scheduler.create_processor< state_machine_type >(); 179 | 180 | // Initiate the processor 181 | my_scheduler.initiate_processor( my_processor_handle ); 182 | 183 | // Optional: queue events 184 | //my_scheduler.queue_event( my_processor_handle, my_event1 ); 185 | //my_scheduler.queue_event( my_processor_handle, my_event2 ); 186 | 187 | // Run the scheduler by calling sc::fifo_scheduler::operator() 188 | my_scheduler(); 189 | } 190 | ``` 191 | Re. the `sc::fifo_scheduler` constructor: 192 | - If `waitOnEmptyQueue` is `false`, then `sc::fifo_scheduler::operator()` returns when the queue is empty. 193 | - If `waitOnEmptyQueue` is `true`, then `sc::fifo_scheduler::operator()` does not return on an empty queue, but waits for future events to be added (by calling `queue_event()` on the scheduler, e.g. from another thread or from the state machine itself), 194 | - In this case, a call of `fifo_scheduler<>::terminate()` is needed to interrupt the waiting and return from `sc::fifo_scheduler::operator()`. 195 | 196 |
197 | 198 | For more examples of the use of asynchronous state machines, e.g. multiple processors from one scheduler, see the [Boost Statechart tutorials](https://www.boost.org/doc/libs/1_81_0/libs/statechart/doc/tutorial.html). 199 | 200 |
201 |
202 | 203 | Let's now look at the SMACC2 `sm_atomic` example. 204 | 205 | 206 | ## The sm_atomic example 207 | 208 | ### Program startup 209 | 210 | The state machine program starts with a call to `smacc2::run()`, see [sm_atomic_node.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/sm__atomic__node_8cpp.html): 211 | 212 | ```c++ 213 | int main(int argc, char ** argv) 214 | { 215 | rclcpp::init(argc, argv); 216 | smacc2::run(); 217 | } 218 | ``` 219 | 220 | `SmAtomic` is the state machine class. 221 | 222 | `smacc2::run()` is defined in [smacc_signal_detector.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__signal__detector_8hpp_source.html), see description below the code: 223 | 224 | ```c++ 225 | template 226 | void run() 227 | { 228 | // create the asynchronous state machine scheduler 229 | SmaccFifoScheduler scheduler1(true); 230 | 231 | // create the signalDetector component 232 | SignalDetector signalDetector(&scheduler1); 233 | 234 | // create the asynchronous state machine processor 235 | SmaccFifoScheduler::processor_handle sm = 236 | scheduler1.create_processor(&signalDetector); 237 | 238 | // initialize the asynchronous state machine processor 239 | signalDetector.setProcessorHandle(sm); 240 | 241 | scheduler1.initiate_processor(sm); 242 | 243 | //create a thread for the asynchronous state machine processor execution 244 | boost::thread otherThread(boost::bind(&sc::fifo_scheduler<>::operator(), &scheduler1, 0)); 245 | 246 | // use the main thread for the signal detector component (waiting actionclient requests) 247 | signalDetector.pollingLoop(); 248 | } 249 | ``` 250 | Let's have a look: 251 | 252 | - First, a `SmaccFifoScheduler` is created. 253 | - A `SmaccFifoScheduler` is a typedef for an `sc::fifo_scheduler`. (see [smacc_fifo_scheduler.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__fifo__scheduler_8hpp_source.html))
254 | - A `SmaccFifoWorker` is similarly an `sc::fifo_worker` and a `SmaccAllocator` an `std::allocator` (see [smacc_fifo_worker.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__fifo__worker_8hpp_source.html)). 255 | 256 | So this is more or less standard Boost Statechart, given `SmAtomic` is an `sc::asynchronous_state_machine`. 257 | 258 | - Then a `SignalDetector` is created. This is a SMACC2 class.
259 | We will check out its functionality later on, but for now notice that a few lines below a call is made to `signalDetector.pollingLoop()` and that the comments state that this loop waits for actionclient requests. 260 | 261 | - The rest of the code is also standard for Boost Statechart asynchronous state machines: 262 | - Recall that the instantiation of the state machine class (i.e. SmAtomic) is done by the `fifo_scheduler<>::create_processor<>( args )` call and that the `args` are passed to the state machine constructor, 263 | - The `FifoScheduler` runs in a separate thread (`sc::fifo_scheduler<>::operator()`). 264 | 265 |
266 | 267 | ### smacc2::SignalDetector 268 | 269 | So let's further look at the SignalDetector code ([smacc_signal_detector.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__signal__detector_8hpp_source.html) and [signal_detector.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/signal__detector_8cpp_source.html)). 270 | 271 | In above run() function, calls were made to the SignalDetector constructor, `setProcessorHandle` and `pollingLoop` methods.
272 | - The constructor only sets some member variables, among others `initialized_ = false`.
273 | - `SignalDetector::setProcessorHandle` also just sets a member variable pointing to the handle.
274 | - `SignalDetector::pollingLoop` polls `initialized_` until it becomes true. 275 | 276 | So the initialization is probably initiated from the state machine code, since the signalDetector was passed as an argument to `create_processor<>()` (and hence the state machine constructor). 277 | 278 | Indeed, in the `ISmaccStateMachine` constructor ([smacc_state_machine.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__state__machine_8cpp_source.html)): 279 | - A ROS2 Node is instantiated (automatically named corresponding to the state machine), 280 | - `SignalDetector::initialize()` is called, 281 | - `run_mode` parameter of the node is read and runMode set accordingly (`DEBUG` or `RELEASE`). 282 | 283 | `SignalDetector::initialize()`: 284 | - Calls `findUpdatableClientsAndComponents()` (more on this below, not relevant for now) 285 | - Declares a ROS2 parameter `signal_detector_loop_freq`, and sets its loop frequency accordingly (standard: 20Hz), 286 | - Sets `initialized_` to true. 287 | 288 | 289 |
290 | 291 | Given that `initialized_` is true, `SignalDetector::pollingLoop` continues.
292 | We see that it polls *something* and spins the node: 293 | ```c++ 294 | while (rclcpp::ok() && !end_) 295 | { 296 | pollOnce(); 297 | rclcpp::spin_some(nh); 298 | r.sleep(); 299 | } 300 | ``` 301 |
302 | 303 | > 304 | >
305 | > 306 | > ### Intermediate conclusions #1 307 | > 308 | > - A `FifoScheduler` and `Processor` are created to run an asynchronous state machine. 309 | > - The state machine is created by `create_processor<>()`. The state machine constructor mainly 310 | > - Creates a **ROS2 node**, and 311 | > - Initializes the **SignalDetector**, 312 | > - The `FifoScheduler` runs in a **separate thread**, 313 | > - The `SignalDetector` polls *something* and spins the state machine node: 314 | > - At a configurable rate (default 20Hz), 315 | > - In the context of the **main thread**.
316 | >
317 | > 318 | 319 |
320 | 321 |
322 | 323 | ### The SignalDetector poll routine 324 | 325 | `SignalDetector::pollOnce()` is implemented in [signal_detector.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/signal__detector_8cpp_source.html). 326 | 327 |
328 | It does the following (see below for further clarification): 329 | 330 |
331 | 332 | - Lock the state machine mutex,
333 | - Save the "current state counter" and "current state" of the state machine, 334 | - Call `findUpdatableClientsAndComponents()`. This rebuilds a `std::vector` **`updatableClients_`**, 335 | - Call `executeUpdate(state_machine_node)` on each of the `ISmaccUpdatable`'s in `updatableClients_`, 336 | - Then, IF the state machine is NOT `TRANSITIONING`, `CONFIGURING`, `ENTERING` or `EXITING`: 337 | - If the state has changed (current state counter != lastState_): 338 | - Call `findUpdatableStateElements(currentstate)`. This rebuilds a `std::vector` **`updatableStateElements_`** 339 | - Call `executeUpdate(state_machine_node)` on each of the `ISmaccUpdatable`'s in `updatableStateElements_`, 340 | - Call `rclcpp::spin_some(nh)`.
341 | 342 |
343 | 344 | [ QUESTION:  *The mutex is not related to Boost Statechart, so what is holding the FifoScheduler (in the other thread) from processing a state change event while `pollOnce` is executed (by the main thread)?* ]
345 | --> ANSWER: It seems that this mutex is also locked in `SmaccState::exit()` which blocks the transition. However: by then `specificNamedOnExit` and `notifyTransition` have been called? 346 | 347 | [ QUESTION:  _Why is `spin_some` called twice: both here in `pollOnce()` as well as in `pollingLoop()`?_ ] 348 | 349 | 350 |
351 |
352 | 353 | > 354 | >
355 | > 356 | >### Intermezzo 357 | > 358 | > The next paragraph introduces orthogonals, clients, client behafiors, etc. 359 | > 360 | > From the current (27 jan 2023) [SMACC2 documentation](https://smacc.dev/intro-to-substate-objects/) we gather: 361 | > - Orthogonals are classes: 362 | > - Instantiated in the state machine, 363 | > - Persistent through the lifetime of the **state machine**, 364 | > - That serve as a container for clients, client behaviors, orthogonal components, 365 | > - Clients: 366 | > - Are also persistent for the life of the **state machine**, 367 | > - Are typically used to do things, like manage connections to outside nodes and devices, 368 | > - Contain code that we would want executed regardless of the current state, 369 | > - Are an important source of events. 370 | > - Client behaviors: 371 | > - Are persistent for the life of the **state**, 372 | > - Are used to execute state specific behaviors. 373 | > - "In a given state, there can be multiple client behaviors in any orthogonal."
374 | > 375 | > This is a rather concise explanation, but for now just accept that these concepts exist and that we will have to fill in the details later. 376 | > 377 | >
378 |
379 |
380 | 381 | ### findUpdatableClientsAndComponents() 382 | 383 | Implemented in [signal_detector.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/signal__detector_8cpp_source.html). It: 384 | 385 | - Clears `std::vector updatableClients_`, 386 | - Iterates over all **orthogonals** (`smacc2::ISmaccOrthogonal`) of the **state machine**, 387 | - Iterates over all **clients** (`smacc2::ISmaccClient`) of each of the **orthogonals**, 388 | - Checks which of these clients and which **components** of these clients (`smacc2::ISmaccComponent`) are derived from **`smacc2::ISmaccUpdatable`** (by using `dynamic_cast<>`), 389 | - If they are an `smacc2::ISmaccUpdatable` (i.e. the `dynamic_cast` is successful), than the resulting pointer is added to `updatableClients_`. 390 | 391 |
392 | 393 | In other words: 394 | - On each signal detector poll loop, `updatableClients_` is rebuilt to hold: 395 | - All clients of each orthogonal of the state machine, and 396 | - All components of those clients,
397 | - If these are `ISmaccUpdatable`. 398 | 399 | [ QUESTION: _Given that orthogonals and clients are persistent throughout the state machine lifetime, why is this vector rebuilt on each poll? Maybe the client's components are not persistent? What are client components anyway?_] 400 | 401 | 402 |
403 | 404 | ### findUpdatableStateElements(currentstate) 405 | 406 | 407 | Implemented in [signal_detector.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/signal__detector_8cpp_source.html). Similar to `findupdatableClientsAndComponents()`, it: 408 | 409 | - Clears `std::vector updatableStateElements_`, 410 | - Iterates over all **orthogonals** (`smacc2::ISmaccOrthogonal`) of the **state machine**, 411 | - Adds all **clients behaviors** (`smacc2::ISmaccClientBehavior`) of each of the **orthogonals** to `updatableStateElements_` if they inherit from `ISmaccUpdatable`, 412 | - Adds the **current state** itself to `updatableStateElements_` if it inherits from `ISmaccUpdatable`, 413 | - Adds all **state reactors** (`smacc2::StateReactor`) of the **state** if they inherit from `ISmaccUpdatable`, 414 | - Adds all **event generators** (`smacc2::SmaccEventGenerator`) of the **state** if they inherit from `ISmaccUpdatable`. 415 | 416 |
417 | 418 | In other words: 419 | - After each state change, `updatableStateElements_` is rebuilt to hold: 420 | - Client behaviors of each orthogonal of the state machine, 421 | - The current state, 422 | - State reactors of the current state, and 423 | - Event generators of the current state, 424 | - if these are `ISmaccUpdatable`. 425 | 426 | Note that, although client behaviors are in the orthogonal (persistent to the state machine lifetime), they are added and removed from the orthogonal on each state change (i.e. client behaviors are persistent to the lifetime of the **state**). 427 | 428 |
429 | 430 | 431 | 432 | ### ISmaccUpdatable 433 | 434 | Let's now look at the `executeUpdate()` calls.
435 | From the implementation in [smacc_updatable.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__updatable_8hpp_source.html) and [smacc_updatable.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__updatable_8cpp_source.html), we learn that:
436 | 437 | - The `ISmaccUpdatable` imposes the implementation of an `update()` method in the derived class, 438 | - An `ISmaccUpdatable` optionally has a period (rclcpp::Duration), 439 | - The `update()` method is called: 440 | - If no duration is set: each time when `execucuteUpdate(node)` is called (by the SignalDetector), 441 | - If a duration is set: when `execucuteUpdate(node)` is called AND the duration has passed since the previous `update()`. 442 | 443 | In other words: an `ISmaccUpdatable` has its `update()` method called periodically, with period equal to, or a multiple of, the SignalDetector polling loop period. 444 | 445 |
446 |
447 | 448 | > 449 | >
450 | > 451 | > ### Intermediate conclusions #2 452 | > 453 | > - The **main thread** runs the SignalDetector **polling loop** and **spins the state machine node**, 454 | > - This at a default frequency of 20Hz or according to a ROS2 parameter, 455 | > - A state machine has **orthogonals**, with lifetime of the **state machine**, 456 | > - An orthogonal has **clients** and clients have **client components**, with lifetime of the **state machine**, 457 | > - An orthogonal has **client behaviors**, according to the **current state**, 458 | > - A state has **state reactors** and **event generators**, 459 | > - Clients, client components, client behaviors, states, state reactors and event generators **can be an `ISmaccUpdatable`**,
460 | > - `ISmaccUpdatables` have their **`update()` method periodically called** by the polling loop (i.e. the main thread), 461 | > - This either at the polling loop frequency or at the set update period of the `ISmaccUpdatable`. 462 | > 463 | >
464 | > 465 | 466 |

467 | 468 | > 469 | >
470 | > 471 | > ### CAVEAT ! 472 | > 473 | > `dynamic_cast<>()` is used to check if the object (client, client behavior, etc) inherits from `ISmaccUpdatable`.
474 | > However, `dynamic_cast<>()` returns `nullptr` in case of **private** inheritance. 475 | > 476 | > E.g. consider following class definitions: 477 | > ```c++ 478 | > class MyClient1 : public smacc2::ISmaccClient, smacc2::ISmaccUpdatable {}; 479 | > class MyClient2 : public smacc2::ISmaccClient, public smacc2::ISmaccUpdatable {}; 480 | > ``` 481 | > 482 | >
483 | > 484 | > - `MyClient1` is **not** recognized as an `ISmaccUpdatable` and its `update()` is **not** called. 485 | > - `MyClient2` works as expected. 486 | > 487 | >
488 | > 489 | 490 | 491 | 492 | 493 |
494 |
495 | 496 | ## The sm_atomic example, revisited 497 | 498 | As it turns out, none of the clients, client behaviors, states, etc in the sm_atomic example are `ISmaccUpdatable`.
499 | So that's a bit of an anticlimax isn´t it? 500 | 501 | 502 | Yet, we are better prepared now to dig through the sm_atomic code: 503 | 504 | ### The state machine 505 | 506 | [sm_atomic.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/sm__atomic_8hpp_source.html) 507 | 508 | Has a method `onInitialize()` that creates an orthogonal (class `OrTimer`). 509 | 510 |
511 | 512 | ### The orthogonal 513 | 514 | [or_timer.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/sm__atomic_2include_2sm__atomic_2orthogonals_2or__timer_8hpp_source.html) 515 | 516 | Has a method `onInitialize()` that creates a client (`ClRosTimer`) in itself (i.e. the orthogonal). 517 | 518 |
519 | 520 | ### The states 521 | 522 | [st_state_1.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc2__sm__reference__library_2sm__atomic_2include_2sm__atomic_2states_2st__state__1_8hpp_source.html) has methods: 523 | - `staticConfigure()` 524 | - `runtimeConfigure()` 525 | - `onEntry()` 526 | - `onExit()` 527 | 528 | `staticConfigure()` configures two client behaviors (`CbTimerCountdownLoop` and `CbTimerCountdownOnce`) in the orthogonal. 529 | 530 |
531 | 532 | The event reaction is defined similar to Boost Statechart reactions, but with a somewhat different syntax: 533 | 534 | ```c++ 535 | // Boost Statechart 536 | transition< eventtype, targetstate > 537 | 538 | // SMACC2 539 | Transition< // Note the capital 'T' 540 | EvTimer, // Event type 541 | State2, // Target state 542 | SUCCESS // Tag (see below) 543 | > 544 | ``` 545 | Note that, while Boost Statechart states have an `exit()` member function which is called just before the state object is destructed, they do not have the `onEntry()`, `onExit(),` and `..Configure()` member functions. More on that below. 546 | 547 |
548 | 549 | [st_state_2.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc2__sm__reference__library_2sm__atomic_2include_2sm__atomic_2states_2st__state__2_8hpp_source.html) 550 | 551 | Identical to `st_state_1`, except that `staticConfigure()` configures only one client behavior in the orthogonal. 552 | 553 |
554 | 555 | ### Transitions 556 | 557 | Let's dig into the transitions first. 558 | 559 | We find the implementation in [smacc_transition.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__transition_8hpp_source.html). 560 | 561 | ```c++ 562 | template < 563 | class Event, class Destination, typename Tag, 564 | class TransitionContext, void (TransitionContext::*pTransitionAction)(const Event &)> 565 | class Transition 566 | { 567 | ... 568 | }; 569 | ``` 570 | 571 | Now, this is rather strange at first, as there's five template parameters, whereas the example above took only three.
572 | The trick is that there's a forward declaration of `Transition` hidden at the bottom of [smacc_types.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__types_8hpp_source.html) which has the default values: 573 | 574 | ```c++ 575 | template < 576 | class Event, class Destination, typename Tag = default_transition_tags::default_transition_name, 577 | class TransitionContext = boost::statechart::detail::no_context, 578 | void (TransitionContext::*pTransitionAction)(const Event &) = &boost::statechart::detail::no_context::no_function> 579 | class Transition; 580 | ``` 581 | 582 | The transition tags are also defined in that file: 583 | 584 | ```c++ 585 | // you can also use these other labels in order to have 586 | // a better code readability and also to improve the visual representation 587 | // in the viewer 588 | struct DEFAULT {}; 589 | struct ABORT {}; 590 | struct SUCCESS {}; 591 | struct CANCEL {}; 592 | // struct PREEMPT {}; 593 | // struct REJECT {}; 594 | struct CONTINUELOOP {}; 595 | struct ENDLOOP {}; 596 | struct default_transition_name : SUCCESS {}; 597 | ``` 598 | 599 | Comparing [smacc_transition.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__transition_8hpp_source.html) to the original Boost Statechart one (`/usr/include/boost/statechart/transition.hpp`), we see that both implement the `react_without_action()` and `react_with_action()` member functions, but the SMACC2 version has some extra functionality: 600 | 601 | - It adds some log info (RCLCPP_DEBUG), 602 | - It calls `specificNamedOnExit(state, tag_type)`, 603 | - It calls `notifyTransition()` on the state 604 | 605 |
606 | 607 | The implementation of `specificNamedOnExit(state,tag_type)` is found in [state_traits.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/state__traits_8hpp_source.html).
608 | It's rather tough code to read, so I did not fully validate this, but I'm pretty sure it does the following: 609 | - Check if the state that is being exited has a specific `onExit(tag_type)` defined for the tag type that was specified in the Transition, 610 | - And, if so: call that specific `onExit(tag_type)` on the exiting state. 611 | 612 |
613 | 614 | 615 | Now we're at it, that same file also implements `standardOnExit(state)`. Similarly, this one seems to check if the state implements `onExit()` and calls it accordingly. `standardOnExit(state)` --and hence the state's `onExit()`-- is called from the standard Boost Statechart `exit()` call of the state (implementation in [`Smacc2::SmaccState::exit()`](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__state__base_8hpp_source.html) ) 616 | 617 |
618 |
619 | 620 | The implementation of `notifyTransision()` is in [smacc_state_impl.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__state__impl_8hpp_source.html).
621 | It forwards the notification to `ISmaccState::notifyTransitionFromTransitionTypeInfo(TypeInfo::Ptr & transitionType)`. Reading through this it seems that: 622 | - A `smacc2::ISmaccState` has a `smacc2::introspection::SmaccStateInfo`, 623 | - A `SmaccStateInfo` has an `std::vector< SmaccTransitionInfo > transitions_`, 624 | - The current transition's type (`TypeInfo`) is compared to all `SmaccTransitionInfo` structs in `transitions_`, 625 | - If it is found, it is published on `/smacc/transition_log` as a `smacc2_msgs::msg::SmaccTransitionLogEntry`, 626 | - If not, debug info is logged as RCLCPP_ERROR_STREAM. 627 | 628 | 629 | [ QUESTION:  *in `ISmaccStateMachine::publishTransition()`:   `this->transitionLogHistory_.push_back(transitionLogEntry);` ---> This an evergrowing vector? There's no clear anywhere?*] 630 | 631 |
632 | 633 | > 634 | >
635 | > 636 | > ### Intermediate conclusions #3 637 | > 638 | > - SMACC2 Transitions (with captial 'T') optionally take an extra 'TAG' template parameter, 639 | > - States can implement specific `onExit(tag_type specific_tag)` member functions, 640 | > - These are called in case of a Transition that has that specific tag type, 641 | > - States can also have a generic `onExit()` without tag type, 642 | > - This is called from the `exit()` function of the state (as it is an `sc::simple_state`), 643 | > - Hence the specific `onExit(tag_type)` is called before the generic `onExit()` if both are present. 644 | > - Transitions are published on `/smacc/transition_log` and a history of all these transition messages is kept in an (evergrowing?) vector. 645 | > 646 | > 647 | >
648 | > 649 | > [ QUESTION: *Does this imply that it is not intended to use `sc::custom_reaction< event >` and corresponding `sc::result react( const event & )` functions?* ] 650 | > 651 | >
652 | > 653 | 654 | 655 |
656 |
657 | 658 | 659 | ### The Client 660 | 661 | [cl_ros_timer.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/include_2ros__timer__client_2cl__ros__timer_8hpp_source.html) and [timer_client.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/timer__client_8cpp_source.html) 662 | 663 | In the header file, the event is also declared: 664 | 665 | ```c++ 666 | template 667 | struct EvTimer : sc::event> {}; 668 | ``` 669 | 670 | [ QUESTION  *Not clear why EvTimer is a template class, afaik it could also be the following (less confusing for first time users):  671 | `struct EvTimer : sc::event {}; `*]
672 | [ POSSIBLE ANSWER: *I think the template definition is used to define source- and orthogonal-specific events. I.e. one type of client can be added to multiple orthogonals and send client- and orthogonal-specific events (as long as the orthogonals are of a different type).*] 673 | 674 |
675 | 676 | The timer client seems to: 677 | - Create a ROS2 timer in its `onInitialize()`, 678 | - Its timer callback runs either one time (`bool oneshot = true`) or periodically (`oneshot = false`, default), 679 | - The timer callback calls: 680 | - If it has been set: `this->onTimerTick_()` 681 | - `onTimerTick_` is set by a call to `ClRosTimer::onTimerTick(void (T::*callback)(), T * object)`), 682 | - and `postTimerEvent_()` 683 | - `postTimerEvent_` is set in `ClRosTimer::onOrthogonalAllocation()` 684 | - It resolves to `this->postEvent()`
685 | [QUESTION: ~~is this general or client-specific?~~ It seems to be client-specific, e.g. it could as well call `postEvent(event)` instead, if an instantiated event object should be passed on] 686 | 687 |
688 | 689 | Note that for the sm_atomic example, the timer client created by the orthogonal uses default parameter `oneshot = false`, i.e. it is a periodic timer client:
690 | [or_timer.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/sm__atomic_2include_2sm__atomic_2orthogonals_2or__timer_8hpp_source.html) 691 | ```c++ 692 | void onInitialize() override { auto client = this->createClient(1s); } 693 | ``` 694 | 695 |
696 |
697 | 698 | The call to `this->postEvent()` needs further study:
699 | It is the base class method `ISmaccState::postEvent()`, which resolves to `statemachine->postEvent()`, implemented in [smacc_state_machine_impl.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__state__machine__impl_8hpp_source.html). 700 | 701 | These state machine `postEvent()` methods take an `EventLifeTime` which defaults to `ABSOLUTE` : 702 | ```c++ 703 | template 704 | void postEvent(EventType * ev, EventLifeTime evlifetime = EventLifeTime::ABSOLUTE); 705 | 706 | template 707 | void postEvent(EventLifeTime evlifetime = EventLifeTime::ABSOLUTE); 708 | ``` 709 | 710 |
711 | 712 | `ISmaccStateMachine::postEvent()` instantiates a new event object, of type `EventType`, and then calls `ISmaccStateMachine::postEvent(event)`.
713 | 714 |    [ QUESTION:  ~~Ugly raw pointer. What is the lifetime of an event? Who deletes it?~~ See below: `SignalDetector::postEvent(EventType* ev)` ]

715 | 716 | `ISmaccStateMachine::postEvent( event, eventLifeTime)`: 717 | - Discards the event if its EventLifeTime is `CURRENT_STATE` and the current state is `EXITING` or `TRANSITIONING`, or else 718 | - Propagates the event to the state reactors: 719 | - This calls `notifyEvent(event)` on each state reactor of the **state**, and recursively of all **parent states**, 720 | - And finally calls `postEvent(event)` on the SignalDetector. 721 | 722 |
723 | 724 | `SignalDetector::postEvent(EventType* ev)`: 725 | - Converts the raw event pointer to an intrusive_ptr: 726 | - `boost::intrusive_ptr weakPtrEvent = ev;`
727 | - If I understand it correctly, this transfers ownership of the raw pointer to the intrusive_ptr, which will delete the pointer when the intrusive_ptr goes out of scope.
728 | -  [QUESTION: Is this correct?]
729 | - This means that weakPtrEvent is somewhat of an ill-chosen name and should rather be sharedPtrEvent or intrusivePtrEvent.
730 | - And then dispatches the event to the state machine **FifoScheduler queue**. 731 | 732 | 733 |

734 | 735 | ### The Client Behaviors 736 | 737 | 738 | [`sm_atomic::State1`](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc2__sm__reference__library_2sm__atomic_2include_2sm__atomic_2states_2st__state__1_8hpp_source.html) 739 | and 740 | [`sm_atomic::State2`](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc2__sm__reference__library_2sm__atomic_2include_2sm__atomic_2states_2st__state__2_8hpp_source.html) 741 | configure client behaviors into the orthogonal in their `staticConfigure()` methods: 742 | 743 | ```c++ 744 | static void sm_atomic::State1::staticConfigure() 745 | { 746 | configure_orthogonal(3); // EvTimer triggers each 3 client ticks 747 | configure_orthogonal(5); // EvTimer triggers once at 10 client ticks //5? 748 | } 749 | 750 | static void sm_atomic::State2::staticConfigure() 751 | { 752 | configure_orthogonal(5); // EvTimer triggers once at 10 client ticks //5? 753 | } 754 | ``` 755 | 756 |
757 | 758 | Let's look at `configure_orthogonal<>(Args)` first, see [smacc_state_base.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__state__base_8hpp_source.html#l00039): 759 | 760 | 761 | `configure_orthogonal()` passes following lambda function to `configure_orthogonal_internal()`:
762 |   `[=](ISmaccState * state) { state->configure(args...); });` 763 | 764 |
765 | 766 | `configure_orthogonal_internal()`: 767 | - Populates a `ClientBehaviorInfoEntry` with: 768 | - Above lambda function pointer (`factoryFunction`), 769 | - The behavior typeid 770 | - The orthogonal typeid 771 | - It adds a new entry to ab std::map of pairs ( `state`, `std::vector` ) if no entry exists yet for this state, and 772 | - It adds the `ClientBehaviorInfoEntry` to the std::vector of the state. 773 | 774 | [ _The factoryFunction is called by `entryStateInternal()`_ ] 775 | 776 |
777 | 778 | Even though it is not being called yet, let's have a look at `state->configure(args...);` 779 | 780 | [smacc_state_impl.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__state__impl_8hpp_source.html) 781 | 782 | - It get's the orthogonal from the state machine, 783 | - It creates a shared_ptr to a new client behavior, 784 | - It adds it to the orthogonal, 785 | - It calls `onOrthogonalAllocation()` on the client behavior object. 786 | 787 | 788 |

789 | 790 | Ok, let's look at the client behavior code now: 791 | 792 | [cb_timer_countdown_loop.hpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/include_2ros__timer__client_2client__behaviors_2cb__timer__countdown__loop_8hpp_source.html) 793 | and 794 | [cb_timer_countdown_loop.cpp](https://robosoft-ai.github.io/smacc2_doxygen/master/html/cb__timer__countdown__loop_8cpp_source.html) 795 | 796 | The assumed chronologic order is as follows: 797 | - At some point, `entryStateInternal()` is called on the state, which executes the `state->configure<>(args...)`, 798 | - This creates the client behavior; its constructor is called, 799 | - (For the `cb_timer_*` client behaviors, the constructor only initializes some member variables) 800 | - Then the client behaviors are added to the orthogonal and their `onOrthogonalAllocation()` is called, 801 | - This defines a function that posts an event, 802 | - At some point, the client behavior's `onEntry()` method is called. This: 803 | - Requests the client, which will 804 | - Return a pointer to the client from this orthogonal, or if not found, 805 | - Return a pointer to that client in another orthogonal, or if not found, 806 | - Return a nullpointer (which will crash if dereferenced), 807 | - Registers a callback function with the client, which is called by the client (through a `boost::signals2::connection`, which is not necessarily relevant, except that this implies that multiple callback functions (of multiple client behaviors) can be registered, which will be called consecutively), 808 | - The callback signal connection is done through the state machine, which ensures that these are disconnected upon state change. It seems that currentlly, states, state reactors and client behaviors can register such signals, see [`createSignalConnection()`](https://robosoft-ai.github.io/smacc2_doxygen/master/html/smacc__state__machine__impl_8hpp_source.html#l00355). 809 | 810 | 811 | 812 |
813 |
814 | 815 |
816 | 817 | ### Intermediate conclusions #4 818 | 819 | Clients can implement following functions, which are chronologically called: 820 | ```c++ 821 | - Constructor 822 | - template void onOrthogonalAllocation() 823 | - void onInitialize() 824 | ``` 825 | 826 | 827 | Clients Behaviors similarly have: 828 | ```c++ 829 | - Constructor 830 | - template void onOrthogonalAllocation() 831 | - void onEntry() 832 | - void onExit() 833 | ``` 834 | 835 | 836 | Other relevant functions of the `ISmaccClient` base class: 837 | ```c++ 838 | - void connectSignal(TSmaccSignal &signal, void(T::*callback)(), T *object) 839 | - void postEvent() 840 | - void postEvent(const EventType &ev) 841 | ``` 842 | 843 | 844 | 845 | -------------------------------------------------------------------------------- /ROS2_core/ROS2_logging.md: -------------------------------------------------------------------------------- 1 | # Study of ROS 2 logging with focus on realtime-compliance 2 | 3 | ## Introduction 4 | 5 | This study started with a simple question: "Is it ok to include log macro calls in realtime code, so you can log during debugging but disable it through the loglevel during normal operation?". The result is an almost complete walktrough through the code, describing all aspects of the current ROS 2 logging subsystems in rcl, rcutils and rclcpp.
6 | I hope it can be useful to many, and maybe even incite some to also start looking into the ROS 2 core implementation. I'm looking forward to reading your notes! 7 | 8 | With respect to the realtime-compliance of the code, I mainly looked for: 9 | - Heap allocations, and 10 | - Blocking calls (e.g. locking a mutex). 11 | 12 | Any other things that might be relevant, please let me know! 13 | 14 | Furthermore, some conclusions are based on assumptions, which obviously I think are correct but which I did not formally check (e.g. the assumption that lambda functions are in stack memory (or some other preallocated region) and hence don't allocate, unless of course if there would be an actual allocation inside the lambda function).
15 |
16 | If there are inaccuracies or incorrect statements in below description, please correct me! 17 | 18 |
19 | 20 | ## TL;DR 21 | 22 | Logging is _obviously_ not realtime-compliant.
23 | It is possible however to use log macro calls in your code, and disable them at runtime through the loglevel.
24 | This could be useful e.g. for debug output while testing, without compromising realtime behavior during normal operation. 25 | 26 | 27 |
28 | 29 | However, even when disabled some function calls are still made, so **following rules are necessary conditions** for realtime-compliance: 30 | 31 | - Don't use the streaming macros (e.g. RCLCPP_DEBUG_STREAM), since these allocate using plain `malloc`, **before** the loglevel is evaluated and logging is discarded.
32 | 33 | - Call the logger macros with: 34 | - `node::get_logger()`, 35 | - E.g. `RCLCPP_DEBUG(this->get_logger(), "Log string")`, 36 | - Or: pass a logger member variable that was instantiated outside the realtime loop, 37 | - E.g. `RCLCPP_DEBUG(my_logger_, "Log string")`, 38 | - But do **not** use `rclcpp::get_logger("some_name")`, 39 | - E.g. `RCLCPP_DEBUG(rclcpp::get_logger("some_name"), "Log string")`, since this allocates on each call, using plain `malloc`. 40 |

41 | 42 | 43 | - Each log macro call eventually calls `rcutils_logging_get_logger_effective_level(name)` which ([on some occasions](#ancestorallocation)) allocates memory. Hence: 44 | - rclcpp should be initialized with a realtime-compliant memory allocator, 45 | - **This seems currently not possible due to [this](https://github.com/ros2/rcl/issues/1036) and [this](https://github.com/ros2/rcl/issues/1037),** 46 | - As a workaround: don't use child loggers (i.e. with dot separated names such as "parent_logger.child_logger", or by call of `Logger::get_child("name")`) for log macros in a realtime part of your code. 47 | 48 |
49 | 50 | ### A few peculiarities about the /rosout publisher 51 | 52 | - A publisher is created **only** for _node_ loggers, and **not** for _non-node_ loggers.
53 | An example: 54 | - `RCLCPP_INFO(node_->get_logger(), "Message")` is published to /rosout, but 55 | - `RCLCPP_INFO(rclcpp::get_logger("name"), "Message")` is not published to /rosout.
56 |
57 | 58 | - Child loggers publish using the publisher of the parent logger.
59 | This is configured in the call to `Logger::get_child("child_name")`, and is active for the lifetime of the child logger.
60 | This implies that: 61 | - Calling `get_child` on a _non-node_ logger throws an exception and exits your program, 62 | - Log calls with the full name of a child logger, e.g. `get_logger("node_name.child_name")`, will only publish to /rosout if there still is an instance of `Logger::get_child("child_name")` concurrently valid in some scope. 63 | 64 |
65 | 66 | E.g. this will **not** output "Log 2" to /rosout:
67 | ```c++ 68 | auto node = std::make_shared("LoggerNode"); 69 | RCLCPP_INFO(node->get_logger().get_child("child"), "Log 1"); // child logger only exists in scope of this log call 70 | RCLCPP_INFO(rclcpp::get_logger("LoggerNode.child"), "Log 2"); // publishing no longer configured 71 | ``` 72 |
73 | 74 | But this will: 75 | ```c++ 76 | auto node = std::make_shared("LoggerNode"); 77 | auto childlogger = node->get_logger().get_child("child"); 78 | RCLCPP_INFO(node->get_logger().get_child("child"), "Log 1"); // new instance of child logger in local scope, publishing is already configured 79 | RCLCPP_INFO(rclcpp::get_logger("LoggerNode.child"), "Log 2"); // publishing still active as childlogger still exists 80 | ``` 81 | 82 |
83 | 84 | Note though, that using the full name of children for node loggers is not recommended anyway, as the node name could be remapped at launch. 85 | 86 |
87 |
88 | 89 | The rest of this document gives a detailed overview of the code path and logic wrt. logging from rclcpp / rcutils / rcl. 90 | 91 |
92 |
93 | 94 | 95 | 96 | 97 | ## rclcpp Logger class 98 | 99 | Function calls such as `this->get_logger()` or `rclcpp::get_logger("logger_name")` are generally being described as "giving you _the node's logger_" or "giving you _the named logger_". Because of this, one would expect that these instantiations of the logger class perform the actual logging. 100 | 101 | This is however not the case: rclcpp "loggers" don't do any logging: logging is done solely through the macro calls, that eventually resolve to rcutils function calls. 102 | 103 | 104 | The [rclcpp::Logger](https://github.com/ros2/rclcpp/blob/b1e834a8dfb0e2058fbf0e3adcc06cd8eda86243/rclcpp/include/rclcpp/logger.hpp#L51) itself has little functionality: 105 | - It holds a name, 106 | - It has a method [`set_level(Level level)`](https://github.com/ros2/rclcpp/blob/b1e834a8dfb0e2058fbf0e3adcc06cd8eda86243/rclcpp/src/rclcpp/logger.cpp#L111) which passes the name and loglevel to `rcutils_logging_set_logger_level(name, level)`. 107 | - This sets the loglevel into a hash table (contains logger name hash and corresponding loglevel value, for lookup on each log call). More on this below. 108 | - It has some other functions, such as: 109 | - [`get_name()`](https://github.com/ros2/rclcpp/blob/b1e834a8dfb0e2058fbf0e3adcc06cd8eda86243/rclcpp/include/rclcpp/logger.hpp#L140): returns the name, 110 | - [`get_child(child_name)`](https://github.com/ros2/rclcpp/blob/b1e834a8dfb0e2058fbf0e3adcc06cd8eda86243/rclcpp/src/rclcpp/logger.cpp#L71): returns a Logger instance with name "logger_name.child_name" and configures the rosout logging system for publishing output to /rosout.
111 | 112 |
113 | 114 | Re. realtime compliance: 115 | - The [logger constructor](https://github.com/ros2/rclcpp/blob/3062dec77e4695dc0dc8a2efe764dd18c2ad47da/rclcpp/include/rclcpp/logger.hpp#L122-L123) allocates a `std::string` with standard allocator (`malloc`) 116 | - `rclcpp::get_logger(name)` calls the constructor and returns by value, 117 | - `rclcpp::get_node_logger` idem, 118 | - [`rclcpp::get_logging_directory`](https://github.com/ros2/rclcpp/blob/b1e834a8dfb0e2058fbf0e3adcc06cd8eda86243/rclcpp/src/rclcpp/logger.cpp#L57) calls `rcl_logging_get_logging_directory` explicitly with default allocator (i.e. `malloc`), 119 | - `Logger::get_child()` also allocates memory 120 | - So basically these are all **not realtime-compliant** 121 | - [`node::get_logger()`](https://github.com/ros2/rclcpp/blob/33dae5d679751b603205008fcb31755986bcee1c/rclcpp/src/rclcpp/node_interfaces/node_logging.cpp#L19-L33) returns a Logger by value, 122 | - Given a Logger holds its name as an `std::shared_ptr`, which upon copy by the copy constructor does not allocate new memory for the string, I assume this is ok. 123 | - Conclusion: 124 | - Calling the logger macros with `rclcpp::get_logger("some_name")` is **not realtime-compliant** 125 | - Calling the logger macros with `this->get_logger()` **is realtime-compliant** (wrt the logger object that is; for the inner workings of the macros see below). 126 | 127 | 128 |
129 |
130 | 131 | ## rclcpp logger macro's 132 | 133 | Below description covers the 'DEBUG' loglevel macros, but it is obviously identical for the other loglevels (INFO / WARNING / etc). 134 |
135 | The rclcpp logger macros are in `logging.hpp`, which is generated at compile time from `rclcpp/resource/logging.hpp.em` (i.e. `logging.hpp` is in the build and install folder, but not in the ROS 2 source). 136 | 137 |
138 | 139 | RCLCPP_DEBUG / RCLCPP_DEBUG_EXPRESSION / RCLCPP_DEBUG_FUNCTION / RCLCPP_DEBUG_SKIPFIRST 140 | - These macros have a compile-time assert that 'logger' is an `rclcpp::Logger` 141 | - Followed by call of an **rcutils** macro, respectively: 142 | - `RCUTILS_LOG_DEBUG_NAMED` 143 | - `RCUTILS_LOG_DEBUG_EXPRESSION_NAMED` 144 | - `RCUTILS_LOG_DEBUG_FUNCTION_NAMED` 145 | - `RCUTILS_LOG_DEBUG_SKIPFIRST_NAMED` 146 | 147 |
148 | 149 | RCLCPP_DEBUG_THROTTLE / RCLCPP_DEBUG_SKIPFIRST_THROTTLE 150 | - Similar to above, but also define a lambda function to return the current time 151 | - **Assumption: stack allocated --> realtime-compliant**, but I did not check the time functions. 152 | - Respective rcutils macro calls: 153 | - `RCUTILS_LOG_DEBUG_THROTTLE_NAMED` 154 | - `RCUTILS_LOG_DEBUG_SKIPFIRST_THROTTLE_NAMED` 155 | 156 |
157 | 158 | RCLCPP_DEBUG_STREAM / 159 | RCLCPP_DEBUG_STREAM_ONCE / etc 160 | - Similar to above, but these macros first stream the arguments into a `std::stringstream` and then call the regular macros, passing on the combined string retrieved from the stringstream. 161 | - **Heap allocation, no custom allocator
162 | --> not realtime-compliant, even if log is disabled through the loglevel**
163 | 164 |
165 | 166 | The rclcpp logging macros can be disabled at compile time: 167 | - Define `RCLCPP_LOG_MIN_SEVERITY=RCLCPP_LOG_MIN_SEVERITY_[DEBUG|INFO|WARN|ERROR|FATAL]`
168 | in your build options to compile out anything below that severity. 169 | - Use `RCLCPP_LOG_MIN_SEVERITY_NONE` to compile out all macros. 170 | 171 |
172 |
173 | 174 | ## rcutils log functionality 175 | 176 | All rcutils logging macros start with a call to `RCUTILS_LOGGING_AUTOINIT`, which initializes the logging if it was not initialized yet.
177 | - By default however, `rclcpp::init()` initializes logging before any log call, more on that [below](#rclcpp_init). 178 | 179 |
180 | 181 | ### RCUTILS_LOGGING_AUTOINIT 182 | 183 | - [RCUTILS_LOGGING_AUTOINIT](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/include/rcutils/logging.h#L560) first checks if logging is already initialized, and, if not: 184 | - Calls [`rcutils_logging_initialize(void)`](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L129-L132) which calls [`rcutils_logging_initialize_with_allocator(rcutils_allocator_t)`](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L513) with the default allocator 185 | - Default allocator uses standard `malloc/free/realloc/calloc` (stdlib.h) 186 | - Question: Is there a way to pass a different allocator?
187 |   Is this done by manually calling `rcutils_logging_initialize_with_allocator(rcutils_allocator_t)` with a custom `rcutils_allocator_t` before using any logger macro or function?
188 | ---> ANSWER: it should be possible through the `InitOptions`, though there currently are certain issues, see description [below](#rclcpp_init) wrt. initialisation from `rclcpp::init`. 189 | 190 |
191 | 192 | ### `rcutils_logging_initialize_with_allocator(allocator)` 193 | 194 |
195 | 196 | - `g_rcutils_logging_allocator` is set to the given `allocator` if the allocator is valid ([code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L519-L523)) 197 | 198 | - `g_rcutils_logging_output_handler` is a **function pointer** to the current output handler ([code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L525)) 199 | - It is set here to `rcutils_logging_console_output_handler()` 200 | - This is lateron changed by `rclcpp::init()` to an `rclcpp_logging_multiple_output_handler`, which calls this `rcutils_logging_console_output_handler()` as well as the rosout and external log library handler. 201 |
202 |
203 | - Environment variables: 204 | - `RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED`: no longer used, outputs an error message and is ignored - [code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L528-L541) 205 | - `RCUTILS_LOGGING_USE_STDOUT`: to output to stdout instead of stderr - [code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L543-L563) 206 | - `RCUTILS_LOGGING_BUFFERED_STREAM` - [code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L570-L591): 207 | - Empty = default of the stream, 208 | - 0 = force unbuffered, 209 | - 1 = force line buffered. 210 | - Correspondingly a call to `setvbuf` to configure the buffering - [code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L580) 211 | 212 | - `RCUTILS_COLORIZED_OUTPUT` - [code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L593-L612) 213 | - Empty = auto, 214 | - 0 = force disable, 215 | - 1 = force enable. 216 | 217 | - `RCUTILS_CONSOLE_OUTPUT_FORMAT`: custom output format string - [code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L614-L633) 218 | - Output format string is copied to `g_rcutils_logging_output_format_string` but truncated to MAX_OUTPUT_FORMAT_LEN, 219 | - If the environment variable was not set or could not be read, the default is used: `"[{severity}] [{time}] [{name}]: {message}"` 220 | 221 |
222 | 223 | - `g_rcutils_logging_severities_map` is initialized ([code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L635-L646)). This is a static `rcutils_hash_map_t`. 224 | - This maps logger names to loger severities. 225 | - Logger names are stored as hashes instead of strings as this is more efficient. 226 | - On each logging call: 227 | - It is checked if the map contains a hash corresponding to that log call name, and 228 | - If so: the corresponding severity is read from the map, 229 | - If not: the default severity is used, 230 | - If the severity of the macro call >= the hashmap severity, the message is logged. 231 | - First, an empty hashmap is requested, 232 | - Then it is initialized with following arguments: 233 | - Initial size is 2 (comments state that this has to be power of 2 due to some optimization on lookup), 234 | - Key size: sizeof(const char*), 235 | - Data size: sizeof(int), 236 | - Hash function, 237 | - Compare function, 238 | - Allocator 239 |
240 |
241 | - `parse_and_create_handlers_list()` is called 242 | - This parses `g_rcutils_logging_output_format_string`. This variable: 243 | - Either has been read from environment variable `RCUTILS_CONSOLE_OUTPUT_FORMAT` (see above), 244 | - Or was set to the default output format string: `"[{severity}] [{time}] [{name}]: {message}"`, 245 | - The parser installs handler functions: 246 | - That add the corresponding values to the output log string, according to each valid `{item}`, 247 | - And to copy all other parts of the format string to the output string (i.e. those parts that do not correspond to valid `{items}`). 248 | - Implementation is imo hard to read as it has little comments: 249 | - [These lines](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L452-L453) appear to handle the case where there is no start delimiter left: 250 | - `rcutils_find()` does not find a start delimiter and hence returns `SIZE_MAX` 251 | - Hence `chars_to_copy` is set to the remaining characters 252 | - [This line](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L454) adds a handler `copy_from_orig` to the array of handlers, with `start_offset = i` and `end_offset = i + chars_to_copy` 253 | - When formatting a log string, this handler will copy the corresponding part of the original log formatting string into the output. 254 | - [This](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L464) then jumps back to the start of the while loop (I think, but it seems not necessary??), 255 | - `rcutils_find` is called again for start delimiter and returns zero, so the if clause is skipped 256 | - We arrive at [another call](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L472) to `rcutils_find`, this time for the end delimiter, 257 | - [If no end delimiter is found](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L475-L483) in the remainder of the formatting string (same logic with `SIZE_MAX`), add a handler to copy the remainder of this string, 258 | - [Else](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L485-L506): 259 | - Copy that part of the string into `token`, 260 | - Check if `token` actually is a token (`find_token_handler`) 261 | - If so: add the corresponding handler, 262 | - If not: add the `copy_from_orig` handler 263 |
264 | 265 | - And finally, `g_rcutils_logging_severities_map_valid` and `g_rcutils_logging_initialized` are set to `true`.
266 | 267 | This concludes `RCUTILS_LOGGING_AUTOINIT`.
268 | 269 |
270 |
271 |
272 | 273 | Following to the `RCUTILS_LOGGING_AUTOINIT` call, each of the rcutils macros resolves to a call of:
274 | ```c++ 275 | RCUTILS_LOG_COND_NAMED(severity, condition_before, condition_after, name, ...) 276 | ``` 277 | Functional differences between the macros (e.g. throttle, skipfirst, etc) is realized through the `condition_before` and `condition_after` macro arguments of that macro (see below). 278 | 279 | 280 |
281 |
282 |
283 | 284 | ### RCUTILS_LOG_COND_NAMED 285 | 286 | Initializes static struct with the calling function name, file name and line number ([code](https://github.com/ros2/rcutils/blob/f0bee9e66830ababfe1e0f2414d46e36a0b60ec5/resource/logging_macros.h.em#L69)), 287 | **memory preallocated since it is static --> realtime-compliant** 288 | 289 | Then, it checks if logging is enabled for that name and severity, by calling `rcutils_logging_logger_is_enabled_for(name, severity)` (see below).
290 | If so, it concatenates: 291 | 292 | ```c++ 293 | condition_before rcutils_log_internal() condition_after 294 | ``` 295 | 296 | In this, `condition_before` and `condition_after` are `#define` statements, which add conditional code around the call of `rcutils_log_internal()`. 297 | 298 |
299 | 300 | E.g. for `CONDITION_EXPRESSION` the defines are as follows: 301 | 302 | ```c++ 303 | #define RCUTILS_LOG_CONDITION_EXPRESSION_BEFORE(expression) if (expression) { 304 | 305 | #define RCUTILS_LOG_CONDITION_EXPRESSION_AFTER } 306 | ``` 307 | so the concatenation results in: 308 | 309 | ```c++ 310 | if (expression) { rcutils_log_internal(); } 311 | ``` 312 | 313 |
314 | 315 | Similar expressions are defined for the other log macros (throttle, skip first, etc). 316 | 317 | As an example, this is the implementation of `RCLCPP_DEBUG_ONCE`: 318 | 319 | ```c++ 320 | #define RCLCPP_DEBUG_ONCE(logger, ...) \ 321 | do { \ 322 | static_assert( \ 323 | ::std::is_same>, \ 324 | typename ::rclcpp::Logger>::value, \ 325 | "First argument to logging macros must be an rclcpp::Logger"); \ 326 | \ 327 | RCUTILS_LOG_DEBUG_ONCE_NAMED( \ 328 | (logger).get_name(), \ 329 | __VA_ARGS__); \ 330 | } while (0) 331 | ``` 332 | 333 | `RCUTILS_LOG_DEBUG_ONCE_NAMED` calls `RCUTILS_LOG_COND_NAMED`: 334 | 335 | ```c++ 336 | # define RCUTILS_LOG_DEBUG_ONCE_NAMED(name, ...) \ 337 | RCUTILS_LOG_COND_NAMED( \ 338 | RCUTILS_LOG_SEVERITY_DEBUG, \ 339 | RCUTILS_LOG_CONDITION_ONCE_BEFORE, RCUTILS_LOG_CONDITION_ONCE_AFTER, name, \ 340 | __VA_ARGS__) 341 | ``` 342 | 343 | ```c++ 344 | #define RCUTILS_LOG_COND_NAMED(severity, condition_before, condition_after, name, ...) \ 345 | do { \ 346 | RCUTILS_LOGGING_AUTOINIT; \ 347 | static rcutils_log_location_t __rcutils_logging_location = {__func__, __FILE__, __LINE__}; \ 348 | if (rcutils_logging_logger_is_enabled_for(name, severity)) { \ 349 | condition_before \ 350 | rcutils_log_internal(&__rcutils_logging_location, severity, name, __VA_ARGS__); \ 351 | condition_after \ 352 | } \ 353 | } while (0) 354 | ``` 355 | 356 | with following conditions: 357 | 358 | ```c++ 359 | #define RCUTILS_LOG_CONDITION_ONCE_BEFORE \ 360 | { \ 361 | static int __rcutils_logging_once = 0; \ 362 | if (RCUTILS_UNLIKELY(0 == __rcutils_logging_once)) { \ 363 | __rcutils_logging_once = 1; 364 | 365 | #define RCUTILS_LOG_CONDITION_ONCE_AFTER } \ 366 | } 367 | ``` 368 | 369 | The compiler combines those `#define` statements, resulting in the following expression:
370 | (the static assert was ommitted as it is a compile-time check)
371 | 372 | 373 | ```c++ 374 | do { 375 | do { 376 | RCUTILS_LOGGING_AUTOINIT; 377 | static rcutils_log_location_t __rcutils_logging_location = {__func__, __FILE__, __LINE__}; 378 | if (rcutils_logging_logger_is_enabled_for(name, severity)) { 379 | { 380 | static int __rcutils_logging_once = 0; 381 | if (RCUTILS_UNLIKELY(0 == __rcutils_logging_once)) { 382 | __rcutils_logging_once = 1; 383 | rcutils_log_internal(&__rcutils_logging_location, severity, name, __VA_ARGS__); 384 | } 385 | } 386 | } while (0) 387 | } while (0) 388 | ``` 389 | 390 | In other words: in _the scope of the macro call_, a static variable is defined, to track if _that particular_ macro call was already called or not.
391 | So this effectively results in each log message being logged once and only once by its macro call. 392 |
393 |
394 | There's a specific reason for using the `do { .... } while (0)` construction, see the [reference in the code](https://github.com/ros2/rclcpp/blob/1a9b117d5357f4d37ecd457843ee27e8ba56b65c/rclcpp/resource/logging.hpp.em#L97-L99) for more info. 395 |
396 |
397 | 398 | For realtime execution, the logging macros are disabled by setting the loglevels so that `rcutils_logging_logger_is_enabled_for(name, severity)` returns `false`.
399 | Hence, the conditions and `rcutils_log_internal()` function are not called. 400 | 401 |
402 |
403 | 404 | ### rcutils_logging_logger_is_enabled_for(name, severity) 405 | 406 |
407 | 408 | - Calls `rcutils_logging_get_logger_effective_level` to get the 'effective loglevel' for logger 'name', 409 | 410 | - Returns true if `severity >= effective_loglevel`. 411 | - `severity` is the severity of the macro call (e.g. RCLCPP_DEBUG), 412 | - `effective_loglevel` is the loglevel which was set for this logger name or its ancestors (see below), or the default loglevel if no loglevel was set. 413 | 414 |
415 |
416 | 417 | ### rcutils_logging_get_logger_effective_level(name) 418 | 419 | Looks up 'name' in the hash map: 420 | - [If the hash map has no entries](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L866-L884): return `g_rcutils_logging_default_logger_level` 421 | 422 | - Else it looks up if there is a [hash for 'name'](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L888-L892) or, if not, for the ['ancestors' of 'name'](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L904-L939) and: 423 | - If found: returns the corresponding severity, 424 | - Else: returns `g_rcutils_logging_default_logger_level`
425 |
426 | - The 'ancestor' hierarchy is signified by logger names being separated by dots: 427 | - A logger named `x` is an ancestor of `x.y`, 428 | - Both `x` and `x.y` are ancestors of `x.y.z`, etc.
429 |
430 | 431 | **To search for ancestors, a copy of 'name' is made, allocated by g_rcutils_logging_allocator --> realtime-compliant allocator mandatory**
432 | _Idea for possible code change to avoid this allocation: add extra search and hash function that takes a parameter 'up_to_nth_delimiter', so instead of hashing until the end of the string (\0), the hashing is done until the specified number of occurences of `RCUTILS_LOGGING_SEPARATOR_CHAR` (i.e. '.') are encountered. This way no copy has to be made._ 433 | 434 |
435 |
436 | 437 | ### rcutils_logging_set_logger_level(name, level) 438 | 439 | Above hashmap is populated by calls to `rcutils_logging_set_logger_level`.
440 | Loglevels are typically specified through the command line arguments, which are processed in `rclcpp::init` (see [below](#rclcpp_init)).
441 | 442 | `rcutils_logging_set_logger_level` does the following: 443 | - [Check](https://github.com/ros2/rcutils/blob/1db1f16a49378f4693b74296449ee920ff53cffe/src/logging.c#L978-L980) that the log level is in the range `[0, number of loglevels - 1]`. 444 | - [Get](https://github.com/ros2/rcutils/blob/1db1f16a49378f4693b74296449ee920ff53cffe/src/logging.c#L985) the corresponding string, 445 | - [Check](https://github.com/ros2/rcutils/blob/1db1f16a49378f4693b74296449ee920ff53cffe/src/logging.c#L993) if an entry exist in the hashmap for that logger name, 446 | - If so: remove it, and iterate over the hash map to see if there are cached values for child loggers (i.e. not manually set) that also should be removed. Cached values are an [optimization that currently is disabled](https://github.com/ros2/rcutils/blob/1db1f16a49378f4693b74296449ee920ff53cffe/src/logging.c#L946-L959). 447 | - Finally [add the new key](https://github.com/ros2/rcutils/blob/1db1f16a49378f4693b74296449ee920ff53cffe/src/logging.c#L1052-L1057) or change the [default loglevel](https://github.com/ros2/rcutils/blob/1db1f16a49378f4693b74296449ee920ff53cffe/src/logging.c#L1059-L1062). 448 | 449 |
450 |
451 |
452 | 453 | ### `rcutils_log_internal(location, severity, name, format, ... )` 454 | 455 | For realtime execution, the logging macros are disabled by setting the loglevels so that `rcutils_logging_logger_is_enabled_for(name, severity)` returns `false`. Hence, the conditions and `rcutils_log_internal()` function are not called.
456 | However, realtime compliance of `rcutils_log_internal(location, severity, name, format, ... )` could still be relevant if somebody (yes, that's you!) decides to write a realtime-compliant output handler (e.g. a non-locking buffered one? So the realtime calls never block, and a non-realtime thread reads from the buffer and does the actual logging output.). 457 | 458 | Anyway, `rcutils_log_internal(location, severity, name, format, ... )` [is called](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1113-L1121). 459 | 460 | - The `va_list`, `va_start` and `va_end` calls deal with converting the "`...`" part of the function call into a variable named "`args`" that can be passed on to the call of `vrcutils_log_internal`.
461 | **Does va_start allocate?** How does it convert "..." into args? 462 | - Then in [`vrcutils_log_internal`](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1083-L1097): 463 | - The [current time is retrieved](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1088) `rcutils_system_time_now()`. This [boils down to](https://github.com/ros2/rcutils/blob/c83c4c7b197e72527fc9e0b438f9f1e6225f70af/src/time_unix.c#L65) `clock_gettime()` which **I think is realtime-compliant?**, and then 464 | - The output handler function pointer is dereferenced to [call the ouput handler](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1095) with the arguments. 465 | 466 |
467 | 468 | For rclcpp logging, an output handler is set in `rclcpp::init()`, that outputs to `stderr`, a `logfile` and publishes to `/rosout`.
469 | `stderr` is handled by the [rcutils_logging_console_output_handler](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1256). 470 | 471 |
472 |
473 |
474 | 475 | ## Recap 476 | 477 | It starts with an rclcpp macro call: 478 | 479 | `RCLCPP_INFO(node->get_logger(), "Some log message");` 480 | 481 |
482 | 483 | After some rcutils macro magic, this resolves to: 484 | - A call of `RCUTILS_LOGGING_AUTOINIT` (which only does things when logging is not initialized yet), 485 | - Followed by `rcutils_logging_logger_is_enabled_for(name, severity)`. 486 |
487 | 488 | Here it stops if logging is disabled through the loglevel. 489 | 490 |
491 | 492 | Otherwise a call is made to `rcutils_log_internal()`. 493 | 494 | 495 | This basically passes on to `vrcutils_log_internal()`, which calls the ouput handler. 496 | 497 |
498 | 499 | So let's now check the rclcpp initialization, as this sets the output handler. 500 | 501 | 502 |
503 |
504 | 505 | ## rclcpp logger initialization 506 | 507 | Rclcpp logging is typically initialized from `rclcpp::init`. 508 | 509 |
510 | 511 | `rclcpp::init()` is implemented in [`rclcpp/utilities.cpp`](https://github.com/ros2/rclcpp/blob/33dae5d679751b603205008fcb31755986bcee1c/rclcpp/src/rclcpp/utilities.cpp#L33-L44) and basically calls:
512 |   `get_global_default_context()->init(argc, argv, init_options);` 513 | 514 | 515 | `get_global_default_context()` [returns a shared_ptr](https://github.com/ros2/rclcpp/blob/33dae5d679751b603205008fcb31755986bcee1c/rclcpp/src/rclcpp/contexts/default_context.cpp#L22-L27) to a `DefaultContext`, which inherits from `rclcpp::Context`. 516 | 517 | The `Context` constructor is empty apart from zero-initialising some member variables. 518 | 519 | Then, `Context::init()` is called. It has several functional blocks: 520 | 521 | - [Initialize the context](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L203-L213): 522 | 523 | - It [locks](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L198) an `init_mutex_`, which is a `std::recursive_mutex`, 524 | - It [allocates](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L203) a new `rcl_context_t`, 525 | - It [calls](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L207) `rcl_get_zero_initialized_context()`, 526 | - It [calls](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L208) `rcl_init` on the context (description below), and 527 | - If all went well, it [stores](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L213) `context` and a corresponding destructor function `__delete_context()` into the `std::shared_ptr` called `rcl_context_`. 528 |
529 | - [Initialize the logging](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L215-L234) (can be disabled through the `InitOptions`): 530 | - [Locks](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L216-L217) the global logging mutex (shared_prt to static `std::recursive_mutex` ) 531 | - [If the reference count is zero](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L218-L219) (i.e. no other contexts initialized the logging yet), a [call is made](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L220-L223) to `rcl_logging_configure_with_output_handler` 532 | - With the `rcl_context_` global arguments, 533 | - With the [allocator](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L222) defined in the `init_options`, 534 | - With the `rclcpp_logging_output_handler` 535 | - For a further description, see below. 536 |
537 | - Then [it checks](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L239-L241) for unparsed arguments (there shouldn't be any): 538 | - If there are: [catch the exception](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L247-L257), clean up (`rcl_shutdown` etc) and rethrow, 539 |
540 | - Finally [save the `initoptions`](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L243) and [add the context](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L245-L246) as a weak pointer to the global `WeakContextsWrapper`. 541 | 542 |
543 |
544 | 545 | **Regarding above call of `rcl_init`:** 546 | - [It does some checks](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/init.c#L54-L69): 547 | - If `argc`and `argv` correspond (i.e. `argc` non-null `argv` values), 548 | - If the options and context are not null and the allocator is valid, 549 | 550 | - **There's a [call to logging](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/init.c#L71-L73) before logging is initalized** ---> [bugreport](https://github.com/ros2/rcl/issues/1037) 551 | 552 | - [This comment](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/init.c#L87) is interesting:
553 |  `// use zero_allocate so the cleanup function will not try to clean up uninitialized parts later`
554 | I assume this is part of the rationale for the "two-step initialization" procedure that is often used: 555 | - First get a zero-initialized _something_, 556 | - Then initialize the _something_, 557 | - If initialization fails, then everything which is still zero should not be cleaned up. 558 |
559 |
560 | - It [calls](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/init.c#L99) `rcl_init_options_copy` 561 | - This seems to be RMW-related, as it [resolves to](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/init_options.c#L106) a call of `rmw_init_options_copy`. 562 |
563 |
564 | - `argc` and `argv` are [copied into the context](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/init.c#L105-L124) 565 | - The command line arguments [are parsed](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/init.c#L127): 566 | - Do some [error checks](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L254-L266) 567 | - [Allocate](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L271) an `rcl_arguments_t` 568 | - It does not have `zero` in the name (`_rcl_allocate_initialized_arguments_impl`) this time, but it is also zero-initialized. 569 | - [Here](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L2055-L2070) is the complete list of members. Wrt logging, following ar relevant: 570 | - `args_impl->log_levels` 571 | - `args_impl->external_log_config_file` 572 | - `args_impl->log_stdout_disabled` 573 | - `args_impl->log_rosout_disabled` 574 | - `args_impl->log_ext_lib_disabled` 575 |

576 | - [Allocate the members](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L282-L315) of the `args_impl` of the `rcl_arguments_t`.
577 | It states in the comment that it is "over-allocating".
578 | Indeed, each allocation is done for `argc` values (i.e. the maximum possible amount). After parsing, the non-needed allocations are [deallocated](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L596-L667)
579 | Wrt logging: the [call to](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L311) `rcl_log_levels_init` [allocates](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/log_level.c#L52-L57) memory for `rcl_logger_setting_t`. 580 |

581 | - Then it starts [parsing](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L331-L594). The definition of the known command-line arguments is [here](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/include/rcl/arguments.h#L41-L84).
582 |   (**There's several more calls to logging here, though logging still is uninitalized** --> [bugreport](https://github.com/ros2/rcl/issues/1037))
583 | Amongst others, it parses: 584 | - Command-line [loglevel arguments](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L420-L444), 585 | - Command-line specified [logger file](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L446-L476)
586 | --> This simply reads the file: there are currently no checks in the [code](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/arguments.c#L1976-L1992) 587 |

588 | - The rest of `rcl_init` mainly seems to setup RMW. 589 | 590 | 591 |
592 |
593 | 594 | **After `rcl_init` the call to `rcl_logging_configure_with_output_handler` is made to initialize the logging:** 595 | 596 | 597 | - It starts with a [call to](https://github.com/ros2/rcl/blob/bc979c6f22d6af54ad473cd65cd81708a4da8a93/rcl/src/rcl/logging.c#L65) `RCUTILS_LOGGING_AUTOINIT`, 598 | - This is strange, as `RCUTILS_LOGGING_AUTOINIT` uses the standard allocator. 599 | - Filed a [bug report](https://github.com/ros2/rcl/issues/1036) 600 |

601 | - Then, the parsed command-line arguments from `rcl_init()` are taken and corresponding [loglevels are set](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/logging.c#L68-L90) 602 |

603 | - Following three output handlers [are initialized](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/logging.c#L91-L113) and [added](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/logging.c#L91-L113) (unless disabled through the command-line arguments): 604 | 1. `rcutils_logging_console_output_handler`, 605 | 2. `rcl_logging_rosout_output_handler` 606 | 3. `rcl_logging_ext_lib_output_handler` 607 |

608 | - The log config file is passed solely to the [external logger](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/logging.c#L103). 609 |

610 | - Finally `rcutils_logging_set_output_handler` is called, so the `rclcpp_logging_multiple_output_handler` is used. 611 |
612 |
613 |
614 | 615 | The `rclcpp_logging_multiple_output_handler`: 616 | 617 | - [Locks](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L131-L133) the rclcpp global logging mutex, and 618 | - [Calls](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L134-L135) `rcl_logging_multiple_output_handler`, which simply [calls](https://github.com/ros2/rcl/blob/bc979c6f22d6af54ad473cd65cd81708a4da8a93/rcl/src/rcl/logging.c#L157-L161) each of the three output handlers consecutively. 619 | 620 |
621 |
622 |
623 | 624 | 625 | ## rcl output handlers 626 | 627 |
628 | 629 | As mentioned, rcl installs three output handlers, console, rosout and external library: 630 | 631 | 632 |
633 | 634 | ### rcutils_logging_console_output_handler 635 | 636 |
637 | 638 | The `rcutils_logging_console_output_handler` does the following: 639 | 640 | - [Check](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1264) for initialized, 641 | - [Check](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1270-L1281) if severity is correct, else return, 642 | - [Check](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1283-L1289) if output is colorized, 643 | - [Initialize](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1291-L1307) `msg_array` and `output_array` 644 | - Initial buffer size is 1024 characters (including terminating `\0`)  **Fixed-size array in stack memory** 645 | - Both use the `g_rcutils_logging_allocator` if expansion beyond 1024 characters is needed.  **Can be realtime-compliant if realtime-compliant allocator is used, or stay below 1024 characters.**
646 |
647 | 648 | - [Call](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1309-L1311) to `SET_OUTPUT_COLOR_WITH_SEVERITY(status, severity, color)`.
649 | This calls [SET_COLOR_WITH_SEVERITY](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1241-L1246) and [SET_OUTPUT_COLOR_WITH_COLOR](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1241-L1246). 650 | 651 | `SET_COLOR_WITH_SEVERITY` resolves to: 652 | ```c++ 653 | { 654 | const char * color = NULL; // color is char* in stack memory 655 | { 656 | switch (severity) { 657 | case RCUTILS_LOG_SEVERITY_DEBUG: 658 | color = "\033[32m"; // color points to static read-only string --> ok 659 | break; 660 | case RCUTILS_LOG_SEVERITY_INFO: 661 | color = "\033[0m"; 662 | break; 663 | 664 | /* rest of code ommitted for clarity */ 665 | 666 | } 667 | } 668 | ``` 669 | 670 | And `SET_OUTPUT_COLOR_WITH_COLOR(status, color, output_array)` does [the following](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1230-L1240): 671 | - Calls `rcutils_char_array_strncat` 672 | - This appends the color string to `output_array`, 673 | - Will not allocate as `output_array` is still empty and its capacity (1024 - 1) is larger than the color string that is copied into it. 674 |
675 |
676 | 677 | - If all above went ok, `args` is cloned into a new `va_list` and passed on to `rcutils_char_array_vsprintf`, see [this code](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1313-L1322)
678 | **Does va_copy allocate? It's a copy?** 679 | 680 | - `rcutils_char_array_vsprintf`: 681 | - Calls `vsnprintf` from ``. This converts a variable argument list `va_list` into a formatted string in a sized buffer. **Does this allocate?** 682 | - If buffer is too small, `vsnprintf` returns the needed buffer size to fit. 683 | - If needed, `msg_array` is resized accordingly and `vsnprintf` called a 2nd time.   **Can be realtime-compliant if realtime-compliant allocator is used, or stay below 1024 characters.**
684 |
685 | 686 | - If all is ok, `rcutils_logging_format_message` [is called](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1324-L1331): 687 | - This [populates](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1128-L1134) a `logging_input_t` data member and 688 | - Iterates accross the formatting handlers that were set by [parse_and_create_handlers_list()](#parse_and_create_handlers_list) 689 | - Recall: these handlers populate `output_array` according to the formatspecification (e.g. `"[{severity}] [{time}] [{name}]: {message}"`) 690 | - Similar to above, `output_array` is resized as needed.   **Can be realtime-compliant if realtime-compliant allocator is used, or stay below 1024 characters.**
691 |
692 | 693 | - Then `SET_STANDARD_COLOR_IN_BUFFER` [is called](https://github.com/ros2/rcutils/blob/61018b2f88e55ac81edda4a45a02634493c999ed/src/logging.c#L1334) which appends "\033[0m" to the end of the buffer to reset the color output, 694 | 695 | - and finally ... 696 | 697 | - An `fprintf` call is made to output the `output_array`: 698 | ```c 699 | if (RCUTILS_RET_OK == status) { 700 | fprintf(g_output_stream, "%s\n", output_array.buffer); 701 | } 702 | ``` 703 | 704 | 705 |
706 |
707 | 708 | ### rosout 709 | 710 | This publishes log info to topic /rosout.
711 | Configuration of this output handler is spread accross a few steps: 712 | - A call to `rcl_logging_rosout_init` before the handler is registered, 713 | - Some logic upon creation of a node, 714 | - Some logic upon call of `Logger::get_child()` 715 |
716 |
717 | 718 | **Upon `rcl_logging_rosout_init`:** 719 | - This [initializes two hashmaps](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L89-L119): `__logger_map` and `__sublogger_map`.
720 | - Hashmap allocator is the one which was passed to `rcl_logging_configure_with_output_handler` (i.e. the one defined in the `InitOptions`, see [here](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L222)). 721 | - `__logger_map` links full logger names (e.g. `"my_logger"` or `"other_logger.child.grandchild"`) to `rosout_map_entry_t` instances, which hold a reference to the corresponding node publisher. 722 | - `__sublogger_map` links full names to a reference counter, to track when cleanup is needed. 723 | 724 |
725 | 726 | 727 | **Upon creation of a node:** 728 | 729 | - On creation of a node, a [NodeBase is instantiated](https://github.com/ros2/rclcpp/blob/432bf21f0261bab209b37ccfe6da550f02751a22/rclcpp/src/rclcpp/node.cpp#L162), which: 730 | - [Locks](https://github.com/ros2/rclcpp/blob/33dae5d679751b603205008fcb31755986bcee1c/rclcpp/src/rclcpp/node_interfaces/node_base.cpp#L54-L58) the global logging mutex, and 731 | - [Calls](https://github.com/ros2/rclcpp/blob/33dae5d679751b603205008fcb31755986bcee1c/rclcpp/src/rclcpp/node_interfaces/node_base.cpp#L63-L67) `rcl_node_init`. 732 |

733 | - This does a lot of things, and then [calls](https://github.com/ros2/rcl/blob/4eccc3cbe65f5b58981f22efaf612a65731cb2f0/rcl/src/rcl/node.c#L287-L294) `rcl_logging_rosout_init_publisher_for_node`, which: 734 | - [Checks the hash map](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L243-L261) 735 | - If an entry already exists for this name (due to another node with the same name), a warning is issued.
736 | (This is another rcutils log macro call, but this is ok here as logging should have be enabled by now.) 737 |

738 | - [Creates a publisher](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L263-L275) 739 | - This [allocates](https://github.com/ros2/rcl/blob/60d80648c2a7cdbadcc7f22bdbc3c358c04dff7c/rcl/src/rcl/publisher.c#L65) using the allocator defined in the `rcl_publisher_options_t`. 740 | - The provided publisher options are the [default ones](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L266), i.e. `malloc`. [--> bugreport](https://github.com/ros2/rcl/issues/1040) 741 | - Note following [TODO](https://github.com/ros2/rcl/blob/60d80648c2a7cdbadcc7f22bdbc3c358c04dff7c/rcl/src/rcl/publisher.c#L109) in the code:
742 | ` // TODO(wjwwood): pass along the allocator to rmw when it supports it`
743 | I did not further look into this. Relevant [link](https://github.com/ros2/rmw/issues/159)? 744 |

745 | 746 | - [Adds it](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L277-L289) to the `__logger_map` 747 |

748 | 749 | Note that this is the only place where rosout publishers are created.
750 | This implies that only log messages associated to a node logger are published to `/rosout`.
751 | Log messages from log macro calls with a non-node logger (i.e. a "named logger", e.g. `rclcpp::get_logger("some_name")`) are **not** published to `/rosout`. 752 | 753 |

754 | 755 | **Upon call of `Logger::get_child()`:** 756 | 757 | - [Locks](https://github.com/ros2/rclcpp/blob/399f4df7396d67b42ccaea651bbd87d66b0d62b3/rclcpp/src/rclcpp/logger.cpp#L78-L81) the global logging mutex 758 | 759 | - [Configures](https://github.com/ros2/rclcpp/blob/399f4df7396d67b42ccaea651bbd87d66b0d62b3/rclcpp/src/rclcpp/logger.cpp#L82) the subnode publishing by a call to `rcl_logging_rosout_add_sublogger`: 760 | - This first [gets the full name](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L434) (i.e. "logger" + "child" --> "logger.child"). 761 | - This [allocates memory](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L408-L410) using `__rosout_allocator` (which is the allocator given to `rcl_logging_configure_with_output_handler()`, i.e. the one defined in the `InitOptions`, see [here](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L222)). 762 |

763 | 764 | - Then [checks if there is an entry](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging_rosout.c#L435) for the parent node in the `__logger_map`, 765 | - If not, [throws an error](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging_rosout.c#L436-L440) 766 | - Note that this implies that, if the rosout publisher is enabled, a call to `get_child()` on a non-node logger (i.e. a "named logger") will **throw an exception**. 767 | - This **terminates your program**. 768 |

769 | - Else: 770 | - If there is already a key in the `__logger_map` for the full name ("parent.child"): 771 | - [Augment the reference counter](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging_rosout.c#L442-L453) in the `__sublogger_map`,
772 | - Else: 773 | - [Add](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging_rosout.c#L456-L461) a new entry in `__logger_map` for the sublogger full name, with the same `entry` as the parent (i.e. using the publisher of the parent), 774 | - [Allocate and add](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging_rosout.c#L463-L474) a new sublogger entry to `__sublogger_map`. 775 |

776 | - Finally [return, or cleanup](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging_rosout.c#L487-L493) if something went wrong along the way. 777 | 778 | 779 |
780 |
781 | 782 | **The output handler itself:**
783 | The `rcl_logging_rosout_output_handler` has a similar functionality as the console output handler: 784 | 785 | - Get node/publisher info from the hashmap for that logger name - [code](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L340) 786 | - The `if` clause spans the whole output handler function body, so if no hash is found (i.e. for a named logger) it just returns. 787 |

788 | - Initialize an empty message buffer and call `rcutils_char_array_vsprintf` - [code](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L342-L356) 789 | - For the description of `rcutils_char_array_vsprintf`, see [above description](#rcutils_vspintf) of the console output handler. 790 |

791 | - Then it [creates](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L363) a message by calling `rcl_interfaces__msg__Log__create()`.
792 | Afaik, the code implementing this function is generated upon build time from the [Log.msg interface](https://github.com/ros2/rcl_interfaces/blob/rolling/rcl_interfaces/msg/Log.msg), yielding following source file:
793 |   `build/rcl_interfaces/rosidl_generator_c/rcl_interfaces/msg/detail/log__functions.c`
794 | which allocates using the **default allocator** and initializes the message: 795 | ```c 796 | rcl_interfaces__msg__Log * 797 | rcl_interfaces__msg__Log__create() 798 | { 799 | rcutils_allocator_t allocator = rcutils_get_default_allocator(); 800 | rcl_interfaces__msg__Log * msg = (rcl_interfaces__msg__Log *)allocator.allocate(sizeof(rcl_interfaces__msg__Log), allocator.state); 801 | if (!msg) { 802 | return NULL; 803 | } 804 | memset(msg, 0, sizeof(rcl_interfaces__msg__Log)); 805 | bool success = rcl_interfaces__msg__Log__init(msg); 806 | if (!success) { 807 | allocator.deallocate(msg, allocator.state); 808 | return NULL; 809 | } 810 | return msg; 811 | } 812 | ``` 813 |
814 | 815 | - Then, the message is [populated](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L365-L372) and [published](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L373) 816 | - The publish call resorts to a call of [rwm_publish](https://github.com/ros2/rcl/blob/60d80648c2a7cdbadcc7f22bdbc3c358c04dff7c/rcl/src/rcl/publisher.c#L262), 817 | - This code path was not further studied for this document. 818 | - Note that the last argument is `NULL`(no pre-allocted memory to be used). 819 |

820 | - Finally the message is [finalized and deallocated](https://github.com/ros2/rcl/blob/d15594effa63065a19a9f69960ea80f5ac5be8bd/rcl/src/rcl/logging_rosout.c#L381): 821 | ```c 822 | void 823 | rcl_interfaces__msg__Log__destroy(rcl_interfaces__msg__Log * msg) 824 | { 825 | rcutils_allocator_t allocator = rcutils_get_default_allocator(); 826 | if (msg) { 827 | rcl_interfaces__msg__Log__fini(msg); 828 | } 829 | allocator.deallocate(msg, allocator.state); 830 | } 831 | ``` 832 | 833 | 834 | 835 | 836 |
837 |
838 | 839 | ### External library (spdlog) 840 | 841 | An interface for external logging libraries is defined in `rcl_logging`.
842 | 843 | This declares [following functions](https://github.com/ros2/rcl_logging/blob/rolling/rcl_logging_interface/include/rcl_logging_interface/rcl_logging_interface.h), to be implemented by the library: 844 | - `rcl_logging_external_initialize` 845 | - `rcl_logging_external_set_logger_level` 846 | - `rcl_logging_external_log` 847 | - `rcl_logging_external_shutdown` 848 | 849 | And following function, [implemented](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_interface/src/logging_dir.c#L25) by the interface itself: 850 | - `rcl_logging_get_logging_directory`
851 | This returns the full path to the logging directory. It is: 852 | - Either the value of environment variable `ROS_LOG_DIR`, 853 | - Or the default of `$ROS_HOME/log`, 854 | - `$ROS_HOME` is another environment variable that can be set, or defaults to `$HOME/.ros`. 855 | 856 |
857 | 858 | Currently, there are [two implementations](https://github.com/ros2/rcl_logging): 859 | - `rcl_logging_spdlog`, using the `spdlog` library, 860 | - `rcl_logging_noop`, which is an empty implementation (does nothing). 861 |
862 | 863 | For reference: there used to be also a `log4cxx` implementation, but that was [removed](https://github.com/ros2/rcl_logging/pull/78) at some point. 864 | 865 |
866 | 867 | I did not check in detail how to select a specific external library implementation.
868 | This [Discourse post](https://discourse.ros.org/t/ros2-logging/6469/34) states the following: 869 | 870 | > The external logging library is statically linked when rcl is compiled, but I believe that the rcl library is dynamically linked during runtime. That should mean that you only need to recompile rcl_logging_spdlog and rcl and make sure they’re sourced as an overlay to the base ROS install. 871 | 872 | So I assume it is a compile-time option. 873 | 874 | Note that [this anwer](https://discourse.ros.org/t/ros2-logging/6469/36) to above post states that "overlaying didn’t work for me reliably". So ymmv... 875 | 876 | 877 |

878 | 879 | `rcl_logging_external_initialize` 880 | - This first locks a mutex 881 | - It is strange that this implementation uses a mutex at this level, whereas the others don't. 882 | - In any case, in the context of rclcpp logging, initialization calls are serialized anyway by the rclcpp mutexes, so an extra mutex is not necessary. 883 | 884 |
885 | 886 | - It [errors](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp#L106-L111) if a configuration file was provided. 887 | 888 | 889 | - It [reads](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp#L115-L121) environment variable `RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR` which probably no one still knows about ;-), 890 | 891 | - It [gets](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp#L127) the path to the log directory (default `$HOME/.ros/log/`) and [creates](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp#L137) the directory if needed. 892 | 893 | - It [retrieves and concatenates](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp#L143-L175) all parts of the log file name, 894 | 895 | - Then it [creates and registers](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp#L177-L191) a spdlog sink and logger, configured to flush every 5 seconds and on error. 896 | 897 |

898 | 899 | **The other interface functions** 900 | 901 | Refer to their [implementation](https://github.com/ros2/rcl_logging/blob/cdef749a304f734ba275f8466a4883db6400dc75/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp#L197-L217). 902 | 903 | 904 |

905 | 906 | **The output handler** 907 | 908 | The `rcl_logging_ext_lib_output_handler` is very similar to the console output handler: 909 | - It also [calls](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging.c#L193-L196) `rcutils_char_array_vsprintf` and `rcutils_logging_format_message` to populate the message string, 910 | - And then is [passes](https://github.com/ros2/rcl/blob/12e32fefdfc628224087cfd250760a2d3d57981e/rcl/src/rcl/logging.c#L210) this to `rcl_logging_external_log()`. 911 | 912 |


913 | 914 | 915 | ## Conclusion 916 | 917 | This concludes this study of the rcl / rcutils / rclcpp logging implementation. 918 | 919 | There only parts (I think) that are not covered here, are the cleanup routines called from [`context::shutdown`](https://github.com/ros2/rclcpp/blob/1fd5a96561166ad2ad557bbc1a297cd652883cb2/rclcpp/src/rclcpp/context.cpp#L339-L353).
920 | However, if you have come this far, I think you're capable to study these on your own. ;-) 921 |

922 | Thanks for reading, I hope this document is useful to you. 923 |

924 | Now back to the robots. 925 | 926 | --------------------------------------------------------------------------------