From bac44c5e98f849896b95dc9a3d4c7500eeed1a63 Mon Sep 17 00:00:00 2001 From: acuadros95 Date: Tue, 5 Apr 2022 13:02:02 +0200 Subject: [PATCH 1/8] Doc update for parameters upgrade --- .../parameters/parameters.md | 323 ++++++++++++++---- 1 file changed, 254 insertions(+), 69 deletions(-) diff --git a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md index 71697853..bc18541e 100644 --- a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md +++ b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md @@ -9,13 +9,20 @@ ROS 2 parameters allow the user to create variables on a node and manipulate/rea 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 +micro-ROS parameters implementation has been upgraded in the latest micro-ROS Rolling distribution, two approaches are presented in this tutorial: micro-ROS Foxy/Galactic and micro-ROS Rolling and beyond: - [Initialization](#initialization) - [Memory requirements](#memory-requirements) -- [Callback](#callback) - [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 Rolling](#micro-ros-rolling) + - [Initialization options](#initialization-options-1) + - [Callback](#callback-1) + - [Delete a parameter](#delete-a-parameter) + - [Parameters description](#parameters-description) ## Initialization @@ -33,28 +40,6 @@ Note: micro-ROS parameter server is only supported on ROS 2 Galactic distributio } ``` -- 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; - } - ``` - ## 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: @@ -86,50 +71,6 @@ rc = rclc_executor_init( RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER, &allocator); ``` -## Callback - -When adding the parameter server to the executor, a callback can be configured. -This callback will 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) -{ - // Get parameter name - printf("Parameter %s modified.", param->name.data); - - // Get parameter type - switch (param->value.type) - { - // Get parameter value acording type - case RCLC_PARAMETER_BOOL: - printf(" New value: %d (bool)", param->value.bool_value); - break; - case RCLC_PARAMETER_INT: - printf(" New value: %ld (int)", param->value.integer_value); - break; - case RCLC_PARAMETER_DOUBLE: - printf(" New value: %f (double)", param->value.double_value); - break; - default: - break; - } - - 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: -```c -// Add parameter server to 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 executor without callback -rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); -``` - ## Add a parameter micro-ROS parameter server supports the following parameter types: @@ -183,7 +124,9 @@ micro-ROS parameter server supports the following parameter types: // Get parameter value on param_value rc = rclc_parameter_get_double(¶m_server, parameter_name, ¶m_value); ``` - + +*Max name size is controlled by the compilation time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.* + ## Cleaning up To destroy an initialized parameter server: @@ -194,3 +137,245 @@ 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 client side. + +## micro-ROS Foxy/Galactic + +### Initialization options + + - Custom options: + + The following options can be configured: + - notify_changed_over_dds: Publish parameters events to the rest of nodes. + - 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; + } + ``` + +### Callback + +When adding the parameter server to the executor, a callback can be configured. +This callback will 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) +{ + // Get parameter name + printf("Parameter %s modified.", param->name.data); + + // Get parameter type + switch (param->value.type) + { + // Get parameter value acording type + case RCLC_PARAMETER_BOOL: + printf(" New value: %d (bool)", param->value.bool_value); + break; + case RCLC_PARAMETER_INT: + printf(" New value: %ld (int)", param->value.integer_value); + break; + case RCLC_PARAMETER_DOUBLE: + printf(" New value: %f (double)", param->value.double_value); + break; + default: + break; + } + + 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: +```c +// Add parameter server to 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 executor without callback +rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); +``` + +## micro-ROS Rolling + +### Initialization options + +- Custom options: + + The following options can be configured: + - notify_changed_over_dds: Publish parameters events to the rest of nodes. + - max_params: Maximum number of parameters allowed on the `rclc_parameter_server_t` object. + - allow_undeclared_parameters: Allows creation of parameters from external parameters 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. + + ```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, + .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; + } + ``` + +- Low memory mode: + This mode ports the parameters functionality to memory constrained devices. The following constrains are applied: + - Request size limited to 1 parameter on Set, Get, Get types and Describe services. + - List parameters request has no prefixes enabled nor depth. + - Parameter description strings not allowed, `rclc_add_parameter_description` is disabled. + + Memory benchmark 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 + +### Callback + +When adding the parameter server to the executor, a callback can be configured. This callback will 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. + +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`. + +```c +bool on_parameter_changed(const Parameter * old_param, const Parameter * new_param, void * context) +{ +(void) context; + +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"); +} + +return true; +} +``` + +Parameters modifications are disabled while this callback is executed, causing this methods to return `RCLC_PARAMETER_DISABLED_ON_CALLBACK`: +- 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_constraints_double +- rclc_add_parameter_constraints_integer + + +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: +```c +// Add parameter server to 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 executor without callback +rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); +``` + +To configure the callback context: +```c +// Add parameter server to executor including defined callback and a context +rc = rclc_executor_add_parameter_server_with_context(&executor, ¶m_server, on_parameter_changed, &context); +``` + +### Delete a parameter +Parameters can be deleted both by the parameter server and external clients: +Example usage: +```c +rclc_delete_parameter(¶m_server, "param2"); +``` + +Note that for external delete requests the server callback will be executed, allowing the user to reject the operation. + +### Parameters description + +- Parameter description + Adds a description of a parameter and its constrains. This descriptors will be returned to describe parameters requests. + Example usage: + ```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 constrains + Informative numeric constrains can be added to int and double parameters, returning this values on describe parameters requests. + Note that this constrains will not be applied by the parameter server, leaving values filtering to the user callback. + + The following values can be configured: + - 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. + + Example usage: + ```c + int64_t int_from = 0; + int64_t int_to = 20; + uint64_t int_step = 2; + rclc_add_parameter_constraints_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_constraints_double(¶m_server, "param3", double_from, double_to, double_step); + ``` + +- 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. Example usage: + ```c + bool read_only = true; + rclc_set_parameter_read_only(¶m_server, "param3", read_only); + ``` \ No newline at end of file From 3768630bed4a835838189390ad500f8844403fec Mon Sep 17 00:00:00 2001 From: acuadros95 Date: Tue, 5 Apr 2022 14:40:48 +0200 Subject: [PATCH 2/8] Minor fix on parameters guide --- .../parameters/parameters.md | 186 +++++++++--------- 1 file changed, 98 insertions(+), 88 deletions(-) diff --git a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md index bc18541e..dfdfb1c6 100644 --- a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md +++ b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md @@ -5,26 +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) +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. micro-ROS parameters implementation has been upgraded in the latest micro-ROS Rolling distribution, two approaches are presented in this tutorial: micro-ROS Foxy/Galactic and micro-ROS Rolling and beyond: -- [Initialization](#initialization) -- [Memory requirements](#memory-requirements) -- [Add a parameter](#add-a-parameter) -- [Cleaning up](#cleaning-up) +- [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 Rolling](#micro-ros-rolling) - [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) -## Initialization +## General implementation +### Initialization - Default initialization: ```c @@ -35,16 +38,16 @@ micro-ROS parameters implementation has been upgraded in the latest micro-ROS Ro rcl_ret_t rc = rclc_parameter_server_init_default(¶m_server, &node); 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: -```json +```yaml # colcon.meta example with memory requirements to use a parameter server { "names": { @@ -71,7 +74,7 @@ rc = rclc_executor_init( RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER, &allocator); ``` -## Add a parameter +### Add a parameter micro-ROS parameter server supports the following parameter types: @@ -90,8 +93,8 @@ micro-ROS parameter server supports the following parameter types: rc = rclc_parameter_get_bool(¶m_server, "param1", ¶m_value); if (RCL_RET_OK != rc) { - ... // Handle error - return -1; + ... // Handle error + return -1; } ``` @@ -127,7 +130,7 @@ micro-ROS parameter server supports the following parameter types: *Max name size is controlled by the compilation time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.* -## Cleaning up +### Cleaning up To destroy an initialized parameter server: @@ -161,8 +164,8 @@ This will delete any automatically created infrastructure on the agent (if possi 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; } ``` @@ -220,29 +223,30 @@ rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); - notify_changed_over_dds: Publish parameters events to the rest of nodes. - max_params: Maximum number of parameters allowed on the `rclc_parameter_server_t` object. - allow_undeclared_parameters: Allows creation of parameters from external parameters 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. + - low_mem_mode: Reduces the memory used by the parameter server, functionality constrains are applied. - ```c - // Parameter server object - rclc_parameter_server_t param_server; + ```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, - .allow_undeclared_parameters = true, - .low_mem_mode = false; }; + // 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); + // 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; - } - ``` + if (RCL_RET_OK != rc) { + ... // Handle error + return -1; + } + ``` - Low memory mode: + This mode ports the parameters functionality to memory constrained devices. The following constrains are applied: - Request size limited to 1 parameter on Set, Get, Get types and Describe services. - List parameters request has no prefixes enabled nor depth. @@ -268,37 +272,44 @@ Callback parameters: ```c bool on_parameter_changed(const Parameter * old_param, const Parameter * new_param, void * context) { -(void) context; - -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; + (void) context; + + if (old_param == NULL) + { + printf("Creating new parameter %s\n", new_param->name.data); } - printf("\n"); -} + 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; + } -return true; + printf("\n"); + } + + return true; } ``` @@ -312,7 +323,6 @@ Parameters modifications are disabled while this callback is executed, causing t - rclc_add_parameter_constraints_double - rclc_add_parameter_constraints_integer - 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: ```c // Add parameter server to executor including defined callback @@ -331,51 +341,51 @@ To configure the callback context: rc = rclc_executor_add_parameter_server_with_context(&executor, ¶m_server, on_parameter_changed, &context); ``` +### Add a parameter +Parameters can also be created by external clients if `allow_undeclared_parameters` flag is set. +They client just needs to set a value on a unexisting parameter, the parameter will be created if the server is not full and the callback allows the operation. + ### Delete a parameter Parameters can be deleted both by the parameter server and external clients: -Example usage: ```c rclc_delete_parameter(¶m_server, "param2"); ``` -Note that for external delete requests the server callback will be executed, allowing the user to reject the operation. +*For external delete requests the server callback will be executed, allowing the user to reject the operation.* ### Parameters description -- Parameter description - Adds a description of a parameter and its constrains. This descriptors will be returned to describe parameters requests. - Example usage: +- Parameter description + Adds a description of a parameter and its constrains, which will be returned on a describe parameters 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 constrains - Informative numeric constrains can be added to int and double parameters, returning this values on describe parameters requests. - Note that this constrains will not be applied by the parameter server, leaving values filtering to the user callback. - - The following values can be configured: +- Parameter constrains + Informative numeric constrains can be added to int and double parameters, returning this values on describe parameters 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. - Example usage: - ```c - int64_t int_from = 0; - int64_t int_to = 20; - uint64_t int_step = 2; - rclc_add_parameter_constraints_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_constraints_double(¶m_server, "param3", double_from, double_to, double_step); - ``` + ```c + int64_t int_from = 0; + int64_t int_to = 20; + uint64_t int_step = 2; + rclc_add_parameter_constraints_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_constraints_double(¶m_server, "param3", double_from, double_to, double_step); + ``` -- 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. Example usage: + *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); - ``` \ No newline at end of file + ``` From 20b408c4220689f05673b9ec533eaf52da9e7f8b Mon Sep 17 00:00:00 2001 From: acuadros95 Date: Tue, 5 Apr 2022 15:31:20 +0200 Subject: [PATCH 3/8] Add CAPRA logo --- .../overview/users_and_clients/images/capra.png | Bin 0 -> 6629 bytes _docs/overview/users_and_clients/index.md | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 _docs/overview/users_and_clients/images/capra.png 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 0000000000000000000000000000000000000000..02f03ecc01c48ad374af5959b3dd2cca94518d13 GIT binary patch literal 6629 zcmZ`;Ra6uJ(_KPJ8pS1-5Rj7Yln{^(0jUL+Sh~AWmhKQ(T4Yg>T6&QbmhO}g6j-`T z^7nuH&UeoDFmvZ&p61M)bLZYz9W50SB3dE<06?Oqs-*W1*Zw~UaQ*092>Sx00`DFk0OI}tAzy%~A3!1iOC|&$8+3hh8@B`PJ>pu9=DX z-vFhE&D|rwbGPo1MJ>lH0KYq{er#T4&no8NQ{!+Y#I zZ)0FNwE$XIzzat+|6Blnu(e+yKs6K~8k$nvBn(bN4KDG&gVCr5$yz7KL$d)Sj;={a z0HKqPQ;LX5x|Ul$;F&#-SwwDSn^L|04FCXaQB!(l;Gef2;uMrSc-hD=*wZDDP?Q}> zpuo@c{DniV@E6~?{4lue-F+d3CMi;2dE3fu>R0a_3oX6-GIF-EVH1j&Dp8K7<~6B@ zPW;c}>SZgMdiC;8>44*9`;DAxV=suvL9#|zDnXQvO<3BA=}wylQIWXP4wk%BVzVdv zE~G$k=$uZ*>f-J^5Q>jySQDol!#s8xZZ$6^lVt_K5&yx01}9QaLDa9Dj_R48$KZ#j z4Rv1V!z2K!6cMS#45ovHeJlxX=)o3(POE7C5GJJz}L7emYk^<&q!zp_iV zYNPNb4coi(ptl#Z*Lj9Z5iQ8$O)%MrxCr8kZ;lfPB&aD8+FUoU6K@=ri;UXS(ImuX zE%A`2IUz@Ow)`XottT?eB{a47Ajx$L=8aD?ilMpAOE(a+T>}cH^2%{M+-tR(ciyP? zQ6gT;ISoK>R2IW?S$0ID2`x`@zK&$$9$%ywy2#N^l?0R#wd)wyW>U~6uyq;!r|_kb zXHiSlXQhzLik5uzLha`Vdkwj^Kisj*3outBeM6mI{>QX6zut!$%WFcsXUa-t6{gx$a%D{gVf8HvSM3F3J zFY!t>Fy5iL*M2RiKAv>MKL++msEr5_&m6(2jP=7L_&kocp+f!xE1QVqk4yY`SsV#G zHlpApX5nCYk!>X$zkWoYro!JWOgDrofOI+LGjj?QLS62pP4s*CPk1hB3DSQ9-(!`Z zeT9xEd{2e5jSc9k{X!2DX3r`9o4fjf0nVYk*khm@O;hrmYkDYsehY7J5)$y5e8lg> zY0s3zCY$mJ(ARlviTSH>vDJtM9dWH-W$ufyA)Foy-9nqmqcA=Yd{o~XV>}EbGCqKo z&Yl6z=-p$OEuBC*?Iklblz=Tr_RWwHqW6nN_AuQ^e}OD;$Q+0`=wbY%NIb#+qrrNQ zE1`@+8(vqmOYHArlJP5+M)A2TUh;vVP&X1AlKTmQ{Mz;2plJHQT0LGO z70Z$9peky=%^{JwiO8`ywcpBw(|K>yHFXqm07E8?RA9fQ+kYs9H6D?Z3*A8xZv#y( z%S2%OZ+r(xX@gn{bfw|F(mv(#9}v}LrhCg%@~PLa6N!xYizyESfwf(7wyJIZ_5=1m z+lq#It30wo!t>|SI+T;)xF^Jx(vJ<|Sas#OV0ki_3mQFblc$#cLB=9)pYRcz&>qz_ z1vC7GKTYR@tEz}+S2=~q=q?(*CdiaUjgcq$t}zb6P3-WE(h?|$_ffGAw5@l`B9!w( z{Zg8x=szTf}E)xFx)9<37)wIVgK( zna-TBKDkjIF?aVRxec0I^9OAq@4FN)UP)|{yf1yxFERWSPwq zuWNkP%Eo8KUP3$gHmma!6uBaz1|WGaYHjj(%bzMiPf(4pM8$7pAE;;gxZ8iO;u3ac z=fNbBYUd>)(EJs=vG|6y$kWMTKp%!3)OK*MfXk^Ef-DZu)D)FJ9e(&l{d$mBYMGn)6VEOWhpV2d#Ro^WgkUY`OEq^~qw|L1Jb<#bI^j(1M0R>^Bo12T_+DGG=*l?FFmjp%#Nm~0=pc-{*T*irtreMA zXFG2vcR1`n@IDgnRk*PSoomLAXr99jNMAZU3_kpdn4X<3jCPzpw=54h0Q;7pJiKqm zW5{)%Z$^Ye5obnYuxGyRB=Ms0_?a!s;+3T|;i2yJ%qd(LT74t94}ev})QN~yOkljwtHWPAz^i39o13I}e1x)rDQ zF@?8l>eo^SGe|=sLDu{>SnLmQ7qY-k#8yz->k_f+ZpBC{0hR8@*e6l&hH?vETSfWP8E*2*UKg80@{!3+A`=KXq=V`qxY%2%h@OwM}xGhT{0KRScSXSIB^QIzqa;s zbRI|lqd@W5TK%GRE*o(*B%0VBDVn83mvZA&L77M5or)d{Vtdgo&G07c=5O%x3GcOr z%B1Ue!Pz#lb;mt0IU7}mZ`_=v$lI*P%x%(p4QuMSXOnyMxJDW=*g^j_&~Yjj zn;O~U?f=&!cdQ^C@-1PLGQuY;sU_*37<}~?*UVK5v(N0 z8J?qOiR(s3Seq>~zcGlXc(VM;uMp>F&`bAxmLwkhQj~f>MH3s(3D1dHZK$Ns!54Ph zY*~DP;{8LOr&q46fONrIOwLId#X_WB>R)k&dz&9bGAhEo!TX%yv6rg8T=X^!92B4i zjPRdVjZ@MlDTQC5hleU7JT!W7B}TB<;jNydMd6h!~uB7;ECUNN0;$;tVg5esjO1BK0lkYf1L`#BaO^TC0kwv(MUcR6>YHh#ZRqZ6368Bj&aR)@FR$GeonNOUts~(cozGju@ zktV+VEM78g6#C^;#8~b9YY8dWnqOV{L7qF@t94YmQ@P{|*IEt(LDCSKSC&pUd03)- zGjXK!tqv!6s$r+v>S7Nb1w z(xn-@d{-PHWqJ^5$Qw8-n6H4{&TdWbz2{O}c!uIQvRT3!d)eTibTkQp7V$5D_M`9Y zje|>1bF=826z34>Aves? zcQl_1OU{mpjV!cMW&MzB>}#vKvcuCbclLuk0sK==g6O$zJLmEXZqjcNqSWuNWq+|N z=HY6UkhBRDnwJiYf5EhsXlybqIfH6A?KmP*(C+^pZ52&>A2@0T3vE4fsEzMh!ya(K zK54MIwpV1a@5=#n=Sccel0P>60$yyW*s-$Q-^|1NJ-l)(-rYjfi_ey38zKY9&i54d+bEcTFA<=@6*ZNno)t`o<`1;>E68}`dbzRIv4Kg&(lfSLk*ar|+T*)2L zQXM=FbO^g*>nBRGYf#}ULC?oF4IWsqaz6T&aAREQ41cvWWARk)CVV+a@-Ry=r8oK|D&2#t(7jSOGqM%`h^aQ|4Tb{ z{_EM3=V2zT)VAL5Nb4OdoO}wN8_jL#$!XrUYV>uVx0U0(cP}9@rrwsWGVJU4KKICs z!CmS@Jsvr}cRorL!A~N(tkmfxiBki9`*{NZyQvqGJ*=MkB(!wIC-kiU?)K%tp>e;X z0EBNjn6Wf!FL^F%`oNHPG{@xm;pR3gYWp4C6g>I;$#^2g%R$&&dn)Ic=4hR!rJ={F zo%cth`QbH<)KfGBq=0^TCf%%%G1*LC#h_4hvwP0)`FUvRFJ}#n3GmBmTxx#jh5^BF zd@YAlxy|a8fc69@|GRIr9*<`)d~OjL zHq^7I(S2pEoiP>SXP8DYzIa~+Z2zx?lcXi5*JE{vVSmavk;|&Wy*~dWIO^aD!mwG#mDr4oXoZc zS^wpHEd-7Wp}zj(YWT=BigAPZ8P1%~zWC??$%AXwPqW1_fxOT>IT}^)m6nUFrw3cy zW;-*ADm*P|10F2R3nXfN856UGZ8E9eC&5~SOO+`wqBfzr9=iq2zyH2sc1^pR`~>`x zPvy(=31wv8Gw_s)+a$@eo6t%ybunh&$4g=F8!;HIG**`7<8uY^X z_y!i9gUejU0bbRVjwLg7J{wEY+9MBfJFTveV@dNda6w#=nQ6YH9k|1m*vp88X4T8& zsAsOMtf9IKNqpFc51dS!-P&<71Wy79Z&c>+zpCj2!Y9p5`(FTwif!N7zSU_W%&gKh zwQW)J^LR6bWhc0%VZOR4!q#WBjZo&_^9RF!J+;}dI}v8Mar*f(ad)#_cS9j4skmM; z#FtPWJhHcoGtu&$H8?n%*9m)@+Pry?=0stcfyP)hzrGsoJVB&#xlLO5q?I)0E#ykz zZV|rTL^iw`+aeaZXer+8UleBE-cs!JHZTrBECpIcBG)J1Hb%{VpV3UQ0oP>P{|>Zo z?JP()Rp3YLevHp!p0deSew_UEZ?#!<`%8XIcI46|$_d*}vh<}}{_gpHK!{PIU*VnV zO46F}nCFTp@v{6zEd@T%B$Gy_cW}%i@JHzguNhCIKFb*!Emx6z$vdK5*wg;S1ZHxw ze>avVG0<*~vbn0*E690;dtYrXHRz*C!sqrT9`*AT8xDAk=m6;2Zf7y|=y^#3stGXTjJhN(5+IWvfLvlv#W|KU1kMKs)T2JmQ1ZLIV{^f$c_UV8 zR3CK6weLpkD!VCiQhXbc{)L!bUUklB_eH8Cp(ux~2}_7Vc(AHI&8RcKwAg97o1C_P z*6c%qWZBmemHKo~qrbTd(fRKJ>>B*UXlNh%tu4FTr3R^r)!tsX@csSpL6B~t=J_#{ z^UqyK8**Necw6~axz@}`ooU$h$th5Uq86ShhSXr@AdG9JEx<_CQF$wu$&>f2Qt!y>LXl=v zl&iW_Zj`j0(mUvzN<%+08|tp_)7McpNQkemc9mOnl%dLf15q_!`fDO*Tu`_3akOxe znxT)(Q1fK(lPMTVlMnNujI*u-MUV=vxaa&u;(OTU25Jvz;IQ-Cs~#=-+#Yh8TU*2q zGeC7XB}Q7-R}iV)Tv*v;g7i!{IA&BP4?^;FIpm1yUg%S8l)@2F%hw?s=Qk(STXxk8 zeltXqsMclIOEo*S-g)!ASsiJcLnq(Ety5ai`p4W~3o@K+ivtVGYNl~1KCMDDLvB3r z>UvFWY+-5-G6Nl4)g$Q&TlIm1i$f;r%F+WH!_|e}+K$B9T3il(hg=g{f`9$ykeEE- zgPm!&1;~~4dcE(ZxB8>GoszE+A&&~y9bGN5icu#Ega&ED2| literal 0 HcmV?d00001 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 From f025d5f1a2109ba16b00a468aaf88462a66ae7b3 Mon Sep 17 00:00:00 2001 From: Antonio Cuadros <49162117+Acuadros95@users.noreply.github.com> Date: Wed, 6 Apr 2022 09:42:13 +0200 Subject: [PATCH 4/8] Apply suggestions from code review Co-authored-by: Pablo Garrido --- _docs/tutorials/programming_rcl_rclc/parameters/parameters.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md index dfdfb1c6..7e2fa13c 100644 --- a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md +++ b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md @@ -45,9 +45,9 @@ micro-ROS parameters implementation has been upgraded in the latest micro-ROS Ro ### 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 5 services and an optional publisher, this needs to be taken into account on the `rmw_microxredds` package memory configuration: -```yaml +```json # colcon.meta example with memory requirements to use a parameter server { "names": { From e9e989738010a6bcd45eda6c3bd826afed036d26 Mon Sep 17 00:00:00 2001 From: acuadros95 Date: Wed, 6 Apr 2022 09:44:17 +0200 Subject: [PATCH 5/8] Prepare for Humble --- .../tutorials/programming_rcl_rclc/parameters/parameters.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md index 7e2fa13c..14ecf4ed 100644 --- a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md +++ b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md @@ -9,7 +9,7 @@ ROS 2 parameters allow the user to create variables on a node and manipulate/rea 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. -micro-ROS parameters implementation has been upgraded in the latest micro-ROS Rolling distribution, two approaches are presented in this tutorial: micro-ROS Foxy/Galactic and micro-ROS Rolling and beyond: +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) @@ -19,7 +19,7 @@ micro-ROS parameters implementation has been upgraded in the latest micro-ROS Ro - [micro-ROS Foxy/Galactic](#micro-ros-foxygalactic) - [Initialization options](#initialization-options) - [Callback](#callback) -- [micro-ROS Rolling](#micro-ros-rolling) +- [micro-ROS Humble](#micro-ros-humble) - [Initialization options](#initialization-options-1) - [Callback](#callback-1) - [Add a parameter](#add-a-parameter-1) @@ -213,7 +213,7 @@ 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); ``` -## micro-ROS Rolling +## micro-ROS Humble ### Initialization options From 926814b31ee3158dcf96aa6a3b845d4cec27111d Mon Sep 17 00:00:00 2001 From: acuadros95 Date: Thu, 7 Apr 2022 12:24:38 +0200 Subject: [PATCH 6/8] Apply changes from code review --- .../parameters/parameters.md | 115 ++++++++---------- 1 file changed, 53 insertions(+), 62 deletions(-) diff --git a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md index 14ecf4ed..011e4e9e 100644 --- a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md +++ b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md @@ -5,7 +5,7 @@ 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). +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 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. @@ -45,7 +45,7 @@ micro-ROS parameters implementation has been upgraded in the latest micro-ROS Hu ### 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-microxredds` package memory configuration: ```json # colcon.meta example with memory requirements to use a parameter server @@ -64,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 rclc Executor handles required for a parameter server: ```c // Executor init example with the minimum RCLC executor handles required @@ -128,7 +128,7 @@ micro-ROS parameter server supports the following parameter types: rc = rclc_parameter_get_double(¶m_server, parameter_name, ¶m_value); ``` -*Max name size is controlled by the compilation time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.* +*Max name size is controlled by the compile-time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.* ### Cleaning up @@ -240,8 +240,8 @@ rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); 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; } ``` @@ -265,65 +265,56 @@ When adding the parameter server to the executor, a callback can be configured. - The user can allow or reject this operations using the `bool` return value. 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`. +- `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`. ```c bool on_parameter_changed(const Parameter * old_param, const Parameter * new_param, void * context) { - (void) context; - - if (old_param == NULL) - { - printf("Creating new parameter %s\n", new_param->name.data); + (void) context; + 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; } - 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"); - } - - return true; + printf("\n"); + } + return true; } ``` -Parameters modifications are disabled while this callback is executed, causing this methods to return `RCLC_PARAMETER_DISABLED_ON_CALLBACK`: +Parameters modifications are disabled while this callback 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_constraints_double -- rclc_add_parameter_constraints_integer +- 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 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 parameters 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); @@ -343,15 +334,15 @@ rc = rclc_executor_add_parameter_server_with_context(&executor, ¶m_server, o ### Add a parameter Parameters can also be created by external clients if `allow_undeclared_parameters` flag is set. -They client just needs to set a value on a unexisting parameter, the parameter will be created if the server is not full and the callback allows the operation. +The client just needs to set a value on a unexisting parameter, the parameter will be created if the server is not full and the callback allows the operation. ### Delete a parameter -Parameters can be deleted both by the parameter server and external clients: +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 user to reject the operation.* +*For external delete requests, the server callback will be executed, allowing the node to reject the operation.* ### Parameters description @@ -363,28 +354,28 @@ rclc_delete_parameter(¶m_server, "param2"); *The maximum string size is controlled by the compilation time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.* -- Parameter constrains - Informative numeric constrains can be added to int and double parameters, returning this values on describe parameters 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. +- Parameter constraints + Informative numeric constraints can be added to int and double parameters, returning this values on describe parameters 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_constraints_integer(¶m_server, "param2", int_from, int_to, int_step); + 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_constraints_double(¶m_server, "param3", double_from, double_to, double_step); + 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: +- 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); From 56f425ac98f327714955b8edaf6c399b21dbfbc6 Mon Sep 17 00:00:00 2001 From: acuadros95 Date: Wed, 13 Apr 2022 12:08:14 +0200 Subject: [PATCH 7/8] Apply review comments --- .../parameters/parameters.md | 76 +++++++++++-------- 1 file changed, 45 insertions(+), 31 deletions(-) diff --git a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md index 011e4e9e..517317c3 100644 --- a/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md +++ b/_docs/tutorials/programming_rcl_rclc/parameters/parameters.md @@ -7,7 +7,7 @@ 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 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 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. +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: @@ -45,9 +45,9 @@ micro-ROS parameters implementation has been upgraded in the latest micro-ROS Hu ### Memory requirements -The parameter server uses five services and an optional publisher. These need 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": { @@ -64,7 +64,7 @@ The parameter server uses five services and an optional publisher. These need to } ``` -At 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 @@ -74,9 +74,11 @@ rc = rclc_executor_init( RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER, &allocator); ``` +*Humble: the variable is `RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER` has been renamed to `RCLC_EXECUTOR_PARAMETER_SERVER_HANDLES`.* + ### Add a parameter -micro-ROS parameter server supports the following parameter types: +The micro-ROS parameter server supports the following parameter types: - Boolean: ```c @@ -86,10 +88,10 @@ micro-ROS parameter server supports the following parameter types: // Add parameter to the server rcl_ret_t rc = rclc_add_parameter(¶m_server, parameter_name, RCLC_PARAMETER_BOOL); - // Set parameter value (Triggers parameter change callback) + // Set parameter value (Triggers `on_parameter_changed` callback, if defined) rc = rclc_parameter_set_bool(¶m_server, parameter_name, param_value); - // Get parameter value on 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) { @@ -139,7 +141,7 @@ To destroy an initialized 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 client side. +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 @@ -148,7 +150,7 @@ This will delete any automatically created infrastructure on the agent (if possi - Custom options: The following options can be configured: - - notify_changed_over_dds: Publish parameters events to the rest of nodes. + - 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 @@ -171,13 +173,18 @@ This will delete any automatically created infrastructure on the agent (if possi ### Callback -When adding the parameter server to the executor, a callback can be configured. -This callback will be executed after a parameter value is modified. +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); @@ -201,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); @@ -220,9 +227,9 @@ rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); - Custom options: The following options can be configured: - - notify_changed_over_dds: Publish parameters events to the rest of nodes. + - 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 parameters clients. A new parameter will be created if a `set` operation is requested on a non-existing parameter. + - 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. ```c @@ -240,25 +247,25 @@ rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); 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; } ``` - Low memory mode: - This mode ports the parameters functionality to memory constrained devices. The following constrains are applied: - - Request size limited to 1 parameter on Set, Get, Get types and Describe services. - - List parameters request has no prefixes enabled nor depth. + 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. - Memory benchmark on `STM32F4` for 7 parameters with `RCLC_PARAMETER_MAX_STRING_LENGTH = 50` and `notify_changed_over_dds = true`: + 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 ### Callback -When adding the parameter server to the executor, a callback can be configured. This callback will be executed on the following events: +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. @@ -273,6 +280,12 @@ Callback parameters: 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) { @@ -300,11 +313,12 @@ bool on_parameter_changed(const Parameter * old_param, const Parameter * new_par } printf("\n"); } + return true; } ``` -Parameters modifications are disabled while this callback is executed, causing the following methods to return `RCLC_PARAMETER_DISABLED_ON_CALLBACK` if they are invoked: +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 @@ -314,27 +328,27 @@ Parameters modifications are disabled while this callback is executed, causing t - 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 parameters commands from ROS 2: +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 +// 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 executor without callback +// Add parameter server to the executor without a callback rc = rclc_executor_add_parameter_server(&executor, ¶m_server, NULL); ``` -To configure the callback context: +Configuration of the callback context: ```c -// Add parameter server to executor including defined callback and a context +// 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); ``` ### Add a parameter -Parameters can also be created by external clients if `allow_undeclared_parameters` flag is set. -The client just needs to set a value on a unexisting parameter, the parameter will be created if the server is not full and the callback allows the operation. +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: @@ -347,7 +361,7 @@ rclc_delete_parameter(¶m_server, "param2"); ### Parameters description - Parameter description - Adds a description of a parameter and its constrains, which will be returned on a describe parameters requests: + 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"); ``` @@ -355,7 +369,7 @@ rclc_delete_parameter(¶m_server, "param2"); *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 parameters requests: + 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. From 3c3153d7196bea9462f6f5f991c757bcd47e0248 Mon Sep 17 00:00:00 2001 From: acuadros95 Date: Wed, 13 Apr 2022 12:16:10 +0200 Subject: [PATCH 8/8] Fix zephyr docs link --- _docs/concepts/rtos/comparison/index.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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 |