Skip to content

Commit

Permalink
Added unit tests for influx_line_protocol
Browse files Browse the repository at this point in the history
  • Loading branch information
Daan Wijffels committed Jan 9, 2025
1 parent 3c26580 commit 0ece0a2
Show file tree
Hide file tree
Showing 4 changed files with 126 additions and 17 deletions.
9 changes: 9 additions & 0 deletions diagnostic_remote_logging/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ set(dependencies
rclcpp
rclcpp_components
diagnostic_msgs
ament_cmake_gtest
CURL
)

Expand Down Expand Up @@ -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()
Original file line number Diff line number Diff line change
Expand Up @@ -36,28 +36,23 @@
* \author Daan Wijfels
*/


#pragma once

#include "diagnostic_msgs/msg/diagnostic_array.hpp"
#include "rclcpp/rclcpp.hpp"

std::string toInfluxTimestamp(const rclcpp::Time& time)
{
double timestamp = time.seconds();
// Extract the integer part (seconds)
uint64_t seconds = static_cast<uint64_t>(timestamp);
// Extract the fractional part (nanoseconds) by subtracting the integer part and scaling
uint64_t nanoseconds = static_cast<uint64_t>((timestamp - seconds) * 1e9);
uint64_t seconds = static_cast<uint64_t>(time.seconds());
uint64_t nanoseconds = static_cast<uint64_t>(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;
}

Expand All @@ -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<diagnostic_msgs::msg::KeyValue>& values)
{
std::string formatted;
Expand All @@ -98,8 +93,6 @@ std::string formatValues(const std::vector<diagnostic_msgs::msg::KeyValue>& valu
formatted += "\"" + kv.value + "\"";
}
formatted += ",";


}
if (!formatted.empty()) {
formatted.pop_back(); // Remove the last comma
Expand Down Expand Up @@ -163,4 +156,3 @@ std::string arrayToInfluxLineProtocol(const diagnostic_msgs::msg::DiagnosticArra

return output;
};

1 change: 1 addition & 0 deletions diagnostic_remote_logging/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_cmake_gtest</test_depend>


<export>
Expand Down
107 changes: 107 additions & 0 deletions diagnostic_remote_logging/test/influx_line_protocol.cpp
Original file line number Diff line number Diff line change
@@ -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 <gtest/gtest.h>
#include <rclcpp/rclcpp.hpp>

// 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<diagnostic_msgs::msg::KeyValue> 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<diagnostic_msgs::msg::DiagnosticArray>();
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);
}

0 comments on commit 0ece0a2

Please sign in to comment.