38 #include <urdf_parser/urdf_parser.h>
40 #include <gtest/gtest.h>
41 #include <boost/filesystem/path.hpp>
63 ASSERT_EQ(robot_model_->getURDF()->getName(),
"pr2");
64 ASSERT_EQ(robot_model_->getSRDF()->getName(),
"pr2");
71 const std::vector<const moveit::core::JointModel*>& joints = robot_model_->getJointModels();
72 for (std::size_t i = 0; i < joints.size(); ++i)
74 ASSERT_EQ(joints[i]->getJointIndex(),
static_cast<int>(i));
75 ASSERT_EQ(robot_model_->getJointModel(joints[i]->getName()), joints[i]);
77 const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModels();
78 for (std::size_t i = 0; i < links.size(); ++i)
80 ASSERT_EQ(links[i]->getLinkIndex(),
static_cast<int>(i));
85 TEST(SiblingAssociateLinks, SimpleYRobot)
91 builder.addChain(
"base_link->a",
"continuous");
92 builder.addChain(
"a->b->c",
"fixed");
93 builder.addChain(
"a->d",
"fixed");
94 builder.addChain(
"d->e",
"continuous");
95 builder.addVirtualJoint(
"odom",
"base_link",
"planar",
"base_joint");
96 builder.addGroup({}, {
"base_joint" },
"base_joint");
97 ASSERT_TRUE(builder.isValid());
98 moveit::core::RobotModelConstPtr
robot_model = builder.build();
100 const std::string a =
"a", b =
"b", c =
"c",
d =
"d";
101 auto connected = { a, b, c,
d };
104 for (
const std::string& root : connected)
106 SCOPED_TRACE(
"root: " + root);
107 std::set<std::string> expected_set(connected);
108 expected_set.erase(root);
109 std::set<std::string> actual_set;
110 for (
const auto& item :
robot_model->getLinkModel(root)->getAssociatedFixedTransforms())
111 actual_set.insert(item.first->getName());
113 std::ostringstream expected, actual;
114 std::copy(expected_set.begin(), expected_set.end(), std::ostream_iterator<std::string>(expected,
" "));
115 std::copy(actual_set.begin(), actual_set.end(), std::ostream_iterator<std::string>(actual,
" "));
121 TEST(RobotModel, CycleDetection)
123 static const std::string
URDF = R
"(<?xml version="1.0"?>
128 <joint name="base_a" type="fixed">
129 <parent link="base"/>
132 <joint name="base_b" type="continuous">
133 <parent link="base"/>
136 <joint name="a_b" type="continuous">
142 auto urdf = std::make_shared<urdf::Model>();
144 ASSERT_TRUE(
urdf->initString(
URDF));
145 auto srdf = std::make_shared<srdf::Model>();
153 int main(
int argc,
char** argv)
155 testing::InitGoogleTest(&argc, argv);
156 return RUN_ALL_TESTS();