diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp index 63595fef985..27663c26123 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp @@ -210,24 +210,6 @@ inline std::chrono::milliseconds convertFromString(co return std::chrono::milliseconds(std::stoul(key.data())); } -/** - * @brief Parse XML string to std::set - * @param key XML string - * @return std::set - */ -template<> -inline std::set convertFromString(StringView key) -{ - // Real numbers separated by semicolons - auto parts = splitString(key, ';'); - - std::set set; - for (const auto part : parts) { - set.insert(convertFromString(part)); - } - return set; -} - /** * @brief Return parameter value from behavior tree node or ros2 parameter file. * @param node rclcpp::Node::SharedPtr diff --git a/nav2_behavior_tree/test/test_bt_utils.cpp b/nav2_behavior_tree/test/test_bt_utils.cpp index 8d68a5a1c79..8e28e29f362 100644 --- a/nav2_behavior_tree/test/test_bt_utils.cpp +++ b/nav2_behavior_tree/test/test_bt_utils.cpp @@ -16,7 +16,6 @@ #include #include #include -#include #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/quaternion.hpp" @@ -419,29 +418,6 @@ TEST(MillisecondsPortTest, test_correct_syntax) EXPECT_EQ(value.count(), 123); } -TEST(ErrorCodePortTest, test_correct_syntax) -{ - std::string xml_txt = - R"( - - - - - )"; - - BT::BehaviorTreeFactory factory; - factory.registerNodeType>>("ErrorCodePort"); - auto tree = factory.createTreeFromText(xml_txt); - - tree = factory.createTreeFromText(xml_txt); - std::set value; - tree.rootNode()->getInput("test", value); - - EXPECT_TRUE(value.find(100) != value.end()); - EXPECT_TRUE(value.find(204) != value.end()); - EXPECT_TRUE(value.find(212) != value.end()); -} - TEST(deconflictPortAndParamFrameTest, test_correct_syntax) { std::string xml_txt =