Skip to content

Commit 13577e7

Browse files
Acuadros95mergify-bot
authored andcommitted
Fix parameter tests timeout (#283)
* Add sleep on parameter event match * Reset global values for gtest_repeat * Fix var name (cherry picked from commit 65b1164)
1 parent 3a1bb2a commit 13577e7

File tree

1 file changed

+22
-6
lines changed

1 file changed

+22
-6
lines changed

rclc_parameter/test/rclc_parameter/test_parameter.cpp

Lines changed: 22 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,8 @@ using namespace std::chrono_literals;
3030

3131
// #include "parameter_client.hpp"
3232

33-
static int callcack_calls = 0;
34-
static rclc_parameter_type_t expected_type;
33+
static int callbacks_calls = 0;
34+
static rclc_parameter_type_t expected_type = RCLC_PARAMETER_NOT_SET;
3535
static union {
3636
bool bool_value;
3737
int64_t integer_value;
@@ -40,7 +40,7 @@ static union {
4040

4141
void on_parameter_changed(Parameter * param)
4242
{
43-
callcack_calls++;
43+
callbacks_calls++;
4444
ASSERT_EQ(expected_type, param->value.type);
4545
switch (param->value.type) {
4646
case RCLC_PARAMETER_BOOL:
@@ -58,8 +58,14 @@ void on_parameter_changed(Parameter * param)
5858
}
5959

6060
TEST(Test, rclc_node_init_default) {
61+
auto default_spin_timeout = std::chrono::duration<int64_t, std::milli>(5000);
6162
std::string node_name("test_node");
6263

64+
// Reset global tests values
65+
expected_type = RCLC_PARAMETER_NOT_SET;
66+
expected_value.bool_value = false;
67+
callbacks_calls = 0;
68+
6369
// Create auxiliar RCLCPP node
6470
rclcpp::init(0, NULL);
6571
auto param_client_node = std::make_shared<rclcpp::Node>("param_aux_client");
@@ -161,7 +167,7 @@ TEST(Test, rclc_node_init_default) {
161167
rclc_parameter_get_double(&param_server, "param3", &param3);
162168
ASSERT_EQ(param3, 0.01);
163169

164-
ASSERT_EQ(callcack_calls, 3);
170+
ASSERT_EQ(callbacks_calls, 3);
165171

166172
// Spin RCLC parameter server in a thread
167173
bool spin = true;
@@ -173,8 +179,11 @@ TEST(Test, rclc_node_init_default) {
173179
}
174180
);
175181

182+
// Wait for parameter server
183+
ASSERT_TRUE(parameters_client->wait_for_service(default_spin_timeout));
184+
176185
// Use auxiliar RCLCPP node for check
177-
auto list_params = parameters_client->list_parameters({}, 10);
186+
auto list_params = parameters_client->list_parameters({}, 10, default_spin_timeout);
178187
ASSERT_EQ(list_params.names.size(), 4u);
179188
for (auto & name : list_params.names) {
180189
std::vector<std::string>::iterator it;
@@ -241,11 +250,18 @@ TEST(Test, rclc_node_init_default) {
241250
promise->set_value();
242251
});
243252

253+
// Sleep for pub/sub match
254+
std::this_thread::sleep_for(500ms);
255+
244256
expected_type = RCLC_PARAMETER_BOOL;
245257
expected_value.double_value = false;
246258
rclc_parameter_set_bool(&param_server, "param1", false);
247259

248-
rclcpp::spin_until_future_complete(param_client_node, future.share());
260+
ASSERT_EQ(
261+
rclcpp::spin_until_future_complete(
262+
param_client_node, future.share(),
263+
default_spin_timeout),
264+
rclcpp::FutureReturnCode::SUCCESS);
249265

250266
ASSERT_EQ(on_parameter_calls, 1u);
251267

0 commit comments

Comments
 (0)