Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
81 changes: 81 additions & 0 deletions nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "geometry_msgs/msg/quaternion.hpp"
#include "nav_msgs/msg/path.hpp"
#include "nav_msgs/msg/goals.hpp"
#include "nav2_msgs/msg/waypoint_status.hpp"

namespace BT
{
Expand Down Expand Up @@ -241,6 +242,86 @@
}
}

/**
* @brief Parse XML string to nav2_msgs::msg::WaypointStatus
* @param key XML string
* @return nav2_msgs::msg::WaypointStatus
*/
template<>
inline nav2_msgs::msg::WaypointStatus convertFromString(const StringView key)
{
// if string starts with "json:{", try to parse it as json
if (StartWith(key, "json:")) {
auto new_key = key;
new_key.remove_prefix(5);
return convertFromJSON<nav2_msgs::msg::WaypointStatus>(new_key);
}

auto parts = BT::splitString(key, ';');
if (parts.size() != 13) {
throw std::runtime_error("invalid number of fields for WaypointStatus attribute)");
} else {
nav2_msgs::msg::WaypointStatus waypoint_status;
waypoint_status.waypoint_status = BT::convertFromString<uint8_t>(parts[0]);
waypoint_status.waypoint_index = BT::convertFromString<uint32_t>(parts[1]);
waypoint_status.waypoint_pose.header.stamp =
rclcpp::Time(BT::convertFromString<int64_t>(parts[2]));
waypoint_status.waypoint_pose.header.frame_id = BT::convertFromString<std::string>(parts[3]);
waypoint_status.waypoint_pose.pose.position.x = BT::convertFromString<double>(parts[4]);
waypoint_status.waypoint_pose.pose.position.y = BT::convertFromString<double>(parts[5]);
waypoint_status.waypoint_pose.pose.position.z = BT::convertFromString<double>(parts[6]);
waypoint_status.waypoint_pose.pose.orientation.x = BT::convertFromString<double>(parts[7]);
waypoint_status.waypoint_pose.pose.orientation.y = BT::convertFromString<double>(parts[8]);
waypoint_status.waypoint_pose.pose.orientation.z = BT::convertFromString<double>(parts[9]);
waypoint_status.waypoint_pose.pose.orientation.w = BT::convertFromString<double>(parts[10]);
waypoint_status.error_code = BT::convertFromString<uint16_t>(parts[11]);
waypoint_status.error_msg = BT::convertFromString<std::string>(parts[12]);
return waypoint_status;
}
}

/**
* @brief Parse XML string to nav2_msgs::msg::WaypointStatus
* @param key XML string
* @return nav2_msgs::msg::WaypointStatus
*/
template<>
inline std::vector<nav2_msgs::msg::WaypointStatus> convertFromString(const StringView key)
{
// if string starts with "json:{", try to parse it as json
if (StartWith(key, "json:")) {
auto new_key = key;

Check warning on line 293 in nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp

View check run for this annotation

Codecov / codecov/patch

nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp#L293

Added line #L293 was not covered by tests
new_key.remove_prefix(5);
return convertFromJSON<std::vector<nav2_msgs::msg::WaypointStatus>>(new_key);

Check warning on line 295 in nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp

View check run for this annotation

Codecov / codecov/patch

nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp#L295

Added line #L295 was not covered by tests
}

auto parts = BT::splitString(key, ';');
if (parts.size() % 13 != 0) {
throw std::runtime_error("invalid number of fields for std::vector<WaypointStatus> attribute)");
} else {
std::vector<nav2_msgs::msg::WaypointStatus> wp_status_vector;
for (size_t i = 0; i < parts.size(); i += 13) {
nav2_msgs::msg::WaypointStatus wp_status;
wp_status.waypoint_status = BT::convertFromString<uint8_t>(parts[i]);
wp_status.waypoint_index = BT::convertFromString<uint32_t>(parts[i + 1]);
wp_status.waypoint_pose.header.stamp =
rclcpp::Time(BT::convertFromString<int64_t>(parts[i + 2]));
wp_status.waypoint_pose.header.frame_id = BT::convertFromString<std::string>(parts[i + 3]);
wp_status.waypoint_pose.pose.position.x = BT::convertFromString<double>(parts[i + 4]);
wp_status.waypoint_pose.pose.position.y = BT::convertFromString<double>(parts[i + 5]);
wp_status.waypoint_pose.pose.position.z = BT::convertFromString<double>(parts[i + 6]);
wp_status.waypoint_pose.pose.orientation.x = BT::convertFromString<double>(parts[i + 7]);
wp_status.waypoint_pose.pose.orientation.y = BT::convertFromString<double>(parts[i + 8]);
wp_status.waypoint_pose.pose.orientation.z = BT::convertFromString<double>(parts[i + 9]);
wp_status.waypoint_pose.pose.orientation.w = BT::convertFromString<double>(parts[i + 10]);
wp_status.error_code = BT::convertFromString<uint16_t>(parts[i + 11]);
wp_status.error_msg = BT::convertFromString<std::string>(parts[i + 12]);
wp_status_vector.push_back(wp_status);
}
return wp_status_vector;
}
}

/**
* @brief Parse XML string to std::chrono::milliseconds
* @param key XML string
Expand Down
126 changes: 126 additions & 0 deletions nav2_behavior_tree/test/test_bt_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -387,6 +387,132 @@ TEST(PathPortTest, test_correct_syntax)
EXPECT_EQ(path.poses[1].pose.orientation.w, 14.0);
}

TEST(WaypointStatusPortTest, test_wrong_syntax)
{
std::string xml_txt =
R"(
<root BTCPP_format="4">
<BehaviorTree ID="MainTree">
<WaypointStatusPort test="0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;msg;8.0" />
</BehaviorTree>
</root>)";

BT::BehaviorTreeFactory factory;
factory.registerNodeType<TestNode<nav2_msgs::msg::WaypointStatus>>("WaypointStatusPort");
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);

xml_txt =
R"(
<root BTCPP_format="4">
<BehaviorTree ID="MainTree">
<WaypointStatusPort test="0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;" />
</BehaviorTree>
</root>)";

EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);
}

TEST(WaypointStatusPortTest, test_correct_syntax)
{
std::string xml_txt =
R"(
<root BTCPP_format="4">
<BehaviorTree ID="MainTree">
<WaypointStatusPort test="0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;8;error" />
</BehaviorTree>
</root>)";

BT::BehaviorTreeFactory factory;
factory.registerNodeType<TestNode<nav2_msgs::msg::WaypointStatus>>("WaypointStatusPort");
auto tree = factory.createTreeFromText(xml_txt);

nav2_msgs::msg::WaypointStatus values;
tree.rootNode()->getInput("test", values);
EXPECT_EQ(values.waypoint_status, 0);
EXPECT_EQ(values.waypoint_index, 1);
EXPECT_EQ(rclcpp::Time(values.waypoint_pose.header.stamp).nanoseconds(), 0);
EXPECT_EQ(values.waypoint_pose.header.frame_id, "map");
EXPECT_EQ(values.waypoint_pose.pose.position.x, 1.0);
EXPECT_EQ(values.waypoint_pose.pose.position.y, 2.0);
EXPECT_EQ(values.waypoint_pose.pose.position.z, 3.0);
EXPECT_EQ(values.waypoint_pose.pose.orientation.x, 4.0);
EXPECT_EQ(values.waypoint_pose.pose.orientation.y, 5.0);
EXPECT_EQ(values.waypoint_pose.pose.orientation.z, 6.0);
EXPECT_EQ(values.waypoint_pose.pose.orientation.w, 7.0);
EXPECT_EQ(values.error_code, 8);
EXPECT_EQ(values.error_msg, "error");
}

TEST(WaypointStatusVectorPortTest, test_wrong_syntax) {
std::string xml_txt =
R"(
<root BTCPP_format="4">
<BehaviorTree ID="MainTree">
<WaypointStatusVectorPort test="0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;msg;8.0;0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;msg;8.0" />
</BehaviorTree>
</root>)";

BT::BehaviorTreeFactory factory;
factory.registerNodeType<TestNode<std::vector<nav2_msgs::msg::WaypointStatus>>>(
"WaypointStatusVectorPort");
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);

xml_txt =
R"(
<root BTCPP_format="4">
<BehaviorTree ID="MainTree">
<WaypointStatusVectorPort test="0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;" />
</BehaviorTree>
</root>)";

EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);
}

TEST(WaypointStatusVectorPortTest, test_correct_syntax)
{
std::string xml_txt =
R"(
<root BTCPP_format="4">
<BehaviorTree ID="MainTree">
<WaypointStatusVectorPort test="0;1;0;map;1.0;2.0;3.0;4.0;5.0;6.0;7.0;8;error;9;10;0;odom;11.0;12.0;13.0;14.0;15.0;16.0;17.0;18;msg" />
</BehaviorTree>
</root>)";

BT::BehaviorTreeFactory factory;
factory.registerNodeType<TestNode<std::vector<nav2_msgs::msg::WaypointStatus>>>(
"WaypointStatusVectorPort");
auto tree = factory.createTreeFromText(xml_txt);

std::vector<nav2_msgs::msg::WaypointStatus> values;
tree.rootNode()->getInput("test", values);
EXPECT_EQ(values[0].waypoint_status, 0);
EXPECT_EQ(values[0].waypoint_index, 1);
EXPECT_EQ(rclcpp::Time(values[0].waypoint_pose.header.stamp).nanoseconds(), 0);
EXPECT_EQ(values[0].waypoint_pose.header.frame_id, "map");
EXPECT_EQ(values[0].waypoint_pose.pose.position.x, 1.0);
EXPECT_EQ(values[0].waypoint_pose.pose.position.y, 2.0);
EXPECT_EQ(values[0].waypoint_pose.pose.position.z, 3.0);
EXPECT_EQ(values[0].waypoint_pose.pose.orientation.x, 4.0);
EXPECT_EQ(values[0].waypoint_pose.pose.orientation.y, 5.0);
EXPECT_EQ(values[0].waypoint_pose.pose.orientation.z, 6.0);
EXPECT_EQ(values[0].waypoint_pose.pose.orientation.w, 7.0);
EXPECT_EQ(values[0].error_code, 8);
EXPECT_EQ(values[0].error_msg, "error");
EXPECT_EQ(values[1].waypoint_status, 9);
EXPECT_EQ(values[1].waypoint_index, 10);
EXPECT_EQ(rclcpp::Time(values[1].waypoint_pose.header.stamp).nanoseconds(), 0);
EXPECT_EQ(values[1].waypoint_pose.header.frame_id, "odom");
EXPECT_EQ(values[1].waypoint_pose.pose.position.x, 11.0);
EXPECT_EQ(values[1].waypoint_pose.pose.position.y, 12.0);
EXPECT_EQ(values[1].waypoint_pose.pose.position.z, 13.0);
EXPECT_EQ(values[1].waypoint_pose.pose.orientation.x, 14.0);
EXPECT_EQ(values[1].waypoint_pose.pose.orientation.y, 15.0);
EXPECT_EQ(values[1].waypoint_pose.pose.orientation.z, 16.0);
EXPECT_EQ(values[1].waypoint_pose.pose.orientation.w, 17.0);
EXPECT_EQ(values[1].error_code, 18);
EXPECT_EQ(values[1].error_msg, "msg");
}

TEST(MillisecondsPortTest, test_correct_syntax)
{
std::string xml_txt =
Expand Down
Loading