From 0ece0a258fa84066e14eb722ebd28c506740e0ab Mon Sep 17 00:00:00 2001 From: Daan Wijffels Date: Thu, 9 Jan 2025 14:00:45 +0000 Subject: [PATCH] Added unit tests for influx_line_protocol --- diagnostic_remote_logging/CMakeLists.txt | 9 ++ .../influx_line_protocol.hpp | 26 ++--- diagnostic_remote_logging/package.xml | 1 + .../test/influx_line_protocol.cpp | 107 ++++++++++++++++++ 4 files changed, 126 insertions(+), 17 deletions(-) create mode 100644 diagnostic_remote_logging/test/influx_line_protocol.cpp diff --git a/diagnostic_remote_logging/CMakeLists.txt b/diagnostic_remote_logging/CMakeLists.txt index a36c0a1d..f646b4e8 100644 --- a/diagnostic_remote_logging/CMakeLists.txt +++ b/diagnostic_remote_logging/CMakeLists.txt @@ -10,6 +10,7 @@ set(dependencies rclcpp rclcpp_components diagnostic_msgs + ament_cmake_gtest CURL ) @@ -44,4 +45,12 @@ install(TARGETS influx_component RUNTIME DESTINATION bin ) +if(BUILD_TESTING) + ament_add_gtest(unit_tests test/influx_line_protocol.cpp) + target_include_directories(unit_tests PRIVATE include) + target_link_libraries(unit_tests influx_component) + ament_target_dependencies(unit_tests ${dependencies}) +endif() + + ament_package() diff --git a/diagnostic_remote_logging/include/diagnostic_remote_logging/influx_line_protocol.hpp b/diagnostic_remote_logging/include/diagnostic_remote_logging/influx_line_protocol.hpp index a09c3e77..d7d5aa22 100644 --- a/diagnostic_remote_logging/include/diagnostic_remote_logging/influx_line_protocol.hpp +++ b/diagnostic_remote_logging/include/diagnostic_remote_logging/influx_line_protocol.hpp @@ -36,7 +36,6 @@ * \author Daan Wijfels */ - #pragma once #include "diagnostic_msgs/msg/diagnostic_array.hpp" @@ -44,20 +43,16 @@ std::string toInfluxTimestamp(const rclcpp::Time& time) { - double timestamp = time.seconds(); - // Extract the integer part (seconds) - uint64_t seconds = static_cast(timestamp); - // Extract the fractional part (nanoseconds) by subtracting the integer part and scaling - uint64_t nanoseconds = static_cast((timestamp - seconds) * 1e9); + uint64_t seconds = static_cast(time.seconds()); + uint64_t nanoseconds = static_cast(time.nanoseconds()) % 1000000000; - // Convert both parts to strings + // Convert to strings std::string secStr = std::to_string(seconds); std::string nanosecStr = std::to_string(nanoseconds); - // Ensure the nanoseconds part is zero-padded to 9 digits + // Zero-pad nanoseconds to 9 digits nanosecStr = std::string(9 - nanosecStr.length(), '0') + nanosecStr; - // Concatenate and return the result return secStr + nanosecStr; } @@ -73,13 +68,13 @@ std::string escapeSpace(const std::string& input) return result; } -bool is_number(const std::string& s) { - std::istringstream iss(s); - double d; - return iss >> std::noskipws >> d && iss.eof(); +bool is_number(const std::string& s) +{ + std::istringstream iss(s); + double d; + return iss >> std::noskipws >> d && iss.eof(); } - std::string formatValues(const std::vector& values) { std::string formatted; @@ -98,8 +93,6 @@ std::string formatValues(const std::vector& valu formatted += "\"" + kv.value + "\""; } formatted += ","; - - } if (!formatted.empty()) { formatted.pop_back(); // Remove the last comma @@ -163,4 +156,3 @@ std::string arrayToInfluxLineProtocol(const diagnostic_msgs::msg::DiagnosticArra return output; }; - diff --git a/diagnostic_remote_logging/package.xml b/diagnostic_remote_logging/package.xml index 981c4dcc..02a1737b 100644 --- a/diagnostic_remote_logging/package.xml +++ b/diagnostic_remote_logging/package.xml @@ -15,6 +15,7 @@ ament_lint_auto ament_lint_common + ament_cmake_gtest diff --git a/diagnostic_remote_logging/test/influx_line_protocol.cpp b/diagnostic_remote_logging/test/influx_line_protocol.cpp new file mode 100644 index 00000000..fd398e65 --- /dev/null +++ b/diagnostic_remote_logging/test/influx_line_protocol.cpp @@ -0,0 +1,107 @@ +#include "diagnostic_msgs/msg/diagnostic_array.hpp" +#include "diagnostic_msgs/msg/diagnostic_status.hpp" +#include "diagnostic_msgs/msg/key_value.hpp" +#include +#include + +// Include the functions to test +#include "diagnostic_remote_logging/influx_line_protocol.hpp" // Replace with the actual header file name + +diagnostic_msgs::msg::KeyValue createKeyValue(const std::string& key, const std::string& value) +{ + diagnostic_msgs::msg::KeyValue output; + output.key = key; + output.value = value; + return output; +} + +// Test toInfluxTimestamp +TEST(InfluxTimestampTests, CorrectConversion) +{ + rclcpp::Time time(1672531200, 123456789); // Example time + std::string expected = "1672531200123456789"; + EXPECT_EQ(toInfluxTimestamp(time), expected); +} + +// Test escapeSpace +TEST(EscapeSpaceTests, HandlesSpaces) +{ + EXPECT_EQ(escapeSpace("test string"), "test\\ string"); + EXPECT_EQ(escapeSpace("no_space"), "no_space"); + EXPECT_EQ(escapeSpace("multiple spaces here"), "multiple\\ spaces\\ here"); +} + +// Test is_number +TEST(IsNumberTests, ValidatesNumbers) +{ + EXPECT_TRUE(is_number("123")); + EXPECT_TRUE(is_number("123.456")); + EXPECT_TRUE(is_number("-123.456")); + EXPECT_FALSE(is_number("123abc")); + EXPECT_FALSE(is_number("abc123")); + EXPECT_FALSE(is_number("")); +} + +// Test formatValues +TEST(FormatValuesTests, FormatsKeyValuePairs) +{ + std::vector values; + values.push_back(createKeyValue("key1", "value")); + values.push_back(createKeyValue("key2", "42")); + values.push_back(createKeyValue("key3", "-3.14")); + values.push_back(createKeyValue("key with spaces", "value with spaces")); + + std::string expected = "key1=\"value\",key2=42,key3=-3.14,key\\ with\\ spaces=\"value with spaces\""; + EXPECT_EQ(formatValues(values), expected); +} + +// Test splitHardwareID +TEST(SplitHardwareIDTests, SplitsCorrectly) +{ + EXPECT_EQ(splitHardwareID("node_name"), std::make_pair(std::string("none"), std::string("node_name"))); + EXPECT_EQ(splitHardwareID("/ns/node_name"), std::make_pair(std::string("ns"), std::string("node_name"))); + EXPECT_EQ(splitHardwareID("/ns/prefix/node_name"), std::make_pair(std::string("ns"), std::string("prefix/node_name"))); +} + +// Test statusToInfluxLineProtocol +TEST(StatusToInfluxLineProtocolTests, FormatsCorrectly) +{ + diagnostic_msgs::msg::DiagnosticStatus status; + status.hardware_id = "/ns/node_name"; + status.level = 2; + status.message = "Test message"; + status.values.push_back(createKeyValue("key1", "value1")); + status.values.push_back(createKeyValue("key2", "42")); + + std::string expected = "node_name,ns=ns level=2,message=\"Test message\",key1=\"value1\",key2=42 1672531200123456789\n"; + std::string output; + statusToInfluxLineProtocol(output, status, "1672531200123456789"); + + EXPECT_EQ(output, expected); +} + +// Test arrayToInfluxLineProtocol +TEST(ArrayToInfluxLineProtocolTests, HandlesMultipleStatuses) +{ + auto diag_msg = std::make_shared(); + diag_msg->header.stamp = rclcpp::Time(1672531200, 123456789); + + diagnostic_msgs::msg::DiagnosticStatus status1; + status1.hardware_id = "/ns1/node1"; + status1.level = 1; + status1.message = "First status"; + status1.values.push_back(createKeyValue("keyA", "valueA")); + + diagnostic_msgs::msg::DiagnosticStatus status2; + status2.hardware_id = "node2"; + status2.level = 2; + status2.message = "Second status"; + status2.values.push_back(createKeyValue("keyB", "42")); + + diag_msg->status = {status1, status2}; + + std::string expected = "node1,ns=ns1 level=1,message=\"First status\",keyA=\"valueA\" 1672531200123456789\n" + "node2,ns=none level=2,message=\"Second status\",keyB=42 1672531200123456789\n"; + + EXPECT_EQ(arrayToInfluxLineProtocol(diag_msg), expected); +} \ No newline at end of file