Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion rclc/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,9 @@ During the configuration phase, the user shall define:
- trigger condition (optional, default: ANY)
- data communcation semantics (optional, default ROS2)

As the Executor is intended for embedded controllers, dynamic memory management is crucial. Therefore at initialization of the rclc Executor, the user defines the total number of callbacks. The necessary dynamic memory will be allocated only in this phase and no more memory in the running phase. This makes this Executor static in the sense, that during runtime no additional callbacks can be added.
As the Executor is intended for embedded controllers, dynamic memory management is crucial. Therefore at initialization of the rclc Executor, the user defines the total number of callbacks. The necessary dynamic memory will be allocated only in this phase and no more memory in the running phase. This makes this Executor static in the sense, that during runtime no additional callbacks can be added.

Also in the XRCE-DDS middleware the maximum number of handles need to be configured. See [Memory Management Tutorial](https://docs.vulcanexus.org/en/humble/rst/tutorials/micro/memory_management/memory_management.html#entity-creation) for the defaults and configuration of the colcon.meta configuration file. To make sure that the changes were applied, you can check the defined values in the following library include file: build/rmw_microxrcedds/include/rmw_microxrcedds_c/config.h.

Then, the user adds handles and the corresponding callbacks (e.g. for subscriptions and timers) to the Executor. The order in which this takes place, defines later the sequential processing order during runtime.

Expand Down
10 changes: 9 additions & 1 deletion rclc/include/rclc/executor.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,15 @@ rclc_executor_get_zero_initialized_executor(void);
* Therefore at initialization of the RCLC-Executor, the user defines the total \p number_of_handles.
* A handle is a term for subscriptions, timers, services, clients and guard conditions. The
* heap will be allocated only in this phase and no more memory will be allocated in the
* running phase in the executor. However, the heap memory of corresponding wait-set is
* running phase in the executor.
*
* Also in the XRCE-DDS middleware the maximum number are configured. See [Memory Management Tutorial](https://docs.vulcanexus.org/en/humble/rst/tutorials/micro/memory_management/memory_management.html#entity-creation)
* for the default values. If you need larger values, you need to update your colcon.meta
* configuration file and rebuild. To make sure that the changes were applied, you can check
* the defined values in the following library include file:
* build/rmw_microxrcedds/include/rmw_microxrcedds_c/config.h
*
* The heap memory of corresponding wait-set is
* allocated in the first iteration of a spin-method, which calls internally rclc_executor_prepare.
* Optionally, you can also call rclc_executor_prepare before calling any of the spin-methods.
* Then all wait-set related memory allocation will be done in rclc_executor_prepare and not
Expand Down