Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

RDFLoader Broken with Xacro Files #1132

Merged
merged 4 commits into from
Mar 22, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion moveit_ros/planning/rdf_loader/src/rdf_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ bool RDFLoader::loadXacroFileToString(std::string& buffer, const std::string& pa
return false;
}

std::string cmd = "ros2 run xacro xacro";
std::string cmd = "ros2 run xacro xacro ";
for (const std::string& xacro_arg : xacro_args)
cmd += xacro_arg + " ";
cmd += path;
Expand Down
9 changes: 9 additions & 0 deletions moveit_ros/planning/rdf_loader/test/data/robin.srdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<?xml version="1.0" encoding="utf-8"?>
<robot name="robin" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="srdf_macro">
<group name="group0">
<chain base_link="base_link" tip_link="flipper"/>
</group>
</xacro:macro>
<xacro:srdf_macro />
</robot>
9 changes: 9 additions & 0 deletions moveit_ros/planning/rdf_loader/test/test_rdf_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,15 @@ TEST(RDFIntegration, executor)
EXPECT_EQ("gonzo", loader.getSRDF()->getName());
}

TEST(RDFIntegration, xacro_test)
{
std::string output;
std::vector<std::string> xacro_args;
ASSERT_TRUE(rdf_loader::RDFLoader::loadPkgFileToString(output, "moveit_ros_planning",
"rdf_loader/test/data/robin.srdf.xacro", xacro_args));
EXPECT_GT(output.size(), 0u);
}

int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
Expand Down