Skip to content

Commit 9e4fc05

Browse files
Acuadros95pablogs9ralph-langeJanStaschulat
authored
Upgrade parameters (#274)
* Initial parameters upgrade * Fix memory init/fini * Delete update * Fix name on describe service * Fix var name * Update parameter example * Fix add parameter undeclared * Update test cases * Uncrustify and lint tests * Update tests teardown * Update tests and add low mem mode * Update example with new API * Uncrustify * Fix low mem fini * Add sleep for event pubsub match * Update notify_changed_over_dds * Update string init and deleted event pub * Disable set API on callback * Aux param review (#275) * Update Signed-off-by: Pablo Garrido <[email protected]> * Fix typos Co-authored-by: acuadros95 <[email protected]> * Fix int tests types * Update readme * Minor readme fix * Apply suggestions from code review Co-authored-by: Ralph Lange <[email protected]> * Apply suggestions from code review * Fix example * Requested changes * Apply suggestions from code review Co-authored-by: Jan Staschulat <[email protected]> * Add NULL checks * Apply review comments * Apply review comments * Fix line break * Add test cases Co-authored-by: Pablo Garrido <[email protected]> Co-authored-by: Ralph Lange <[email protected]> Co-authored-by: Jan Staschulat <[email protected]>
1 parent 09de417 commit 9e4fc05

File tree

8 files changed

+2716
-368
lines changed

8 files changed

+2716
-368
lines changed

Diff for: README.md

+3-2
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,12 @@
11
# The rclc repository
2-
This repository provides the rclc package, which complements the [ROS Client Support Library (rcl)](https://github.com/ros2/rcl/) to make up a complete ROS 2 client library for the C programming language. That is, rclc does not add a new layer of types on top of rcl (like rclcpp and rclpy do) but only provides convenience functions that ease the programming with the rcl types. New types are introduced only for concepts that are missing in rcl, most important an Executor and a Lifecycle Node.
2+
This repository provides the rclc package, which complements the [ROS Client Support Library (rcl)](https://github.com/ros2/rcl/) to make up a complete ROS 2 client library for the C programming language. That is, rclc does not add a new layer of types on top of rcl (like rclcpp and rclpy do) but only provides convenience functions that ease the programming with the rcl types. New types are introduced only for concepts that are missing in rcl, most important an Executor, Lifecycle Node and the Parameter server.
33

4-
In detail, this repository contains three packages:
4+
In detail, this repository contains four packages:
55

66
- [rclc](rclc/) provides the mentioned convenience functions for creating instances of publishers, subscriptions, nodes, etc. with the corresponding [rcl types](https://github.com/ros2/rcl/tree/master/rcl/include/rcl). Furthermore, it provides the rclc Executor for C, analogously to rclcpp's [Executor class](https://github.com/ros2/rclcpp/blob/master/rclcpp/include/rclcpp/executor.hpp) for C++. A key feature compared to the rclcpp Executor is that it includes features for implementing deterministic timing behavior.
77
- [rclc_lifecycle](rclc_lifecycle/) introduces an rclc Lifecycle Node, bundling an rcl Node and the [lifecycle state machine](http://design.ros2.org/articles/node_lifecycle.html) from the [rcl_lifecycle package](https://github.com/ros2/rcl/tree/master/rcl_lifecycle).
88
- [rclc_examples](rclc_examples/) provides small examples for the use of the convenience functions and the rclc Executor, as well as a small example for the use of the rclc Lifecycle Node.
9+
- [rclc_parameter](rclc_parameter/) provides convenience functions for creating parameter server instances with full ROS2 parameters client compatibility.
910

1011
Technical information on the interfaces and the usage of these packages is given in the README.md files in the corresponding subfolders.
1112

Diff for: rclc_examples/src/example_parameter_server.c

+44-16
Original file line numberDiff line numberDiff line change
@@ -36,23 +36,44 @@ void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
3636
rclc_parameter_set_int(&param_server, "param2", value);
3737
}
3838

39-
void on_parameter_changed(Parameter * param)
39+
bool on_parameter_changed(const Parameter * old_param, const Parameter * new_param, void * context)
4040
{
41-
printf("Parameter %s modified.", param->name.data);
42-
switch (param->value.type) {
43-
case RCLC_PARAMETER_BOOL:
44-
printf(" New value: %d (bool)", param->value.bool_value);
45-
break;
46-
case RCLC_PARAMETER_INT:
47-
printf(" New value: %ld (int)", param->value.integer_value);
48-
break;
49-
case RCLC_PARAMETER_DOUBLE:
50-
printf(" New value: %f (double)", param->value.double_value);
51-
break;
52-
default:
53-
break;
41+
(void) context;
42+
43+
if (old_param == NULL && new_param == NULL) {
44+
printf("Callback error, both parameters are NULL\n");
45+
return false;
46+
}
47+
48+
if (old_param == NULL) {
49+
printf("Creating new parameter %s\n", new_param->name.data);
50+
} else if (new_param == NULL) {
51+
printf("Deleting parameter %s\n", old_param->name.data);
52+
} else {
53+
printf("Parameter %s modified.", old_param->name.data);
54+
switch (old_param->value.type) {
55+
case RCLC_PARAMETER_BOOL:
56+
printf(
57+
" Old value: %d, New value: %d (bool)", old_param->value.bool_value,
58+
new_param->value.bool_value);
59+
break;
60+
case RCLC_PARAMETER_INT:
61+
printf(
62+
" Old value: %ld, New value: %ld (int)", old_param->value.integer_value,
63+
new_param->value.integer_value);
64+
break;
65+
case RCLC_PARAMETER_DOUBLE:
66+
printf(
67+
" Old value: %f, New value: %f (double)", old_param->value.double_value,
68+
new_param->value.double_value);
69+
break;
70+
default:
71+
break;
72+
}
73+
printf("\n");
5474
}
55-
printf("\n");
75+
76+
return true;
5677
}
5778

5879
int main()
@@ -82,7 +103,7 @@ int main()
82103
// Create executor
83104
rclc_executor_t executor;
84105
rclc_executor_init(
85-
&executor, &support.context, RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER + 1,
106+
&executor, &support.context, RCLC_EXECUTOR_PARAMETER_SERVER_HANDLES + 1,
86107
&allocator);
87108
rclc_executor_add_parameter_server(&executor, &param_server, on_parameter_changed);
88109
rclc_executor_add_timer(&executor, &timer);
@@ -96,6 +117,13 @@ int main()
96117
rclc_parameter_set_int(&param_server, "param2", 10);
97118
rclc_parameter_set_double(&param_server, "param3", 0.01);
98119

120+
// Add parameters constraints
121+
rclc_add_parameter_description(&param_server, "param2", "Second parameter", "Only even numbers");
122+
rclc_add_parameter_constraint_integer(&param_server, "param2", -10, 120, 2);
123+
124+
rclc_add_parameter_description(&param_server, "param3", "Third parameter", "");
125+
rclc_set_parameter_read_only(&param_server, "param3", true);
126+
99127
bool param1;
100128
int64_t param2;
101129
double param3;

Diff for: rclc_parameter/README.md

+297
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,297 @@
1+
# The rclc parameter package
2+
3+
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)
4+
5+
This package provides the rclc API with parameter server instances with full ROS 2 parameter client compatibility. A parameter client has not been implemented for rclc (yet).
6+
Ready to use code examples related to this tutorial can be found in [`rclc/rclc_examples/src/example_parameter_server.c`](../rclc_examples/src/example_parameter_server.c).
7+
8+
## Table of contents
9+
* [Initialization](#initialization)
10+
* [Memory requirements](#memory-requirements)
11+
* [Callback](#callback)
12+
* [Add a parameter](#add-a-parameter)
13+
* [Delete a parameter](#delete-a-parameter)
14+
* [Parameter description](#parameter-description)
15+
* [Cleaning up](#cleaning-up)
16+
17+
## Initialization
18+
19+
- Default initialization:
20+
```c
21+
// Parameter server object
22+
rclc_parameter_server_t param_server;
23+
// Initialize parameter server with default configuration
24+
rcl_ret_t rc = rclc_parameter_server_init_default(&param_server, &node);
25+
26+
if (RCL_RET_OK != rc) {
27+
... // Handle error
28+
return -1;
29+
}
30+
```
31+
32+
- Custom options:
33+
34+
The following options can be configured:
35+
- notify_changed_over_dds: Publish parameter events to other ROS 2 nodes as well.
36+
- max_params: Maximum number of parameters allowed on the `rclc_parameter_server_t` object.
37+
- 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.
38+
- low_mem_mode: Reduces the memory used by the parameter server, functionality constrains are applied.
39+
40+
```c
41+
// Parameter server object
42+
rclc_parameter_server_t param_server;
43+
44+
// Initialize parameter server options
45+
const rclc_parameter_options_t options = {
46+
.notify_changed_over_dds = true,
47+
.max_params = 4,
48+
.allow_undeclared_parameters = true,
49+
.low_mem_mode = false; };
50+
51+
// Initialize parameter server with configured options
52+
rcl_ret_t rc = rclc_parameter_server_init_with_option(&param_server, &node, &options);
53+
if (RCL_RET_OK != rc) {
54+
... // Handle error
55+
return -1;
56+
}
57+
```
58+
59+
- Low memory mode:
60+
61+
This mode ports the parameter functionality to memory constrained devices. The following constrains are applied:
62+
- Request size limited to one parameter on Set, Get, Get types and Describe services.
63+
- List parameter request has no prefixes enabled nor depth.
64+
- Parameter description strings not allowed, `rclc_add_parameter_description` is disabled.
65+
66+
Memory benchmark results on `STM32F4` for 7 parameters with `RCLC_PARAMETER_MAX_STRING_LENGTH = 50` and `notify_changed_over_dds = true`:
67+
- Full mode: 11736 B
68+
- Low memory mode: 4160 B
69+
70+
## Memory requirements
71+
72+
The parameter server uses five services and an optional publisher. These need to be taken into account on the `rmw-microxrcedds` package memory configuration:
73+
74+
```yaml
75+
# colcon.meta example with memory requirements to use a parameter server
76+
{
77+
"names": {
78+
"rmw_microxrcedds": {
79+
"cmake-args": [
80+
"-DRMW_UXRCE_MAX_NODES=1",
81+
"-DRMW_UXRCE_MAX_PUBLISHERS=1",
82+
"-DRMW_UXRCE_MAX_SUBSCRIPTIONS=0",
83+
"-DRMW_UXRCE_MAX_SERVICES=5",
84+
"-DRMW_UXRCE_MAX_CLIENTS=0"
85+
]
86+
}
87+
}
88+
}
89+
```
90+
91+
At runtime, the variable `RCLC_EXECUTOR_PARAMETER_SERVER_HANDLES` defines the necessary number of handles required by a parameter server for the rclc Executor:
92+
93+
```c
94+
// Executor init example with the minimum RCLC executor handles required
95+
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
96+
rc = rclc_executor_init(
97+
&executor, &support.context,
98+
RCLC_EXECUTOR_PARAMETER_SERVER_HANDLES, &allocator);
99+
```
100+
101+
## Callback
102+
103+
When adding the parameter server to the executor, a callback could to be configured. This callback would then be executed on the following events:
104+
- Parameter value change: Internal and external parameter set on existing parameters.
105+
- Parameter creation: External parameter set on unexisting parameter if `allow_undeclared_parameters` is set.
106+
- Parameter delete: External parameter delete on existing parameter.
107+
- The user can allow or reject this operations using the `bool` return value.
108+
109+
Callback parameters:
110+
- `old_param`: Parameter actual value, `NULL` for new parameter request.
111+
- `new_param`: Parameter new value, `NULL` for parameter removal request.
112+
- `context`: User context, configured on `rclc_executor_add_parameter_server_with_context`.
113+
114+
```c
115+
bool on_parameter_changed(const Parameter * old_param, const Parameter * new_param, void * context)
116+
{
117+
(void) context;
118+
119+
if (old_param == NULL && new_param == NULL) {
120+
printf("Callback error, both parameters are NULL\n");
121+
return false;
122+
}
123+
124+
if (old_param == NULL) {
125+
printf("Creating new parameter %s\n", new_param->name.data);
126+
} else if (new_param == NULL) {
127+
printf("Deleting parameter %s\n", old_param->name.data);
128+
} else {
129+
printf("Parameter %s modified.", old_param->name.data);
130+
switch (old_param->value.type) {
131+
case RCLC_PARAMETER_BOOL:
132+
printf(
133+
" Old value: %d, New value: %d (bool)", old_param->value.bool_value,
134+
new_param->value.bool_value);
135+
break;
136+
case RCLC_PARAMETER_INT:
137+
printf(
138+
" Old value: %ld, New value: %ld (int)", old_param->value.integer_value,
139+
new_param->value.integer_value);
140+
break;
141+
case RCLC_PARAMETER_DOUBLE:
142+
printf(
143+
" Old value: %f, New value: %f (double)", old_param->value.double_value,
144+
new_param->value.double_value);
145+
break;
146+
default:
147+
break;
148+
}
149+
printf("\n");
150+
}
151+
152+
return true;
153+
}
154+
```
155+
156+
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:
157+
- rclc_add_parameter
158+
- rclc_delete_parameter
159+
- rclc_parameter_set_bool
160+
- rclc_parameter_set_int
161+
- rclc_parameter_set_double
162+
- rclc_set_parameter_read_only
163+
- rclc_add_parameter_constraint_double
164+
- rclc_add_parameter_constraint_integer
165+
166+
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:
167+
```c
168+
// Add parameter server to the executor including defined callback
169+
rc = rclc_executor_add_parameter_server(&executor, &param_server, on_parameter_changed);
170+
```
171+
172+
Note that this callback is optional as its just an event information for the user. To use the parameter server without a callback:
173+
```c
174+
// Add parameter server to the executor without a callback
175+
rc = rclc_executor_add_parameter_server(&executor, &param_server, NULL);
176+
```
177+
178+
Configuration of the callback context:
179+
```c
180+
// Add parameter server to the executor including defined callback and a context
181+
rc = rclc_executor_add_parameter_server_with_context(&executor, &param_server, on_parameter_changed, &context);
182+
```
183+
184+
## Add a parameter
185+
186+
The micro-ROS parameter server supports the following parameter types:
187+
188+
- Boolean:
189+
```c
190+
const char * parameter_name = "parameter_bool";
191+
bool param_value = true;
192+
193+
// Add parameter to the server
194+
rcl_ret_t rc = rclc_add_parameter(&param_server, parameter_name, RCLC_PARAMETER_BOOL);
195+
196+
// Set parameter value (Triggers `on_parameter_changed` callback, if defined)
197+
rc = rclc_parameter_set_bool(&param_server, parameter_name, param_value);
198+
199+
// Get parameter value and store it in "param_value"
200+
rc = rclc_parameter_get_bool(&param_server, "param1", &param_value);
201+
202+
if (RCL_RET_OK != rc) {
203+
... // Handle error
204+
return -1;
205+
}
206+
```
207+
208+
- Integer:
209+
```c
210+
const char * parameter_name = "parameter_int";
211+
int param_value = 100;
212+
213+
// Add parameter to the server
214+
rcl_ret_t rc = rclc_add_parameter(&param_server, parameter_name, RCLC_PARAMETER_INT);
215+
216+
// Set parameter value
217+
rc = rclc_parameter_set_int(&param_server, parameter_name, param_value);
218+
219+
// Get parameter value on param_value
220+
rc = rclc_parameter_get_int(&param_server, parameter_name, &param_value);
221+
```
222+
223+
- Double:
224+
```c
225+
const char * parameter_name = "parameter_double";
226+
double param_value = 0.15;
227+
228+
// Add parameter to the server
229+
rcl_ret_t rc = rclc_add_parameter(&param_server, parameter_name, RCLC_PARAMETER_DOUBLE);
230+
231+
// Set parameter value
232+
rc = rclc_parameter_set_double(&param_server, parameter_name, param_value);
233+
234+
// Get parameter value on param_value
235+
rc = rclc_parameter_get_double(&param_server, parameter_name, &param_value);
236+
```
237+
238+
Parameters can also be created by external clients if the `allow_undeclared_parameters` flag is set.
239+
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.
240+
241+
*Max name size is controlled by the compile-time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.*
242+
243+
## Delete a parameter
244+
Parameters can be deleted by both, the parameter server and external clients:
245+
```c
246+
rclc_delete_parameter(&param_server, "param2");
247+
```
248+
249+
Note that for external delete requests, the server callback will be executed, allowing the node to reject the operation.
250+
251+
## Parameter description
252+
253+
- Parameter description
254+
Adds a description of a parameter and its constrains, which will be returned on a describe parameter requests:
255+
```c
256+
rclc_add_parameter_description(&param_server, "param2", "Second parameter", "Only even numbers");
257+
```
258+
259+
*The maximum string size is controlled by the compilation time option `RCLC_PARAMETER_MAX_STRING_LENGTH`, default value is 50.*
260+
261+
- Parameter constraints
262+
Informative numeric constraints can be added to int and double parameters, returning this values on describe parameter requests:
263+
- `from_value`: Start value for valid values, inclusive.
264+
- `to_value`: End value for valid values, inclusive.
265+
- `step`: Size of valid steps between the from and to bound.
266+
267+
```c
268+
int64_t int_from = 0;
269+
int64_t int_to = 20;
270+
uint64_t int_step = 2;
271+
rclc_add_parameter_constraint_integer(&param_server, "param2", int_from, int_to, int_step);
272+
273+
double double_from = -0.5;
274+
double double_to = 0.5;
275+
double double_step = 0.01;
276+
rclc_add_parameter_constraint_double(&param_server, "param3", double_from, double_to, double_step);
277+
```
278+
279+
*This constrains will not be applied by the parameter server, leaving values filtering to the user callback.*
280+
281+
- Read-only parameters:
282+
The new API offers a read-only flag. This flag blocks parameter changes from external clients, but allows changes on the server side:
283+
```c
284+
bool read_only = true;
285+
rclc_set_parameter_read_only(&param_server, "param3", read_only);
286+
```
287+
288+
## Cleaning up
289+
290+
To destroy an initialized parameter server:
291+
292+
```c
293+
// Delete parameter server
294+
rclc_parameter_server_fini(&param_server, &node);
295+
```
296+
297+
This will delete any automatically created infrastructure on the agent (if possible) and deallocate used memory on the parameter server side.

0 commit comments

Comments
 (0)