3 #include <gtest/gtest.h>
7 #include <kdl/treefksolverpos_recursive.hpp>
24 std::vector<Link::ConstPtr> links = scene_graph.
getLinks();
25 std::vector<Link::ConstPtr> check_links;
26 SceneGraph::vertex_iterator i, iend;
27 for (boost::tie(i, iend) = boost::vertices(scene_graph); i != iend; ++i)
30 EXPECT_TRUE(links.size() == check_links.size());
32 for (
const auto& l : links)
34 auto it = std::find_if(
35 check_links.begin(), check_links.end(), [&](
const Link::ConstPtr& p) { return p.get() == l.get(); });
36 EXPECT_TRUE(it != check_links.end());
45 Link link_1(
"link_1");
46 Link link_2(
"link_2");
47 Link link_3(
"link_3");
48 Link link_4(
"link_4");
49 Link link_5(
"link_5");
57 Joint joint_1(
"joint_1");
64 Joint joint_2(
"joint_2");
69 joint_2.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 6);
72 Joint joint_3(
"joint_3");
79 Joint joint_4(
"joint_4");
84 joint_4.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
101 EXPECT_TRUE(adjacent_links.size() == 1);
102 EXPECT_TRUE(adjacent_links[0] ==
"link_4");
106 EXPECT_TRUE(inv_adjacent_links.size() == 1);
107 EXPECT_TRUE(inv_adjacent_links[0] ==
"link_2");
111 EXPECT_TRUE(child_link_names.empty());
114 EXPECT_TRUE(child_link_names.size() == 1);
115 EXPECT_TRUE(child_link_names[0] ==
"link_4");
118 EXPECT_TRUE(child_link_names.size() == 3);
119 EXPECT_TRUE(std::find(child_link_names.begin(), child_link_names.end(),
"link_3") != child_link_names.end());
120 EXPECT_TRUE(std::find(child_link_names.begin(), child_link_names.end(),
"link_4") != child_link_names.end());
121 EXPECT_TRUE(std::find(child_link_names.begin(), child_link_names.end(),
"link_5") != child_link_names.end());
124 std::unordered_map<std::string, std::string> adj_map = g.
getAdjacencyMap({
"link_2",
"link_3" });
125 EXPECT_TRUE(adj_map.size() == 4);
126 EXPECT_EQ(adj_map.at(
"link_3"),
"link_3");
127 EXPECT_EQ(adj_map.at(
"link_4"),
"link_3");
128 EXPECT_EQ(adj_map.at(
"link_5"),
"link_2");
129 EXPECT_EQ(adj_map.at(
"link_2"),
"link_2");
132 std::vector<Link::ConstPtr> leaf_links = g.
getLeafLinks();
133 EXPECT_TRUE(leaf_links.size() == 2);
134 EXPECT_TRUE(std::find(leaf_links.begin(), leaf_links.end(), g.
getLink(
"link_5")) != leaf_links.end());
135 EXPECT_TRUE(std::find(leaf_links.begin(), leaf_links.end(), g.
getLink(
"link_4")) != leaf_links.end());
139 EXPECT_TRUE(child_link_names.size() == 1);
140 EXPECT_TRUE(child_link_names[0] ==
"link_5");
143 EXPECT_TRUE(child_link_names.size() == 1);
144 EXPECT_TRUE(child_link_names[0] ==
"link_4");
147 EXPECT_TRUE(child_link_names.size() == 4);
148 EXPECT_TRUE(std::find(child_link_names.begin(), child_link_names.end(),
"link_2") != child_link_names.end());
149 EXPECT_TRUE(std::find(child_link_names.begin(), child_link_names.end(),
"link_3") != child_link_names.end());
150 EXPECT_TRUE(std::find(child_link_names.begin(), child_link_names.end(),
"link_4") != child_link_names.end());
151 EXPECT_TRUE(std::find(child_link_names.begin(), child_link_names.end(),
"link_5") != child_link_names.end());
155 EXPECT_TRUE(active_joints.size() == 2);
156 EXPECT_TRUE(std::find(active_joints.begin(), active_joints.end(), g.
getJoint(
"joint_2")) != active_joints.end());
157 EXPECT_TRUE(std::find(active_joints.begin(), active_joints.end(), g.
getJoint(
"joint_4")) != active_joints.end());
166 std::cout <<
"Is Acyclic: " << g.
isAcyclic() <<
"\n";
170 std::cout <<
"Is Tree: " << g.
isTree() <<
"\n";
174 Link link_6(
"link_6");
176 std::cout <<
"Free Link, Is Tree: " << g.
isTree() <<
"\n";
183 std::cout <<
"Free Link Removed, Is Tree: " << g.
isTree() <<
"\n";
189 Joint joint_5(
"joint_5");
203 std::cout <<
"Is Acyclic: " << g.
isAcyclic() <<
"\n";
207 std::cout <<
"Is Tree: " << g.
isTree() <<
"\n";
210 Joint joint_6(
"joint_6");
224 std::cout <<
"Is Acyclic: " << g.
isAcyclic() <<
"\n";
228 std::cout <<
"Is Tree: " << g.
isTree() <<
"\n";
234 std::cout << path <<
"\n";
235 EXPECT_TRUE(path.links.size() == 3);
236 EXPECT_TRUE(std::find(path.links.begin(), path.links.end(),
"link_1") != path.links.end());
237 EXPECT_TRUE(std::find(path.links.begin(), path.links.end(),
"link_5") != path.links.end());
238 EXPECT_TRUE(std::find(path.links.begin(), path.links.end(),
"link_4") != path.links.end());
239 EXPECT_TRUE(path.joints.size() == 2);
240 EXPECT_TRUE(std::find(path.joints.begin(), path.joints.end(),
"joint_5") != path.joints.end());
241 EXPECT_TRUE(std::find(path.joints.begin(), path.joints.end(),
"joint_6") != path.joints.end());
242 EXPECT_TRUE(path.active_joints.size() == 2);
243 EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(),
"joint_5") != path.active_joints.end());
244 EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(),
"joint_6") != path.active_joints.end());
246 std::cout << (g.
getName().c_str()) <<
"\n";
252 std::cout << path <<
"\n";
253 EXPECT_TRUE(path.links.size() == 3);
254 EXPECT_TRUE(std::find(path.links.begin(), path.links.end(),
"link_1") != path.links.end());
255 EXPECT_TRUE(std::find(path.links.begin(), path.links.end(),
"link_5") != path.links.end());
256 EXPECT_TRUE(std::find(path.links.begin(), path.links.end(),
"link_4") != path.links.end());
257 EXPECT_TRUE(path.joints.size() == 2);
258 EXPECT_TRUE(std::find(path.joints.begin(), path.joints.end(),
"joint_5") != path.joints.end());
259 EXPECT_TRUE(std::find(path.joints.begin(), path.joints.end(),
"joint_6") != path.joints.end());
260 EXPECT_TRUE(path.active_joints.size() == 2);
261 EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(),
"joint_5") != path.active_joints.end());
262 EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(),
"joint_6") != path.active_joints.end());
264 std::cout << (g.
getName().c_str()) <<
"\n";
269 EXPECT_ANY_THROW(g.
getVertex(
"vertex_does_not_exist"));
270 EXPECT_ANY_THROW(g.
getEdge(
"edge_does_not_exist"));
273 TEST(TesseractSceneGraphUnit, TesseractSceneGraphUnit)
289 g_move = std::move(g);
294 TEST(TesseractSceneGraphUnit, TesseractSceneGraphClearUnit)
310 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRootLinkUnit)
315 EXPECT_EQ(g.
getRoot(),
"link_1");
316 EXPECT_TRUE(g.
setRoot(
"link_5"));
317 EXPECT_FALSE(g.
setRoot(
"link_10"));
320 TEST(TesseractSceneGraphUnit, TesseractSceneGraphGetLinkJointUnit)
325 EXPECT_TRUE(g.
getLink(
"link_1") !=
nullptr);
326 EXPECT_TRUE(g.
getJoint(
"joint_1") !=
nullptr);
328 EXPECT_TRUE(g.
getLink(
"does_not_exist") ==
nullptr);
329 EXPECT_TRUE(g.
getJoint(
"does_not_exist") ==
nullptr);
332 TEST(TesseractSceneGraphUnit, TesseractSceneGraphAddLinkJointPairUnit)
337 Link link_6(
"link_6");
338 Joint joint_6(
"joint_5");
344 EXPECT_TRUE(g.
addLink(link_6, joint_6));
345 EXPECT_TRUE(g.
getLink(
"link_6") !=
nullptr);
346 EXPECT_TRUE(g.
getJoint(
"joint_5") !=
nullptr);
351 Link link_6d(
"link_6");
352 Joint joint_6d(
"joint_5d");
357 EXPECT_FALSE(g.
addLink(link_6d, joint_6d));
365 Link link_6e(
"link_6e");
366 Joint joint_6e(
"joint_5");
371 EXPECT_FALSE(g.
addLink(link_6e, joint_6e));
379 TEST(TesseractSceneGraphUnit, TesseractSceneGraphAddLinkUnit)
384 Link replace_link(
"link_5");
387 EXPECT_FALSE(g.
addLink(replace_link));
395 EXPECT_TRUE(g.
addLink(replace_link,
true));
403 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRemoveLinkUnit)
411 EXPECT_TRUE(g.
getJoint(
"joint_4") ==
nullptr);
412 EXPECT_TRUE(g.
getLink(
"link_5") ==
nullptr);
438 EXPECT_FALSE(g.
removeLink(
"link_does_not_exist"));
459 TEST(TesseractSceneGraphUnit, TesseractSceneGraphMoveLinkUnit)
467 EXPECT_NE(j->parent_link_name,
"link_4");
471 EXPECT_TRUE(g.
moveLink(move_joint));
472 EXPECT_TRUE(g.
getJoint(
"joint_4") ==
nullptr);
473 EXPECT_TRUE(g.
getJoint(
"move_joint_4") !=
nullptr);
484 EXPECT_FALSE(ng.
moveLink(move_joint));
494 EXPECT_FALSE(ng.
moveLink(move_joint));
501 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRemoveAllowedCollisionUnit)
517 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointOriginUnit)
523 Eigen::Isometry3d origin = j->parent_to_joint_origin_transform;
524 double check = origin.translation().x();
525 origin.translation().x() = check + 5;
530 EXPECT_DOUBLE_EQ(g.
getJoint(
"joint_4")->parent_to_joint_origin_transform.translation().x(), check + 5);
538 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointLimitsUnit)
544 EXPECT_TRUE(jl !=
nullptr);
547 EXPECT_TRUE(jld ==
nullptr);
557 EXPECT_DOUBLE_EQ(j->limits->lower, -5);
558 EXPECT_DOUBLE_EQ(j->limits->upper, 5);
570 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointPositionLimitsUnit)
579 EXPECT_DOUBLE_EQ(j->limits->lower, -5);
580 EXPECT_DOUBLE_EQ(j->limits->upper, 5);
592 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointVelocityLimitsUnit)
601 EXPECT_DOUBLE_EQ(j->limits->velocity, 10);
613 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointAccelerationLimitsUnit)
622 EXPECT_DOUBLE_EQ(j->limits->acceleration, 20);
634 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointJerkLimitsUnit)
643 EXPECT_DOUBLE_EQ(j->limits->jerk, 20);
655 TEST(TesseractSceneGraphUnit, TesseractSceneGraphMoveJointUnit)
663 EXPECT_NE(j->parent_link_name,
"link_4");
664 EXPECT_TRUE(g.
moveJoint(
"joint_4",
"link_4"));
665 EXPECT_EQ(j->parent_link_name,
"link_4");
673 EXPECT_FALSE(g.
moveJoint(
"joint_does_not_exist",
"link_4"));
679 EXPECT_FALSE(g.
moveJoint(
"joint_4",
"link_does_not_exist"));
685 TEST(TesseractSceneGraphUnit, TesseractSceneGraphAddJointUnit)
690 Joint joint_6(
"joint_5");
701 Joint joint_7(
"joint_7");
712 Joint joint_4(
"joint_4");
724 Link link_6(
"link_6");
725 EXPECT_TRUE(g.
addLink(link_6));
734 EXPECT_TRUE(g.
getJoint(
"joint_7")->limits !=
nullptr);
735 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->lower, -4 * M_PI, 1e-5);
736 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->upper, 4 * M_PI, 1e-5);
737 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->effort, 0.0, 1e-5);
738 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->velocity, 2.0, 1e-5);
739 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->acceleration, 1.0, 1e-5);
741 Link link_7(
"link_7");
742 EXPECT_TRUE(g.
addLink(link_7));
746 Joint joint_8(
"joint_8");
751 joint_8.
limits = std::make_shared<JointLimits>(0, 0, 0, 2, 1, 0.5);
754 EXPECT_TRUE(g.
getJoint(
"joint_7")->limits !=
nullptr);
755 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->lower, -4 * M_PI, 1e-5);
756 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->upper, 4 * M_PI, 1e-5);
757 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->effort, 0.0, 1e-5);
758 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->velocity, 2.0, 1e-5);
759 EXPECT_NEAR(g.
getJoint(
"joint_7")->limits->acceleration, 1.0, 1e-5);
762 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRemoveJointUnit)
771 EXPECT_TRUE(g.
getJoint(
"joint_4") ==
nullptr);
772 EXPECT_TRUE(g.
getLink(
"link_5") !=
nullptr);
781 EXPECT_FALSE(g.
removeJoint(
"joint_does_not_exist"));
802 void printKDLTree(
const KDL::SegmentMap::const_iterator& link,
const std::string& prefix)
804 std::cout << prefix <<
"- Segment " << GetTreeElementSegment(link->second).getName() <<
" has "
805 << GetTreeElementChildren(link->second).size() <<
" children\n";
807 for (
auto child : GetTreeElementChildren(link->second))
816 Link base_link(
"base_link");
817 Link link_1(
"link_1");
818 Link link_2(
"link_2");
819 Link link_3(
"link_3");
820 Link link_4(
"link_4");
821 Link link_5(
"link_5");
823 EXPECT_TRUE(g.
addLink(base_link));
824 EXPECT_TRUE(g.
addLink(link_1));
825 EXPECT_TRUE(g.
addLink(link_2));
826 EXPECT_TRUE(g.
addLink(link_3));
827 EXPECT_TRUE(g.
addLink(link_4));
828 EXPECT_TRUE(g.
addLink(link_5));
830 Joint base_joint(
"base_joint");
834 EXPECT_TRUE(g.
addJoint(base_joint));
836 Joint joint_1(
"joint_1");
840 joint_1.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
843 Joint joint_2(
"joint_2");
848 joint_2.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
851 Joint joint_3(
"joint_3");
856 joint_3.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
859 Joint joint_4(
"joint_4");
864 joint_4.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
873 std::vector<std::string> prefix{
"left_",
"right_" };
874 std::vector<std::string> link_names = {
"base_link",
"link_1",
"link_2",
"link_3",
"link_4",
"link_5" };
879 for (
const auto& p : prefix)
881 for (
const auto& link_name : link_names)
887 for (
const auto& p : prefix)
889 Joint world_joint(p +
"word_joint");
898 EXPECT_TRUE(g.
addJoint(world_joint));
900 Joint base_joint(p +
"base_joint");
904 EXPECT_TRUE(g.
addJoint(base_joint));
906 Joint joint_1(p +
"joint_1");
910 joint_1.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
913 Joint joint_2(p +
"joint_2");
918 joint_2.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
921 Joint joint_3(p +
"joint_3");
926 joint_3.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
929 Joint joint_4(p +
"joint_4");
934 joint_4.
limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
943 KDL::TreeFkSolverPos_recursive solver(tree);
944 KDL::JntArray joints;
946 for (
unsigned int i = 0; i < 4; ++i)
951 solver.JntToCart(joints, frame,
"base_link");
953 EXPECT_TRUE(e_frame.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
958 solver.JntToCart(joints, frame,
"link_1");
960 EXPECT_TRUE(e_frame.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
965 solver.JntToCart(joints, frame,
"link_2");
967 EXPECT_TRUE(e_frame.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
972 solver.JntToCart(joints, frame,
"link_3");
974 Eigen::Isometry3d c_frame{ Eigen::Isometry3d::Identity() };
975 c_frame.translation()(0) = 1.25;
976 EXPECT_TRUE(e_frame.isApprox(c_frame, 1e-8));
981 solver.JntToCart(joints, frame,
"link_4");
983 Eigen::Isometry3d c_frame{ Eigen::Isometry3d::Identity() };
984 c_frame.translation()(0) = 2 * 1.25;
985 EXPECT_TRUE(e_frame.isApprox(c_frame, 1e-8));
990 solver.JntToCart(joints, frame,
"link_5");
992 Eigen::Isometry3d c_frame{ Eigen::Isometry3d::Identity() };
993 c_frame.translation()(1) = 1.25;
994 EXPECT_TRUE(e_frame.isApprox(c_frame, 1e-8));
1000 const std::unordered_map<std::string, double>& joint_values)
1002 std::vector<std::string> prefix{
"left_",
"right_" };
1003 KDL::TreeFkSolverPos_recursive solver(data.
tree);
1004 KDL::TreeFkSolverPos_recursive full_solver(data.
tree);
1006 KDL::JntArray joints;
1007 joints.resize(data.
tree.getNrOfJoints());
1008 for (
unsigned int i = 0; i < data.
tree.getNrOfJoints(); ++i)
1011 KDL::JntArray full_joints;
1012 joints.resize(full_data.
tree.getNrOfJoints());
1013 for (
unsigned int i = 0; i < full_data.
tree.getNrOfJoints(); ++i)
1016 EXPECT_EQ(data.
tree.getRootSegment()->first,
"world");
1017 EXPECT_EQ(full_data.
tree.getRootSegment()->first,
"world");
1019 for (
const auto& p : prefix)
1023 solver.JntToCart(joints, frame, p +
"link_2");
1026 full_solver.JntToCart(full_joints, c_frame, p +
"link_2");
1033 solver.JntToCart(joints, frame, p +
"link_3");
1036 full_solver.JntToCart(full_joints, c_frame, p +
"link_3");
1043 solver.JntToCart(joints, frame, p +
"link_4");
1046 full_solver.JntToCart(full_joints, c_frame, p +
"link_4");
1053 solver.JntToCart(joints, frame, p +
"link_5");
1056 full_solver.JntToCart(full_joints, c_frame, p +
"link_5");
1063 TEST(TesseractSceneGraphUnit, GetSourceLinkUnit)
1068 for (
int i = 1; i <= 3; ++i)
1070 std::string link_name =
"link_" + std::to_string(i);
1071 std::string joint_name =
"joint_" + std::to_string(i);
1074 EXPECT_EQ(l->getName(), link_name);
1075 EXPECT_EQ(j->parent_link_name, link_name);
1076 EXPECT_TRUE(g.
getLink(link_name) == l);
1080 TEST(TesseractSceneGraphUnit, GetTargetLinkUnit)
1085 for (
int i = 1; i <= 3; ++i)
1087 std::string link_name =
"link_" + std::to_string(i + 1);
1088 std::string joint_name =
"joint_" + std::to_string(i);
1091 EXPECT_EQ(l->getName(), link_name);
1092 EXPECT_EQ(j->child_link_name, link_name);
1093 EXPECT_TRUE(g.
getLink(link_name) == l);
1097 TEST(TesseractSceneGraphUnit, GetInboundJointsUnit)
1102 for (
int i = 2; i <= 4; ++i)
1104 std::string link_name =
"link_" + std::to_string(i);
1105 std::string joint_name =
"joint_" + std::to_string(i - 1);
1108 EXPECT_EQ(j.size(), 1);
1109 EXPECT_EQ(j[0]->getName(), joint_name);
1110 EXPECT_EQ(j[0]->child_link_name, link_name);
1111 EXPECT_TRUE(g.
getJoint(joint_name) == j[0]);
1115 TEST(TesseractSceneGraphUnit, GetOutboundJointsUnit)
1120 for (
int i = 1; i <= 3; ++i)
1122 std::string link_name =
"link_" + std::to_string(i);
1123 std::string joint_name =
"joint_" + std::to_string(i);
1128 EXPECT_EQ(j.size(), 2);
1129 EXPECT_EQ(j[0]->getName(), joint_name);
1130 EXPECT_EQ(j[0]->parent_link_name, link_name);
1131 EXPECT_TRUE(g.
getJoint(joint_name) == j[0]);
1133 EXPECT_EQ(j[1]->getName(),
"joint_4");
1134 EXPECT_EQ(j[1]->parent_link_name, link_name);
1135 EXPECT_TRUE(g.
getJoint(
"joint_4") == j[1]);
1139 EXPECT_EQ(j.size(), 1);
1140 EXPECT_EQ(j[0]->getName(), joint_name);
1141 EXPECT_EQ(j[0]->parent_link_name, link_name);
1142 EXPECT_TRUE(g.
getJoint(joint_name) == j[0]);
1147 TEST(TesseractSceneGraphUnit, LoadKDLUnit)
1153 for (
const auto& link : g.
getLinks())
1159 std::vector<std::string> joint_names{
"joint_1",
"joint_2",
"joint_3",
"joint_4" };
1160 std::vector<std::string> link_names{
"base_link",
"link_1",
"link_2",
"link_3",
"link_4",
"link_5" };
1161 std::vector<std::string> static_link_names{
"base_link",
"link_1" };
1162 std::vector<std::string> active_link_names{
"link_2",
"link_3",
"link_4",
"link_5" };
1174 std::cout <<
" ======================================\n";
1175 std::cout <<
" Tree has " << data.
tree.getNrOfSegments() <<
" link(s) and a root link\n";
1176 std::cout <<
" ======================================\n";
1177 auto root = data.
tree.getRootSegment();
1180 EXPECT_EQ(data.
tree.getNrOfJoints(), 4);
1181 EXPECT_EQ(data.
tree.getNrOfSegments(), 5);
1187 for (
const auto& link : g_clone->getLinks())
1189 EXPECT_TRUE(g_clone->getLinkCollisionEnabled(link->getName()));
1190 EXPECT_TRUE(g_clone->getLinkVisibility(link->getName()));
1204 std::cout <<
" ======================================\n";
1205 std::cout <<
" Tree has " << data.
tree.getNrOfSegments() <<
" link(s) and a root link\n";
1206 std::cout <<
" ======================================\n";
1207 auto root = data.
tree.getRootSegment();
1210 EXPECT_EQ(data.
tree.getNrOfJoints(), 4);
1211 EXPECT_EQ(data.
tree.getNrOfSegments(), 5);
1215 TEST(TesseractSceneGraphUnit, LoadSubKDLUnit)
1219 std::vector<std::string> joint_names{
"left_joint_1",
"left_joint_2",
"left_joint_3",
"left_joint_4",
1220 "right_joint_1",
"right_joint_2",
"right_joint_3",
"right_joint_4" };
1221 std::vector<std::string> sub_joint_names{
"left_joint_2",
"left_joint_3",
"left_joint_4",
1222 "right_joint_2",
"right_joint_3",
"right_joint_4" };
1223 std::vector<std::string> link_names{
"world",
"left_link_2",
"left_link_3",
"left_link_4",
"left_link_5",
1224 "right_link_2",
"right_link_3",
"right_link_4",
"right_link_5" };
1226 std::vector<std::string> static_link_names{
"world",
"left_link_2",
"right_link_2" };
1228 std::vector<std::string> active_link_names{
"left_link_3",
"left_link_4",
"left_link_5",
1229 "right_link_3",
"right_link_4",
"right_link_5" };
1231 std::unordered_map<std::string, double> joint_values;
1232 for (
const auto& joint_name : joint_names)
1235 std::uniform_real_distribution<double> sample(jnt->limits->lower, jnt->limits->upper);
1251 std::cout <<
" ======================================\n";
1252 std::cout <<
" Tree has " << data.
tree.getNrOfSegments() <<
" link(s) and a root link\n";
1253 std::cout <<
" ======================================\n";
1254 auto root = data.
tree.getRootSegment();
1257 EXPECT_EQ(data.
tree.getNrOfJoints(), 6);
1258 EXPECT_EQ(data.
tree.getNrOfSegments(), 8);
1264 for (
const auto& link : g_clone->getLinks())
1266 EXPECT_TRUE(g_clone->getLinkCollisionEnabled(link->getName()));
1267 EXPECT_TRUE(g_clone->getLinkVisibility(link->getName()));
1282 std::cout <<
" ======================================\n";
1283 std::cout <<
" Tree has " << data.
tree.getNrOfSegments() <<
" link(s) and a root link\n";
1284 std::cout <<
" ======================================\n";
1285 auto root = data.
tree.getRootSegment();
1288 EXPECT_EQ(data.
tree.getNrOfJoints(), 6);
1289 EXPECT_EQ(data.
tree.getNrOfSegments(), 8);
1293 TEST(TesseractSceneGraphUnit, TestChangeJointOrigin)
1298 Link link_1(
"link_n1");
1299 Link link_2(
"link_n2");
1301 Joint joint_1(
"joint_n1");
1310 Eigen::Isometry3d new_origin = Eigen::Isometry3d::Identity();
1311 new_origin.translation()(0) += 1.234;
1315 EXPECT_TRUE(g.
getJoint(
"joint_n1")->parent_to_joint_origin_transform.isApprox(new_origin));
1316 tesseract_scene_graph::SceneGraph::edge_descriptor e = g.
getEdge(
"joint_n1");
1317 double d = boost::get(boost::edge_weight_t(), g)[e];
1318 EXPECT_EQ(d, g.
getJoint(
"joint_n1")->parent_to_joint_origin_transform.translation().norm());
1321 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertEmptyUnit)
1344 EXPECT_TRUE(ng.
getLink(l->getName()) !=
nullptr);
1349 EXPECT_TRUE(ng.
getJoint(j->getName()) !=
nullptr);
1361 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertWithoutJointNoPrefixUnit)
1384 EXPECT_TRUE(ng.
getLink(l->getName()) !=
nullptr);
1389 EXPECT_TRUE(ng.
getJoint(j->getName()) !=
nullptr);
1398 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertWithoutJointWithPrefixUnit)
1412 std::string prefix =
"r1::";
1414 EXPECT_FALSE(ng.
isTree());
1426 EXPECT_TRUE(ng.
getLink(l->getName()) !=
nullptr);
1427 EXPECT_TRUE(ng.
getLink(prefix + l->getName()) !=
nullptr);
1432 EXPECT_TRUE(ng.
getJoint(j->getName()) !=
nullptr);
1433 EXPECT_TRUE(ng.
getJoint(prefix + j->getName()) !=
nullptr);
1447 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertWithJointWithPrefixUnit)
1465 std::string prefix =
"r1::";
1473 EXPECT_TRUE(ng.
isTree());
1485 EXPECT_TRUE(ng.
getLink(l->getName()) !=
nullptr);
1486 EXPECT_TRUE(ng.
getLink(prefix + l->getName()) !=
nullptr);
1491 EXPECT_TRUE(ng.
getJoint(j->getName()) !=
nullptr);
1492 EXPECT_TRUE(ng.
getJoint(prefix + j->getName()) !=
nullptr);
1506 TEST(TesseractSceneGraphUnit, TesseractSceneState)
1518 EXPECT_NEAR(jv(0), state.
joints[
"j2"], 1e-6);
1519 EXPECT_NEAR(jv(1), state.
joints[
"j3"], 1e-6);
1520 EXPECT_NEAR(jv(2), state.
joints[
"j6"], 1e-6);
1523 TEST(TesseractSceneGraphUnit, TesseractSceneGraphKDLConversions)
1526 Eigen::Isometry3d t = Eigen::Isometry3d::Identity();
1527 t.translation() = Eigen::Vector3d(1, 2, 3);
1529 for (
int i = 0; i < 4; ++i)
1531 for (
int j = 0; j < 4; ++j)
1533 EXPECT_DOUBLE_EQ(kdl_t(i, j), t(i, j));
1539 KDL::Frame kdl_t = KDL::Frame::Identity();
1540 kdl_t.p = KDL::Vector(1, 2, 3);
1542 for (
int i = 0; i < 4; ++i)
1544 for (
int j = 0; j < 4; ++j)
1546 EXPECT_DOUBLE_EQ(kdl_t(i, j), t(i, j));
1552 Eigen::Vector3d v(1, 2, 3);
1554 for (
int i = 0; i < 3; ++i)
1556 EXPECT_DOUBLE_EQ(kdl_v(i), v(i));
1561 KDL::Vector kdl_v(1, 2, 3);
1563 for (
int i = 0; i < 3; ++i)
1565 EXPECT_DOUBLE_EQ(kdl_v(i), v(i));
1570 Eigen::MatrixXd t = Eigen::MatrixXd::Random(6, 6);
1572 for (
int i = 0; i < 6; ++i)
1574 for (
int j = 0; j < 6; ++j)
1576 EXPECT_DOUBLE_EQ(kdl_t(
static_cast<unsigned>(i),
static_cast<unsigned>(j)), t(i, j));
1580 Eigen::MatrixXd t_wrong_size = Eigen::MatrixXd::Random(7, 7);
1585 KDL::Jacobian kdl_t;
1587 kdl_t.data = Eigen::MatrixXd::Random(6, 6);
1589 EXPECT_EQ(t.cols(), 6);
1590 EXPECT_EQ(t.rows(), 6);
1591 for (
int i = 0; i < 6; ++i)
1593 for (
int j = 0; j < 6; ++j)
1595 EXPECT_DOUBLE_EQ(kdl_t(
static_cast<unsigned>(i),
static_cast<unsigned>(j)), t(i, j));
1601 KDL::Jacobian kdl_t;
1603 kdl_t.data = Eigen::MatrixXd::Random(6, 6);
1605 std::vector<int> q_nrs{ 0, 2, 5 };
1607 EXPECT_EQ(t.cols(), 3);
1608 EXPECT_EQ(t.rows(), 6);
1609 for (
int i = 0; i < 6; ++i)
1611 EXPECT_DOUBLE_EQ(kdl_t(
static_cast<unsigned>(i), 0), t(i, 0));
1612 EXPECT_DOUBLE_EQ(kdl_t(
static_cast<unsigned>(i), 2), t(i, 1));
1613 EXPECT_DOUBLE_EQ(kdl_t(
static_cast<unsigned>(i), 5), t(i, 2));
1620 testing::InitGoogleTest(&argc, argv);
1622 return RUN_ALL_TESTS();