From 0b579007c1f824c5e6802464c463c9cf0b62f37d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bekir=20Bostanc=C4=B1?= Date: Tue, 30 Jan 2024 08:29:38 +0000 Subject: [PATCH] fix: change all informations to information --- vda5050_connector/include/vda5050_connector/handler.hpp | 8 ++++---- .../adapter/handler_execution/handler_execution_test.cpp | 6 +++--- .../test/adapter/plugin_load/plugin_load_test.cpp | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/vda5050_connector/include/vda5050_connector/handler.hpp b/vda5050_connector/include/vda5050_connector/handler.hpp index 5378b83..c293f1c 100644 --- a/vda5050_connector/include/vda5050_connector/handler.hpp +++ b/vda5050_connector/include/vda5050_connector/handler.hpp @@ -97,13 +97,13 @@ class SafeState } /** - * @brief Add a new information msg into the informations array of the order state + * @brief Add a new information msg into the information array of the order state * Only one thread/writer can modify the order_state. */ void add_information(const vda5050_msgs::msg::Info & info) { std::unique_lock lock(mutex); - order_state_.informations.push_back(info); + order_state_.information.push_back(info); } /** @@ -127,14 +127,14 @@ class SafeState } /** - * @brief Clear the order state arrays (load, informations and errors). + * @brief Clear the order state arrays (load, information and errors). * Only one thread/writer can clear the order_state. */ void clear() { std::unique_lock lock(mutex); order_state_.loads.clear(); - order_state_.informations.clear(); + order_state_.information.clear(); order_state_.errors.clear(); } diff --git a/vda5050_connector/test/adapter/handler_execution/handler_execution_test.cpp b/vda5050_connector/test/adapter/handler_execution/handler_execution_test.cpp index 74ed3f9..06c1a7b 100644 --- a/vda5050_connector/test/adapter/handler_execution/handler_execution_test.cpp +++ b/vda5050_connector/test/adapter/handler_execution/handler_execution_test.cpp @@ -72,14 +72,14 @@ TEST_F(AdapterTest, HandlerExecution) // Check handlers could modify global current state on configure auto order_state = adapter_node->get_current_state(); - EXPECT_EQ(static_cast(order_state.informations.size()), 1); + EXPECT_EQ(static_cast(order_state.information.size()), 1); EXPECT_FLOAT_EQ(static_cast(order_state.battery_state.battery_charge), 100.0); // Check handlers could modify global current state on execute ASSERT_NO_THROW(adapter_node->call_update_current_state()); order_state = adapter_node->get_current_state(); - // Update current state should clear previous loads, error and informations - EXPECT_EQ(static_cast(order_state.informations.size()), 1); + // Update current state should clear previous loads, error and information + EXPECT_EQ(static_cast(order_state.information.size()), 1); EXPECT_FLOAT_EQ(static_cast(order_state.battery_state.battery_charge), 90.0); // Test vda action execute state machine: Transitions and call of state funcs diff --git a/vda5050_connector/test/adapter/plugin_load/plugin_load_test.cpp b/vda5050_connector/test/adapter/plugin_load/plugin_load_test.cpp index 755687e..b04a6e0 100644 --- a/vda5050_connector/test/adapter/plugin_load/plugin_load_test.cpp +++ b/vda5050_connector/test/adapter/plugin_load/plugin_load_test.cpp @@ -105,7 +105,7 @@ TEST_F(AdapterTest, HandlerLoadHandlers) // Check handlers could modify global current state on configure auto order_state = adapter_node->get_current_state(); - EXPECT_EQ(static_cast(order_state.informations.size()), 1); + EXPECT_EQ(static_cast(order_state.information.size()), 1); EXPECT_FLOAT_EQ(order_state.distance_since_last_node, 10.0); EXPECT_EQ(order_state.paused, true);