Skip to content

Commit 640f16c

Browse files
committed
feat(updater)!: allow user to set key of key-value pair
Signed-off-by: Bart Jimenez Vera <bjv@capra.ooo>
1 parent 1ec7462 commit 640f16c

7 files changed

Lines changed: 53 additions & 35 deletions

File tree

.github/workflows/ci.yml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,6 @@ jobs:
1717
include:
1818
- ros_distribution: "foxy"
1919
os: "ubuntu-20.04"
20-
- ros_distribution: "galactic"
21-
os: "ubuntu-20.04"
2220
- ros_distribution: "humble"
2321
os: "ubuntu-22.04"
2422
- ros_distribution: "rolling"

micro_ros_common_diagnostics/src/hwmonitor.c

Lines changed: 13 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,12 +20,22 @@
2020

2121
#include "micro_ros_diagnostic_updater/micro_ros_diagnostic_updater.h"
2222

23+
// Variable value set in main() if passed as argument
24+
uint16_t task_id = 0;
25+
2326
rcl_ret_t
24-
my_diagnostic_task(diagnostic_value_t * kv)
27+
my_diagnostic_task(
28+
diagnostic_value_t values[MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_VALUES_PER_TASK],
29+
uint8_t * number_of_values)
2530
{
31+
(void)number_of_values;
32+
*number_of_values = 1;
33+
34+
values[0].key = task_id;
35+
2636
// actual diagnostic task to be implemented
2737
rclc_diagnostic_value_set_level(
28-
kv,
38+
&values[0],
2939
micro_ros_diagnostic_msgs__msg__MicroROSDiagnosticStatus__STALE);
3040

3141
return RCL_RET_OK;
@@ -35,7 +45,6 @@ int main(int argc, const char * argv[])
3545
{
3646
uint16_t hardware_id = 0;
3747
uint16_t updater_id = 0;
38-
uint16_t task_id = 0;
3948
if (argc < 2) {
4049
printf("Need at least one argument: hardware ID. Optional: updater ID, task ID.\n");
4150
exit(1);
@@ -91,7 +100,7 @@ int main(int argc, const char * argv[])
91100
return -1;
92101
}
93102
diagnostic_task_t task;
94-
rc = rclc_diagnostic_task_init(&task, hardware_id, updater_id, task_id, &my_diagnostic_task);
103+
rc = rclc_diagnostic_task_init(&task, hardware_id, updater_id, &my_diagnostic_task);
95104
if (rc != RCL_RET_OK) {
96105
printf("Error in creating diagnostic task\n");
97106
return -1;

micro_ros_diagnostic_updater/example/example_processor_updater.c

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,14 +25,17 @@ static const int16_t PROCESSOR_ID = 17;
2525
// The hardware id
2626
static const int16_t PROCESSOR_SERIAL = 1001;
2727
// Task id
28-
static const int16_t PROCESSOR_TEMPERATURE_TASK_ID = 0;
28+
static const int16_t PROCESSOR_TEMPERATURE_KEY = 0;
2929
// Task id
30-
static const int16_t PROCESSOR_LOAD_TASK_ID = 1;
30+
static const int16_t PROCESSOR_LOAD_KEY = 1;
3131

3232
rcl_ret_t
3333
my_diagnostic_temperature(diagnostic_value_t * values, uint8_t * number_of_values)
3434
{
3535
*number_of_values = 1;
36+
37+
// Set the key to get translation
38+
values[0].key = PROCESSOR_TEMPERATURE_KEY;
3639
// Fake a temperature
3740
++my_diagnostic_temp;
3841
if (my_diagnostic_temp > 99) {
@@ -55,6 +58,9 @@ rcl_ret_t
5558
my_diagnostic_load(diagnostic_value_t * values, uint8_t * number_of_values)
5659
{
5760
*number_of_values = 1;
61+
62+
// Set the key to get translation
63+
values[0].key = PROCESSOR_LOAD_KEY;
5864
// Fake a processor load
5965
rclc_diagnostic_value_set_int(&values[0], my_diagnostic_temp / 2);
6066

@@ -111,15 +117,15 @@ int main(int argc, const char * argv[])
111117
}
112118
diagnostic_task_t temperature_task;
113119
rc = rclc_diagnostic_task_init(
114-
&temperature_task, PROCESSOR_SERIAL, PROCESSOR_ID, PROCESSOR_TEMPERATURE_TASK_ID,
120+
&temperature_task, PROCESSOR_SERIAL, PROCESSOR_ID,
115121
&my_diagnostic_temperature);
116122
if (rc != RCL_RET_OK) {
117123
printf("Error in creating diagnostic task\n");
118124
return -1;
119125
}
120126
diagnostic_task_t load_task;
121127
rc = rclc_diagnostic_task_init(
122-
&load_task, PROCESSOR_SERIAL, PROCESSOR_ID, PROCESSOR_LOAD_TASK_ID,
128+
&load_task, PROCESSOR_SERIAL, PROCESSOR_ID,
123129
&my_diagnostic_load);
124130
if (rc != RCL_RET_OK) {
125131
printf("Error in creating diagnostic website checker\n");

micro_ros_diagnostic_updater/example/example_website_checker.c

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -25,35 +25,43 @@ static int my_website_status = 0;
2525
// Hardware ID
2626
static const int16_t WEBSITE_SERIAL = 998;
2727
// Updater ID
28-
static const int16_t WEBSITE_ID = 0;
28+
static const uint16_t WEBSITE_ID = 0;
2929
// Task ID
30-
static const int16_t WEBSITE_STATUS_TASK_ID = 42;
30+
static const uint16_t WEBSITE_STATUS_TASK_ID = 42;
3131

3232

3333
rcl_ret_t
34-
my_diagnostic_website_check(diagnostic_value_t * kv)
34+
my_diagnostic_website_check(
35+
diagnostic_value_t values[MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_VALUES_PER_TASK],
36+
uint8_t * number_of_values)
3537
{
38+
// Cast to avoid warnings
39+
(void)number_of_values;
40+
*number_of_values = 1;
41+
3642
++my_diagnostic_status;
43+
44+
values[0].key = WEBSITE_STATUS_TASK_ID;
3745
if (my_diagnostic_status > 99) {
3846
my_diagnostic_status = 0;
3947
}
4048
if (my_diagnostic_status % 13 == 0) {
4149
my_website_status = 404;
4250
rclc_diagnostic_value_set_level(
43-
kv,
51+
&values[0],
4452
micro_ros_diagnostic_msgs__msg__MicroROSDiagnosticStatus__WARN);
4553
} else if (my_diagnostic_status % 17 == 0) {
4654
my_website_status = 500;
4755
rclc_diagnostic_value_set_level(
48-
kv,
56+
&values[0],
4957
micro_ros_diagnostic_msgs__msg__MicroROSDiagnosticStatus__ERROR);
5058
} else {
5159
my_website_status = 200;
5260
rclc_diagnostic_value_set_level(
53-
kv,
61+
&values[0],
5462
micro_ros_diagnostic_msgs__msg__MicroROSDiagnosticStatus__OK);
5563
}
56-
rclc_diagnostic_value_lookup(kv, my_website_status);
64+
rclc_diagnostic_value_lookup(&values[0], my_website_status);
5765

5866
return RCL_RET_OK;
5967
}
@@ -102,7 +110,7 @@ int main(int argc, const char * argv[])
102110
}
103111
diagnostic_task_t task;
104112
rc = rclc_diagnostic_task_init(
105-
&task, WEBSITE_SERIAL, WEBSITE_ID, WEBSITE_STATUS_TASK_ID,
113+
&task, WEBSITE_SERIAL, WEBSITE_ID,
106114
&my_diagnostic_website_check);
107115
if (rc != RCL_RET_OK) {
108116
printf("Error in creating diagnostic task\n");

micro_ros_diagnostic_updater/include/micro_ros_diagnostic_updater/micro_ros_diagnostic_updater.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,6 @@ typedef struct diagnostic_value_t
3636

3737
typedef struct diagnostic_task_t
3838
{
39-
int16_t id;
4039
uint8_t number_of_values;
4140
diagnostic_value_t values[MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_VALUES_PER_TASK];
4241
int16_t hardware_id;
@@ -72,7 +71,6 @@ rclc_diagnostic_task_init(
7271
diagnostic_task_t * task,
7372
int16_t hardware_id,
7473
int16_t updater_id,
75-
int16_t id,
7674
rcl_ret_t (* function)(
7775
diagnostic_value_t[MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_VALUES_PER_TASK],
7876
uint8_t * number_of_values));

micro_ros_diagnostic_updater/src/micro_ros_diagnostic_updater/micro_ros_diagnostic_updater.c

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,6 @@ rclc_diagnostic_task_init(
5353
diagnostic_task_t * task,
5454
int16_t hardware_id,
5555
int16_t updater_id,
56-
int16_t id,
5756
rcl_ret_t (* function)(
5857
diagnostic_value_t[MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_VALUES_PER_TASK],
5958
uint8_t * number_of_values))
@@ -63,7 +62,6 @@ rclc_diagnostic_task_init(
6362
RCL_CHECK_FOR_NULL_WITH_MSG(
6463
function, "function is a null pointer", return RCL_RET_INVALID_ARGUMENT);
6564

66-
task->id = id;
6765
task->function = function;
6866
task->updater_id = updater_id;
6967
task->hardware_id = hardware_id;
@@ -148,8 +146,7 @@ rclc_diagnostic_updater_add_task(
148146

149147
if (updater->num_tasks >= MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_TASKS_PER_UPDATER) {
150148
RCUTILS_LOG_ERROR(
151-
"Updater could not add task %d, already %d tasks added.",
152-
task->id,
149+
"Updater could not add task, already %d tasks added.",
153150
MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_TASKS_PER_UPDATER);
154151
return RCL_RET_ERROR;
155152
}
@@ -190,7 +187,7 @@ rclc_diagnostic_updater_update(
190187
for (uint8_t value_index = 0u; value_index < updater->tasks[i]->number_of_values;
191188
value_index++)
192189
{
193-
key_value.key = updater->tasks[i]->id;
190+
key_value.key = updater->tasks[i]->values[value_index].key;
194191
key_value.value_type = updater->tasks[i]->values[value_index].value_type;
195192
key_value.bool_value = updater->tasks[i]->values[value_index].bool_value;
196193
key_value.int_value = updater->tasks[i]->values[value_index].int_value;
@@ -205,13 +202,11 @@ rclc_diagnostic_updater_update(
205202
rcl_ret_t rc = rcl_publish(&updater->diag_pub, &updater->diag_status, NULL);
206203
if (rc == RCL_RET_OK) {
207204
RCUTILS_LOG_DEBUG(
208-
"Updater published value for '%d'.",
209-
updater->tasks[i]->id);
205+
"Updater %d published value for '%d'.", updater->id, i);
210206
}
211207
} else {
212208
RCUTILS_LOG_ERROR(
213-
"Updater could not update diagnostic task '%d'.",
214-
updater->tasks[i]->id);
209+
"Updater %d could not update diagnostic task '%d'.", updater->id, i);
215210
}
216211
}
217212

micro_ros_diagnostic_updater/test/test_diagnostic_updater.cpp

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,9 @@ static int diagnostic_mockup_counter_0 = 0;
2828
static int diagnostic_mockup_counter_1 = 0;
2929

3030
rcl_ret_t
31-
update_function_mockup_0(diagnostic_value_t * values, uint8_t * number_of_values)
31+
update_function_mockup_0(
32+
diagnostic_value_t values[MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_VALUES_PER_TASK],
33+
uint8_t * number_of_values)
3234
{
3335
++diagnostic_mockup_counter_0;
3436

@@ -43,7 +45,9 @@ update_function_mockup_0(diagnostic_value_t * values, uint8_t * number_of_values
4345
}
4446

4547
rcl_ret_t
46-
update_function_mockup_1(diagnostic_value_t * values, uint8_t * number_of_values)
48+
update_function_mockup_1(
49+
diagnostic_value_t values[MICRO_ROS_DIAGNOSTIC_UPDATER_MAX_VALUES_PER_TASK],
50+
uint8_t * number_of_values)
4751
{
4852
++diagnostic_mockup_counter_1;
4953

@@ -58,7 +62,7 @@ update_function_mockup_1(diagnostic_value_t * values, uint8_t * number_of_values
5862

5963
TEST(TestDiagnosticUpdater, create_diagnostic_task) {
6064
diagnostic_task_t task;
61-
rcl_ret_t rc = rclc_diagnostic_task_init(&task, 0, 0, 0, &update_function_mockup_0);
65+
rcl_ret_t rc = rclc_diagnostic_task_init(&task, 0, 0, &update_function_mockup_0);
6266
EXPECT_EQ(RCL_RET_OK, rc);
6367
}
6468

@@ -131,7 +135,7 @@ TEST(TestDiagnosticUpdater, updater_add_tasks) {
131135
EXPECT_EQ(RCL_RET_OK, rc);
132136

133137
diagnostic_task_t task;
134-
rc = rclc_diagnostic_task_init(&task, 17, 0, 0, &update_function_mockup_0);
138+
rc = rclc_diagnostic_task_init(&task, 17, 0, &update_function_mockup_0);
135139
EXPECT_EQ(RCL_RET_OK, rc);
136140

137141
rc = rclc_diagnostic_updater_add_task(&updater, &task);
@@ -171,11 +175,11 @@ TEST(TestDiagnosticUpdater, updater_update) {
171175
diagnostic_task_t task0, task1;
172176
rc = rclc_diagnostic_task_init(
173177
&task0,
174-
0, 0, 0,
178+
0, 0,
175179
&update_function_mockup_0);
176180
rc = rclc_diagnostic_task_init(
177181
&task1,
178-
0, 0, 1,
182+
0, 0,
179183
&update_function_mockup_1);
180184

181185
rc = rclc_diagnostic_updater_add_task(&updater, &task0);

0 commit comments

Comments
 (0)