diff --git a/_docs/concepts/rtos/comparison/index.md b/_docs/concepts/rtos/comparison/index.md
index a6d2d635..cd7b7cad 100644
--- a/_docs/concepts/rtos/comparison/index.md
+++ b/_docs/concepts/rtos/comparison/index.md
@@ -45,12 +45,12 @@ The comparison regards the features listed below:
| Community | open-source | open-source | Linux Foundation Collaboration Project, (Intel, Linaro (ARM), nordic, NXP, Synopsys) |
| | | | |
| **Supported Hardware** | | | |
-| Olimex STM32-E407 (Cortex-M4) | yes | yes | yes, [explicitly](https://docs.zephyrproject.org/latest/reference/kernel/scheduling/index.html) |
+| Olimex STM32-E407 (Cortex-M4) | yes | yes | yes, [explicitly](https://docs.zephyrproject.org/latest/kernel/services/scheduling/index.html) |
| Bosch XDK 5 | not explicitly, but similar 6 | yes | no5 |
| MPC57xx | no | no | no |
| **Scheduling** | | | |
| Priority-based | FIFO | yes | yes |
-| Round-Robin 4 | yes | yes 6 | [co-operative](https://docs.zephyrproject.org/latest/reference/kernel/scheduling/index.html) |
+| Round-Robin 4 | yes | yes 6 | [co-operative](https://docs.zephyrproject.org/latest/kernel/services/scheduling/index.html) |
| Sporadic Server | yes | no | no |
| Reservation Based Scheduling (RBS) | no | no | no |
| Rate Monotonic Scheduling (RMS) | ? | yes 10 | yes 10 |
diff --git a/_docs/overview/users_and_clients/images/capra.png b/_docs/overview/users_and_clients/images/capra.png
new file mode 100644
index 00000000..02f03ecc
Binary files /dev/null and b/_docs/overview/users_and_clients/images/capra.png differ
diff --git a/_docs/overview/users_and_clients/index.md b/_docs/overview/users_and_clients/index.md
index 97935aa4..1ef84060 100644
--- a/_docs/overview/users_and_clients/index.md
+++ b/_docs/overview/users_and_clients/index.md
@@ -11,7 +11,7 @@ customers_list:
text: LG Electronics is one of the fourth-largest electronics company in South Korea. It comprises four business units home entertainment, mobile communications, home appliances and vehicle components
title: LG
url: www.lg.com
- - path: https://capra.ooo/wp-content/themes/capra/img/logo_w-tagline.svg
+ - path: ./images/capra.png
text: Capra Robotics creates outdoor mobile robots for multiple uses. Their robot platform, Capra Hircus, is designed to easily integrate with additional hard- or software, making it customizable for specific applications. They support businesses in optimizing their operations and relieve people of repetitive and unhealthy job tasks. Their state-of-the-art mobile robot answers the issues that have troubled the mobile robot industry for years, namely a lack of versatility, poor driving capabilities, short ranges, low operating time and high pricing.
title: Capra Robotics
url: capra.ooo
diff --git a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md
index 71697853..517317c3 100644
--- a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md
+++ b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md
@@ -5,19 +5,29 @@ permalink: /docs/tutorials/programming_rcl_rclc/parameters/
-ROS 2 parameters allow the user to create variables on a node and manipulate/read them with different ROS2 commands. Further information about ROS 2 parameters can be found [here](https://docs.ros.org/en/galactic/Tutorials/Parameters/Understanding-ROS2-Parameters.html)
-
-Ready to use code related to this tutorial can be found in [`rclc/rclc_examples/src/example_parameter_server.c`](https://github.com/ros2/rclc/blob/master/rclc_examples/src/example_parameter_server.c). Fragments of code from this example is used on this tutorial.
-
-Note: micro-ROS parameter server is only supported on ROS 2 Galactic distribution
-
-- [Initialization](#initialization)
-- [Memory requirements](#memory-requirements)
-- [Callback](#callback)
-- [Add a parameter](#add-a-parameter)
-- [Cleaning up](#cleaning-up)
-
-## Initialization
+ROS 2 parameters allow the user to create variables on a node and manipulate/read them with different ROS 2 commands. Further information about ROS 2 parameters can be found [here](https://docs.ros.org/en/rolling/Tutorials/Parameters/Understanding-ROS2-Parameters.html)
+
+Ready to use code examples related to this tutorial can be found in [`rclc/rclc_examples/src/example_parameter_server.c`](https://github.com/ros2/rclc/blob/master/rclc_examples/src/example_parameter_server.c).
+
+micro-ROS parameters implementation has been upgraded in the latest micro-ROS Humble distribution, two approaches are presented in this tutorial: micro-ROS Foxy/Galactic and micro-ROS Humble and beyond:
+
+- [General implementation](#general-implementation)
+ - [Initialization](#initialization)
+ - [Memory requirements](#memory-requirements)
+ - [Add a parameter](#add-a-parameter)
+ - [Cleaning up](#cleaning-up)
+- [micro-ROS Foxy/Galactic](#micro-ros-foxygalactic)
+ - [Initialization options](#initialization-options)
+ - [Callback](#callback)
+- [micro-ROS Humble](#micro-ros-humble)
+ - [Initialization options](#initialization-options-1)
+ - [Callback](#callback-1)
+ - [Add a parameter](#add-a-parameter-1)
+ - [Delete a parameter](#delete-a-parameter)
+ - [Parameters description](#parameters-description)
+
+## General implementation
+### Initialization
- Default initialization:
```c
@@ -28,38 +38,16 @@ Note: micro-ROS parameter server is only supported on ROS 2 Galactic distributio
rcl_ret_t rc = rclc_parameter_server_init_default(¶m_server, &node);
if (RCL_RET_OK != rc) {
- ... // Handle error
- return -1;
- }
- ```
-
-- Custom options:
-
- The user can configure whether to notify parameter changes to the rest of nodes (`notify_changed_over_dds`) and the maximum number of parameters (`max_params`) allowed on the `rclc_parameter_server_t` object:
-
- ```c
- // Parameter server object
- rclc_parameter_server_t param_server;
-
- // Initialize parameter server options
- const rclc_parameter_options_t options = {
- .notify_changed_over_dds = true,
- .max_params = 4 };
-
- // Initialize parameter server with configured options
- rcl_ret_t rc = rclc_parameter_server_init_with_option(¶m_server, &node, &options);
-
- if (RCL_RET_OK != rc) {
- ... // Handle error
- return -1;
+ ... // Handle error
+ return -1;
}
```
-## Memory requirements
+### Memory requirements
-The parameter server uses 5 services and an optional publisher, this needs to be taken into account on the `rmw-microxredds` package memory configuration:
+The parameter server uses five services and an optional publisher. These need to be taken into account on the `rmw-microxrcedds` package memory configuration:
-```json
+```yaml
# colcon.meta example with memory requirements to use a parameter server
{
"names": {
@@ -76,7 +64,7 @@ The parameter server uses 5 services and an optional publisher, this needs to be
}
```
-On runtime, the variable `RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER` defines the RCLC executor handles required for a parameter server:
+At runtime, the variable `RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER` defines the necessary number of handles required by a parameter server for the rclc Executor:
```c
// Executor init example with the minimum RCLC executor handles required
@@ -86,15 +74,117 @@ rc = rclc_executor_init(
RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER, &allocator);
```
-## Callback
+*Humble: the variable is `RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER` has been renamed to `RCLC_EXECUTOR_PARAMETER_SERVER_HANDLES`.*
+
+### Add a parameter
+
+The micro-ROS parameter server supports the following parameter types:
+
+- Boolean:
+ ```c
+ const char * parameter_name = "parameter_bool";
+ bool param_value = true;
+
+ // Add parameter to the server
+ rcl_ret_t rc = rclc_add_parameter(¶m_server, parameter_name, RCLC_PARAMETER_BOOL);
+
+ // Set parameter value (Triggers `on_parameter_changed` callback, if defined)
+ rc = rclc_parameter_set_bool(¶m_server, parameter_name, param_value);
+
+ // Get parameter value and store it in "param_value"
+ rc = rclc_parameter_get_bool(¶m_server, "param1", ¶m_value);
+
+ if (RCL_RET_OK != rc) {
+ ... // Handle error
+ return -1;
+ }
+ ```
+
+- Integer:
+ ```c
+ const char * parameter_name = "parameter_int";
+ int param_value = 100;
+
+ // Add parameter to the server
+ rcl_ret_t rc = rclc_add_parameter(¶m_server, parameter_name, RCLC_PARAMETER_INT);
+
+ // Set parameter value
+ rc = rclc_parameter_set_int(¶m_server, parameter_name, param_value);
+
+ // Get parameter value on param_value
+ rc = rclc_parameter_get_int(¶m_server, parameter_name, ¶m_value);
+ ```
+
+- Double:
+ ```c
+ const char * parameter_name = "parameter_double";
+ double param_value = 0.15;
+
+ // Add parameter to the server
+ rcl_ret_t rc = rclc_add_parameter(¶m_server, parameter_name, RCLC_PARAMETER_DOUBLE);
+
+ // Set parameter value
+ rc = rclc_parameter_set_double(¶m_server, parameter_name, param_value);
+
+ // Get parameter value on param_value
+ rc = rclc_parameter_get_double(¶m_server, parameter_name, ¶m_value);
+ ```
+
+*Max name size is controlled by the compile-time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.*
+
+### Cleaning up
+
+To destroy an initialized parameter server:
+
+```c
+// Delete parameter server
+rclc_parameter_server_fini(¶m_server, &node);
+```
+
+This will delete any automatically created infrastructure on the agent (if possible) and deallocate used memory on the parameter server side.
+
+## micro-ROS Foxy/Galactic
+
+### Initialization options
+
+ - Custom options:
+
+ The following options can be configured:
+ - notify_changed_over_dds: Publish parameter events to other ROS 2 nodes as well.
+ - max_params: Maximum number of parameters allowed on the `rclc_parameter_server_t` object.
+
+ ```c
+ // Parameter server object
+ rclc_parameter_server_t param_server;
+
+ // Initialize parameter server options
+ const rclc_parameter_options_t options = {
+ .notify_changed_over_dds = true,
+ .max_params = 4 };
+
+ // Initialize parameter server with configured options
+ rcl_ret_t rc = rclc_parameter_server_init_with_option(¶m_server, &node, &options);
+
+ if (RCL_RET_OK != rc) {
+ ... // Handle error
+ return -1;
+ }
+ ```
-When adding the parameter server to the executor, a callback can be configured.
-This callback will be executed after a parameter value is modified.
+### Callback
+
+When adding the parameter server to the executor, a callback could be configured.
+This callback would then be executed after a parameter value is modified.
A pointer to the changed parameter is passed as first and only argument. Example:
```c
void on_parameter_changed(Parameter * param)
{
+ if (param == NULL) {
+ printf("Callback error, parameter is NULL\n");
+ return;
+ }
+
// Get parameter name
printf("Parameter %s modified.", param->name.data);
@@ -118,7 +208,7 @@ void on_parameter_changed(Parameter * param)
printf("\n");
}
```
-Once the parameter server and the executor are initialized, the parameter server must be added to the executor in order to accept parameters commands from ROS2:
+Once the parameter server and the executor are initialized, the parameter server must be added to the executor in order to accept parameter commands from ROS 2:
```c
// Add parameter server to executor including defined callback
rc = rclc_executor_add_parameter_server(&executor, ¶m_server, on_parameter_changed);
@@ -130,67 +220,177 @@ Note that this callback is optional as its just an event information for the use
rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL);
```
-## Add a parameter
+## micro-ROS Humble
-micro-ROS parameter server supports the following parameter types:
+### Initialization options
-- Boolean:
- ```c
- const char * parameter_name = "parameter_bool";
- bool param_value = true;
+- Custom options:
- // Add parameter to the server
- rcl_ret_t rc = rclc_add_parameter(¶m_server, parameter_name, RCLC_PARAMETER_BOOL);
+ The following options can be configured:
+ - notify_changed_over_dds: Publish parameter events to other ROS 2 nodes as well.
+ - max_params: Maximum number of parameters allowed on the `rclc_parameter_server_t` object.
+ - allow_undeclared_parameters: Allows creation of parameters from external parameter clients. A new parameter will be created if a `set` operation is requested on a non-existing parameter.
+ - low_mem_mode: Reduces the memory used by the parameter server, functionality constrains are applied.
- // Set parameter value (Triggers parameter change callback)
- rc = rclc_parameter_set_bool(¶m_server, parameter_name, param_value);
+ ```c
+ // Parameter server object
+ rclc_parameter_server_t param_server;
- // Get parameter value on param_value
- rc = rclc_parameter_get_bool(¶m_server, "param1", ¶m_value);
+ // Initialize parameter server options
+ const rclc_parameter_options_t options = {
+ .notify_changed_over_dds = true,
+ .max_params = 4,
+ .allow_undeclared_parameters = true,
+ .low_mem_mode = false; };
+
+ // Initialize parameter server with configured options
+ rcl_ret_t rc = rclc_parameter_server_init_with_option(¶m_server, &node, &options);
if (RCL_RET_OK != rc) {
- ... // Handle error
- return -1;
+ ... // Handle error
+ return -1;
}
```
-- Integer:
- ```c
- const char * parameter_name = "parameter_int";
- int param_value = 100;
+- Low memory mode:
- // Add parameter to the server
- rcl_ret_t rc = rclc_add_parameter(¶m_server, parameter_name, RCLC_PARAMETER_INT);
+ This mode ports the parameter functionality to memory constrained devices. The following constrains are applied:
+ - Request size limited to one parameter on Set, Get, Get types and Describe services.
+ - List parameter request has no prefixes enabled nor depth.
+ - Parameter description strings not allowed, `rclc_add_parameter_description` is disabled.
- // Set parameter value
- rc = rclc_parameter_set_int(¶m_server, parameter_name, param_value);
+ Memory benchmark results on `STM32F4` for 7 parameters with `RCLC_PARAMETER_MAX_STRING_LENGTH = 50` and `notify_changed_over_dds = true`:
+ - Full mode: 11736 B
+ - Low memory mode: 4160 B
- // Get parameter value on param_value
- rc = rclc_parameter_get_int(¶m_server, parameter_name, ¶m_value);
- ```
+### Callback
-- Double:
- ```c
- const char * parameter_name = "parameter_double";
- double param_value = 0.15;
+When adding the parameter server to the executor, a callback could to be configured. This callback would then be executed on the following events:
+- Parameter value change: Internal and external parameter set on existing parameters.
+- Parameter creation: External parameter set on unexisting parameter if `allow_undeclared_parameters` is set.
+- Parameter delete: External parameter delete on existing parameter.
+- The user can allow or reject this operations using the `bool` return value.
- // Add parameter to the server
- rcl_ret_t rc = rclc_add_parameter(¶m_server, parameter_name, RCLC_PARAMETER_DOUBLE);
+Callback parameters:
+- `old_param`: Parameter actual value, `NULL` for new parameter request.
+- `new_param`: Parameter new value, `NULL` for parameter removal request.
+- `context`: User context, configured on `rclc_executor_add_parameter_server_with_context`.
- // Set parameter value
- rc = rclc_parameter_set_double(¶m_server, parameter_name, param_value);
+```c
+bool on_parameter_changed(const Parameter * old_param, const Parameter * new_param, void * context)
+{
+ (void) context;
+
+ if (old_param == NULL && new_param == NULL) {
+ printf("Callback error, both parameters are NULL\n");
+ return false;
+ }
+
+ if (old_param == NULL) {
+ printf("Creating new parameter %s\n", new_param->name.data);
+ } else if (new_param == NULL) {
+ printf("Deleting parameter %s\n", old_param->name.data);
+ } else {
+ printf("Parameter %s modified.", old_param->name.data);
+ switch (old_param->value.type) {
+ case RCLC_PARAMETER_BOOL:
+ printf(
+ " Old value: %d, New value: %d (bool)", old_param->value.bool_value,
+ new_param->value.bool_value);
+ break;
+ case RCLC_PARAMETER_INT:
+ printf(
+ " Old value: %ld, New value: %ld (int)", old_param->value.integer_value,
+ new_param->value.integer_value);
+ break;
+ case RCLC_PARAMETER_DOUBLE:
+ printf(
+ " Old value: %f, New value: %f (double)", old_param->value.double_value,
+ new_param->value.double_value);
+ break;
+ default:
+ break;
+ }
+ printf("\n");
+ }
- // Get parameter value on param_value
- rc = rclc_parameter_get_double(¶m_server, parameter_name, ¶m_value);
- ```
-
-## Cleaning up
+ return true;
+}
+```
-To destroy an initialized parameter server:
+Parameters modifications are disabled while the callback `on_parameter_changed` is executed, causing the following methods to return `RCLC_PARAMETER_DISABLED_ON_CALLBACK` if they are invoked:
+- rclc_add_parameter
+- rclc_delete_parameter
+- rclc_parameter_set_bool
+- rclc_parameter_set_int
+- rclc_parameter_set_double
+- rclc_set_parameter_read_only
+- rclc_add_parameter_constraint_double
+- rclc_add_parameter_constraint_integer
+
+Once the parameter server and the executor are initialized, the parameter server must be added to the executor in order to accept parameter commands from ROS 2:
+```c
+// Add parameter server to the executor including defined callback
+rc = rclc_executor_add_parameter_server(&executor, ¶m_server, on_parameter_changed);
+```
+
+Note that this callback is optional as its just an event information for the user. To use the parameter server without a callback:
+```c
+// Add parameter server to the executor without a callback
+rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL);
+```
+Configuration of the callback context:
```c
-// Delete parameter server
-rclc_parameter_server_fini(¶m_server, &node);
+// Add parameter server to the executor including defined callback and a context
+rc = rclc_executor_add_parameter_server_with_context(&executor, ¶m_server, on_parameter_changed, &context);
```
-This will delete any automatically created infrastructure on the agent (if possible) and deallocate used memory on the client side.
+### Add a parameter
+Parameters can also be created by external clients if the `allow_undeclared_parameters` flag is set.
+The client just needs to set a value on a non-existing parameter. Then this parameter will be created if the server has still capacity and the callback allows the operation.
+
+### Delete a parameter
+Parameters can be deleted by both, the parameter server and external clients:
+```c
+rclc_delete_parameter(¶m_server, "param2");
+```
+
+*For external delete requests, the server callback will be executed, allowing the node to reject the operation.*
+
+### Parameters description
+
+- Parameter description
+ Adds a description of a parameter and its constrains, which will be returned on a describe parameter requests:
+ ```c
+ rclc_add_parameter_description(¶m_server, "param2", "Second parameter", "Only even numbers");
+ ```
+
+ *The maximum string size is controlled by the compilation time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.*
+
+- Parameter constraints
+ Informative numeric constraints can be added to int and double parameters, returning this values on describe parameter requests:
+ - `from_value`: Start value for valid values, inclusive.
+ - `to_value`: End value for valid values, inclusive.
+ - `step`: Size of valid steps between the from and to bound.
+
+ ```c
+ int64_t int_from = 0;
+ int64_t int_to = 20;
+ uint64_t int_step = 2;
+ rclc_add_parameter_constraint_integer(¶m_server, "param2", int_from, int_to, int_step);
+
+ double double_from = -0.5;
+ double double_to = 0.5;
+ double double_step = 0.01;
+ rclc_add_parameter_constraint_double(¶m_server, "param3", double_from, double_to, double_step);
+ ```
+
+ *This constrains will not be applied by the parameter server, leaving values filtering to the user callback.*
+
+- Read-only parameters:
+ The new API offers a read-only flag. This flag blocks parameter changes from external clients, but allows changes on the server side:
+ ```c
+ bool read_only = true;
+ rclc_set_parameter_read_only(¶m_server, "param3", read_only);
+ ```