tesseract_scene_graph_unit.cpp
Go to the documentation of this file.
3 #include <gtest/gtest.h>
4 //#include <boost/graph/filtered_graph.hpp>
5 #include <iostream>
6 #include <fstream>
7 #include <kdl/treefksolverpos_recursive.hpp>
9 
11 #include <tesseract_common/utils.h>
12 
18 
19 // getLinks and getJoint use an internal map so need to check against graph
21 {
22  using namespace tesseract_scene_graph;
23 
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)
28  check_links.push_back(boost::get(boost::vertex_link, scene_graph)[*i]);
29 
30  EXPECT_TRUE(links.size() == check_links.size());
31 
32  for (const auto& l : links)
33  {
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());
37  }
38 }
39 
41 {
42  using namespace tesseract_scene_graph;
43  SceneGraph g;
44 
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");
50 
51  EXPECT_TRUE(g.addLink(link_1));
52  EXPECT_TRUE(g.addLink(link_2));
53  EXPECT_TRUE(g.addLink(link_3));
54  EXPECT_TRUE(g.addLink(link_4));
55  EXPECT_TRUE(g.addLink(link_5));
56 
57  Joint joint_1("joint_1");
58  joint_1.parent_to_joint_origin_transform.translation()(0) = 1.25;
59  joint_1.parent_link_name = "link_1";
60  joint_1.child_link_name = "link_2";
61  joint_1.type = JointType::FIXED;
62  EXPECT_TRUE(g.addJoint(joint_1));
63 
64  Joint joint_2("joint_2");
65  joint_2.parent_to_joint_origin_transform.translation()(0) = 1.25;
66  joint_2.parent_link_name = "link_2";
67  joint_2.child_link_name = "link_3";
68  joint_2.type = JointType::PLANAR;
69  joint_2.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 6);
70  EXPECT_TRUE(g.addJoint(joint_2));
71 
72  Joint joint_3("joint_3");
73  joint_3.parent_to_joint_origin_transform.translation()(0) = 1.25;
74  joint_3.parent_link_name = "link_3";
75  joint_3.child_link_name = "link_4";
76  joint_3.type = JointType::FLOATING;
77  EXPECT_TRUE(g.addJoint(joint_3));
78 
79  Joint joint_4("joint_4");
80  joint_4.parent_to_joint_origin_transform.translation()(1) = 1.25;
81  joint_4.parent_link_name = "link_2";
82  joint_4.child_link_name = "link_5";
83  joint_4.type = JointType::REVOLUTE;
84  joint_4.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
85  EXPECT_TRUE(g.addJoint(joint_4));
86 
87  g.addAllowedCollision("link_1", "link_2", "Adjacent");
88  g.addAllowedCollision("link_2", "link_3", "Adjacent");
89  g.addAllowedCollision("link_3", "link_5", "Adjacent");
90  g.addAllowedCollision("link_2", "link_5", "Adjacent");
91 
92  return g;
93 }
94 
96 {
97  using namespace tesseract_scene_graph;
98 
99  // Check getAdjacentLinkNames Method
100  std::vector<std::string> adjacent_links = g.getAdjacentLinkNames("link_3");
101  EXPECT_TRUE(adjacent_links.size() == 1);
102  EXPECT_TRUE(adjacent_links[0] == "link_4");
103 
104  // Check getInvAdjacentLinkNames Method
105  std::vector<std::string> inv_adjacent_links = g.getInvAdjacentLinkNames("link_3");
106  EXPECT_TRUE(inv_adjacent_links.size() == 1);
107  EXPECT_TRUE(inv_adjacent_links[0] == "link_2");
108 
109  // Check getLinkChildrenNames
110  std::vector<std::string> child_link_names = g.getLinkChildrenNames("link_5");
111  EXPECT_TRUE(child_link_names.empty());
112 
113  child_link_names = g.getLinkChildrenNames("link_3");
114  EXPECT_TRUE(child_link_names.size() == 1);
115  EXPECT_TRUE(child_link_names[0] == "link_4");
116 
117  child_link_names = g.getLinkChildrenNames("link_2");
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());
122 
123  // Check getAdjacencyMap
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");
130 
131  // Check getLeafLinks
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());
136 
137  // Check getJointChildrenNames
138  child_link_names = g.getJointChildrenNames(std::vector<std::string>({ "joint_4" }));
139  EXPECT_TRUE(child_link_names.size() == 1);
140  EXPECT_TRUE(child_link_names[0] == "link_5");
141 
142  child_link_names = g.getJointChildrenNames(std::vector<std::string>({ "joint_3" }));
143  EXPECT_TRUE(child_link_names.size() == 1);
144  EXPECT_TRUE(child_link_names[0] == "link_4");
145 
146  child_link_names = g.getJointChildrenNames(std::vector<std::string>({ "joint_1" }));
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());
152 
153  // check getActiveJoints
154  std::vector<Joint::ConstPtr> active_joints = g.getActiveJoints();
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());
158 
159  // Check Graph
160  checkSceneGraph(g);
161 
162  // Save Graph
163  g.saveDOT(tesseract_common::getTempPath() + "graph_acyclic_tree_example.dot");
164 
165  // Test if the graph is Acyclic
166  std::cout << "Is Acyclic: " << g.isAcyclic() << "\n";
167  EXPECT_TRUE(g.isAcyclic());
168 
169  // Test if the graph is Tree
170  std::cout << "Is Tree: " << g.isTree() << "\n";
171  EXPECT_TRUE(g.isTree());
172 
173  // Test for unused links
174  Link link_6("link_6");
175  g.addLink(link_6);
176  std::cout << "Free Link, Is Tree: " << g.isTree() << "\n";
177  EXPECT_FALSE(g.isTree());
178 
179  // Check Graph
180  checkSceneGraph(g);
181 
182  g.removeLink("link_6");
183  std::cout << "Free Link Removed, Is Tree: " << g.isTree() << "\n";
184  EXPECT_TRUE(g.isTree());
185 
186  // Check Graph
187  checkSceneGraph(g);
188 
189  Joint joint_5("joint_5");
190  joint_5.parent_to_joint_origin_transform.translation()(1) = 1.5;
191  joint_5.parent_link_name = "link_5";
192  joint_5.child_link_name = "link_4";
193  joint_5.type = JointType::CONTINUOUS;
194  g.addJoint(joint_5);
195 
196  // Check Graph
197  checkSceneGraph(g);
198 
199  // Save Graph
200  g.saveDOT(tesseract_common::getTempPath() + "graph_acyclic_not_tree_example.dot");
201 
202  // Test if the graph is Acyclic
203  std::cout << "Is Acyclic: " << g.isAcyclic() << "\n";
204  EXPECT_TRUE(g.isAcyclic());
205 
206  // Test if the graph is Tree
207  std::cout << "Is Tree: " << g.isTree() << "\n";
208  EXPECT_FALSE(g.isTree());
209 
210  Joint joint_6("joint_6");
211  joint_6.parent_to_joint_origin_transform.translation()(1) = 1.25;
212  joint_6.parent_link_name = "link_5";
213  joint_6.child_link_name = "link_1";
214  joint_6.type = JointType::CONTINUOUS;
215  g.addJoint(joint_6);
216 
217  // Check Graph
218  checkSceneGraph(g);
219 
220  // Save Graph
221  g.saveDOT(tesseract_common::getTempPath() + "graph_cyclic_not_tree_example.dot");
222 
223  // Test if the graph is Acyclic
224  std::cout << "Is Acyclic: " << g.isAcyclic() << "\n";
225  EXPECT_FALSE(g.isAcyclic());
226 
227  // Test if the graph is Tree
228  std::cout << "Is Tree: " << g.isTree() << "\n";
229  EXPECT_FALSE(g.isTree());
230 
231  { // Get Shortest Path
232  ShortestPath path = g.getShortestPath("link_1", "link_4");
233 
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());
245 
246  std::cout << (g.getName().c_str()) << "\n";
247  }
248 
249  { // Get Shortest Path wit links reversed
250  ShortestPath path = g.getShortestPath("link_4", "link_1");
251 
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());
263 
264  std::cout << (g.getName().c_str()) << "\n";
265  }
266 
267  // Should throw since this is a directory and not a file
268  EXPECT_ANY_THROW(g.saveDOT(tesseract_common::getTempPath())); // NOLINT
269  EXPECT_ANY_THROW(g.getVertex("vertex_does_not_exist")); // NOLINT
270  EXPECT_ANY_THROW(g.getEdge("edge_does_not_exist")); // NOLINT
271 }
272 
273 TEST(TesseractSceneGraphUnit, TesseractSceneGraphUnit) // NOLINT
274 {
275  {
277  runTest(g);
278  }
279 
280  { // Move Constructor
282  tesseract_scene_graph::SceneGraph g_move(std::move(g));
283  runTest(g_move);
284  }
285 
286  { // Move Assignment Constructor
289  g_move = std::move(g);
290  runTest(g_move);
291  }
292 }
293 
294 TEST(TesseractSceneGraphUnit, TesseractSceneGraphClearUnit) // NOLINT
295 {
296  using namespace tesseract_scene_graph;
298 
299  EXPECT_EQ(g.getLinks().size(), 5);
300  EXPECT_EQ(g.getJoints().size(), 4);
301  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 4);
302 
303  g.clear();
304 
305  EXPECT_EQ(g.getLinks().size(), 0);
306  EXPECT_EQ(g.getJoints().size(), 0);
307  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 0);
308 }
309 
310 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRootLinkUnit) // NOLINT
311 {
312  using namespace tesseract_scene_graph;
314 
315  EXPECT_EQ(g.getRoot(), "link_1");
316  EXPECT_TRUE(g.setRoot("link_5"));
317  EXPECT_FALSE(g.setRoot("link_10"));
318 }
319 
320 TEST(TesseractSceneGraphUnit, TesseractSceneGraphGetLinkJointUnit) // NOLINT
321 {
322  using namespace tesseract_scene_graph;
324 
325  EXPECT_TRUE(g.getLink("link_1") != nullptr);
326  EXPECT_TRUE(g.getJoint("joint_1") != nullptr);
327 
328  EXPECT_TRUE(g.getLink("does_not_exist") == nullptr);
329  EXPECT_TRUE(g.getJoint("does_not_exist") == nullptr);
330 }
331 
332 TEST(TesseractSceneGraphUnit, TesseractSceneGraphAddLinkJointPairUnit) // NOLINT
333 {
334  using namespace tesseract_scene_graph;
336 
337  Link link_6("link_6");
338  Joint joint_6("joint_5");
339  joint_6.parent_to_joint_origin_transform.translation()(0) = 1.25;
340  joint_6.parent_link_name = "link_5";
341  joint_6.child_link_name = "link_6";
342  joint_6.type = JointType::FIXED;
343 
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);
347  EXPECT_EQ(g.getLinks().size(), 6);
348  EXPECT_EQ(g.getJoints().size(), 5);
349 
350  // Add link which already exists but joint does not
351  Link link_6d("link_6");
352  Joint joint_6d("joint_5d");
353  joint_6d.parent_to_joint_origin_transform.translation()(0) = 1.25;
354  joint_6d.parent_link_name = "link_5";
355  joint_6d.child_link_name = "link_6";
356  joint_6d.type = JointType::FIXED;
357  EXPECT_FALSE(g.addLink(link_6d, joint_6d));
358  EXPECT_EQ(g.getLinks().size(), 6);
359  EXPECT_EQ(g.getJoints().size(), 5);
360 
361  // Check Graph
362  checkSceneGraph(g);
363 
364  // Add joint which already exists but link does not
365  Link link_6e("link_6e");
366  Joint joint_6e("joint_5");
367  joint_6d.parent_to_joint_origin_transform.translation()(0) = 1.25;
368  joint_6d.parent_link_name = "link_5";
369  joint_6d.child_link_name = "link_6e";
370  joint_6d.type = JointType::FIXED;
371  EXPECT_FALSE(g.addLink(link_6e, joint_6e));
372  EXPECT_EQ(g.getLinks().size(), 6);
373  EXPECT_EQ(g.getJoints().size(), 5);
374 
375  // Check Graph
376  checkSceneGraph(g);
377 }
378 
379 TEST(TesseractSceneGraphUnit, TesseractSceneGraphAddLinkUnit) // NOLINT
380 {
381  using namespace tesseract_scene_graph;
383 
384  Link replace_link("link_5");
385 
386  // Add link which already exists but replace is not allowed
387  EXPECT_FALSE(g.addLink(replace_link));
388  EXPECT_EQ(g.getLinks().size(), 5);
389  EXPECT_EQ(g.getJoints().size(), 4);
390 
391  // Check Graph
392  checkSceneGraph(g);
393 
394  // Add link which already exists but replace is not allowed
395  EXPECT_TRUE(g.addLink(replace_link, true));
396  EXPECT_EQ(g.getLinks().size(), 5);
397  EXPECT_EQ(g.getJoints().size(), 4);
398 
399  // Check Graph
400  checkSceneGraph(g);
401 }
402 
403 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRemoveLinkUnit) // NOLINT
404 {
405  using namespace tesseract_scene_graph;
406  { // Remove Link
408  EXPECT_EQ(g.getLinks().size(), 5);
409  EXPECT_EQ(g.getJoints().size(), 4);
410  EXPECT_TRUE(g.removeLink("link_5"));
411  EXPECT_TRUE(g.getJoint("joint_4") == nullptr);
412  EXPECT_TRUE(g.getLink("link_5") == nullptr);
413  EXPECT_EQ(g.getLinks().size(), 4);
414  EXPECT_EQ(g.getJoints().size(), 3);
415 
416  // Check Graph
417  checkSceneGraph(g);
418  }
419 
420  { // Make sure all inbound and outbound edges are removed
422  // g = createTestSceneGraph();
424  EXPECT_EQ(g.getLinks().size(), 5);
425  EXPECT_EQ(g.getJoints().size(), 4);
426  EXPECT_TRUE(g.removeLink("link_2"));
427  EXPECT_EQ(g.getLinks().size(), 4);
428  EXPECT_EQ(g.getJoints().size(), 1);
429 
430  // Check Graph
431  checkSceneGraph(g);
432  }
433 
434  { // Try to remove link which does not exist
436  EXPECT_EQ(g.getLinks().size(), 5);
437  EXPECT_EQ(g.getJoints().size(), 4);
438  EXPECT_FALSE(g.removeLink("link_does_not_exist"));
439  EXPECT_EQ(g.getLinks().size(), 5);
440  EXPECT_EQ(g.getJoints().size(), 4);
441 
442  // Check Graph
443  checkSceneGraph(g);
444  }
445 
446  { // Make sure all children are removed if enabled
448  EXPECT_EQ(g.getLinks().size(), 5);
449  EXPECT_EQ(g.getJoints().size(), 4);
450  EXPECT_TRUE(g.removeLink("link_2", true));
451  EXPECT_EQ(g.getLinks().size(), 1);
452  EXPECT_EQ(g.getJoints().size(), 0);
453 
454  // Check Graph
455  checkSceneGraph(g);
456  }
457 }
458 
459 TEST(TesseractSceneGraphUnit, TesseractSceneGraphMoveLinkUnit) // NOLINT
460 {
461  using namespace tesseract_scene_graph;
463 
464  Joint::ConstPtr j = g.getJoint("joint_4");
465  EXPECT_EQ(g.getLinks().size(), 5);
466  EXPECT_EQ(g.getJoints().size(), 4);
467  EXPECT_NE(j->parent_link_name, "link_4");
468 
469  Joint move_joint = j->clone("move_joint_4");
470  move_joint.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);
474  EXPECT_EQ(g.getLinks().size(), 5);
475  EXPECT_EQ(g.getJoints().size(), 4);
476 
477  // Check Graph
478  checkSceneGraph(g);
479 
480  // Parent link does not exist
481  {
483  move_joint.parent_link_name = "link_does_not_exist";
484  EXPECT_FALSE(ng.moveLink(move_joint));
485 
486  // Check Graph
487  checkSceneGraph(ng);
488  }
489 
490  // Child link does not exist
491  {
493  move_joint.child_link_name = "link_does_not_exist";
494  EXPECT_FALSE(ng.moveLink(move_joint));
495 
496  // Check Graph
497  checkSceneGraph(ng);
498  }
499 }
500 
501 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRemoveAllowedCollisionUnit) // NOLINT
502 {
503  using namespace tesseract_scene_graph;
504 
506  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 4);
507  EXPECT_TRUE(g.isCollisionAllowed("link_1", "link_2"));
508 
509  g.removeAllowedCollision("link_1", "link_2");
510  EXPECT_FALSE(g.isCollisionAllowed("link_1", "link_2"));
511  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 3);
512 
514  EXPECT_TRUE(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().empty());
515 }
516 
517 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointOriginUnit) // NOLINT
518 {
519  using namespace tesseract_scene_graph;
521 
522  Joint::ConstPtr j = g.getJoint("joint_4");
523  Eigen::Isometry3d origin = j->parent_to_joint_origin_transform;
524  double check = origin.translation().x();
525  origin.translation().x() = check + 5;
526 
527  EXPECT_EQ(g.getLinks().size(), 5);
528  EXPECT_EQ(g.getJoints().size(), 4);
529  EXPECT_TRUE(g.changeJointOrigin("joint_4", origin));
530  EXPECT_DOUBLE_EQ(g.getJoint("joint_4")->parent_to_joint_origin_transform.translation().x(), check + 5);
531  EXPECT_EQ(g.getLinks().size(), 5);
532  EXPECT_EQ(g.getJoints().size(), 4);
533 
534  // Joint does not exist
535  EXPECT_FALSE(g.changeJointOrigin("joint_does_not_exist", origin));
536 }
537 
538 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointLimitsUnit) // NOLINT
539 {
540  using namespace tesseract_scene_graph;
542 
543  JointLimits::ConstPtr jl = g.getJointLimits("joint_4");
544  EXPECT_TRUE(jl != nullptr);
545 
546  JointLimits::ConstPtr jld = g.getJointLimits("joint_does_not_exist");
547  EXPECT_TRUE(jld == nullptr);
548 
549  JointLimits nlimits;
550  nlimits.lower = -5;
551  nlimits.upper = 5;
552 
553  Joint::ConstPtr j = g.getJoint("joint_4");
554  EXPECT_EQ(g.getLinks().size(), 5);
555  EXPECT_EQ(g.getJoints().size(), 4);
556  EXPECT_TRUE(g.changeJointLimits("joint_4", nlimits));
557  EXPECT_DOUBLE_EQ(j->limits->lower, -5);
558  EXPECT_DOUBLE_EQ(j->limits->upper, 5);
559  EXPECT_EQ(g.getLinks().size(), 5);
560  EXPECT_EQ(g.getJoints().size(), 4);
561 
562  // Joint does not exist
563  EXPECT_FALSE(g.changeJointLimits("joint_does_not_exist", nlimits));
564 
565  // Cannot change limits of fixed or floating joint
566  EXPECT_FALSE(g.changeJointLimits("joint_1", nlimits));
567  EXPECT_FALSE(g.changeJointLimits("joint_3", nlimits));
568 }
569 
570 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointPositionLimitsUnit) // NOLINT
571 {
572  using namespace tesseract_scene_graph;
574 
575  Joint::ConstPtr j = g.getJoint("joint_4");
576  EXPECT_EQ(g.getLinks().size(), 5);
577  EXPECT_EQ(g.getJoints().size(), 4);
578  EXPECT_TRUE(g.changeJointPositionLimits("joint_4", -5, 5));
579  EXPECT_DOUBLE_EQ(j->limits->lower, -5);
580  EXPECT_DOUBLE_EQ(j->limits->upper, 5);
581  EXPECT_EQ(g.getLinks().size(), 5);
582  EXPECT_EQ(g.getJoints().size(), 4);
583 
584  // Joint does not exist
585  EXPECT_FALSE(g.changeJointPositionLimits("joint_does_not_exist", -5, 5));
586 
587  // Cannot change limits of fixed or floating joint
588  EXPECT_FALSE(g.changeJointPositionLimits("joint_1", -5, 5));
589  EXPECT_FALSE(g.changeJointPositionLimits("joint_3", -5, 5));
590 }
591 
592 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointVelocityLimitsUnit) // NOLINT
593 {
594  using namespace tesseract_scene_graph;
596 
597  Joint::ConstPtr j = g.getJoint("joint_4");
598  EXPECT_EQ(g.getLinks().size(), 5);
599  EXPECT_EQ(g.getJoints().size(), 4);
600  EXPECT_TRUE(g.changeJointVelocityLimits("joint_4", 10));
601  EXPECT_DOUBLE_EQ(j->limits->velocity, 10);
602  EXPECT_EQ(g.getLinks().size(), 5);
603  EXPECT_EQ(g.getJoints().size(), 4);
604 
605  // Joint does not exist
606  EXPECT_FALSE(g.changeJointVelocityLimits("joint_does_not_exist", 10));
607 
608  // Cannot change limits of fixed or floating joint
609  EXPECT_FALSE(g.changeJointVelocityLimits("joint_1", 10));
610  EXPECT_FALSE(g.changeJointVelocityLimits("joint_3", 10));
611 }
612 
613 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointAccelerationLimitsUnit) // NOLINT
614 {
615  using namespace tesseract_scene_graph;
617 
618  Joint::ConstPtr j = g.getJoint("joint_4");
619  EXPECT_EQ(g.getLinks().size(), 5);
620  EXPECT_EQ(g.getJoints().size(), 4);
621  EXPECT_TRUE(g.changeJointAccelerationLimits("joint_4", 20));
622  EXPECT_DOUBLE_EQ(j->limits->acceleration, 20);
623  EXPECT_EQ(g.getLinks().size(), 5);
624  EXPECT_EQ(g.getJoints().size(), 4);
625 
626  // Joint does not exist
627  EXPECT_FALSE(g.changeJointAccelerationLimits("joint_does_not_exist", 20));
628 
629  // Cannot change limits of fixed or floating joint
630  EXPECT_FALSE(g.changeJointAccelerationLimits("joint_1", 20));
631  EXPECT_FALSE(g.changeJointAccelerationLimits("joint_3", 20));
632 }
633 
634 TEST(TesseractSceneGraphUnit, TesseractSceneGraphChangeJointJerkLimitsUnit) // NOLINT
635 {
636  using namespace tesseract_scene_graph;
638 
639  Joint::ConstPtr j = g.getJoint("joint_4");
640  EXPECT_EQ(g.getLinks().size(), 5);
641  EXPECT_EQ(g.getJoints().size(), 4);
642  EXPECT_TRUE(g.changeJointJerkLimits("joint_4", 20));
643  EXPECT_DOUBLE_EQ(j->limits->jerk, 20);
644  EXPECT_EQ(g.getLinks().size(), 5);
645  EXPECT_EQ(g.getJoints().size(), 4);
646 
647  // Joint does not exist
648  EXPECT_FALSE(g.changeJointJerkLimits("joint_does_not_exist", 20));
649 
650  // Cannot change limits of fixed or floating joint
651  EXPECT_FALSE(g.changeJointJerkLimits("joint_1", 20));
652  EXPECT_FALSE(g.changeJointJerkLimits("joint_3", 20));
653 }
654 
655 TEST(TesseractSceneGraphUnit, TesseractSceneGraphMoveJointUnit) // NOLINT
656 {
657  using namespace tesseract_scene_graph;
659 
660  Joint::ConstPtr j = g.getJoint("joint_4");
661  EXPECT_EQ(g.getLinks().size(), 5);
662  EXPECT_EQ(g.getJoints().size(), 4);
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");
666  EXPECT_EQ(g.getLinks().size(), 5);
667  EXPECT_EQ(g.getJoints().size(), 4);
668 
669  // Check Graph
670  checkSceneGraph(g);
671 
672  // Joint does not exist
673  EXPECT_FALSE(g.moveJoint("joint_does_not_exist", "link_4"));
674 
675  // Check Graph
676  checkSceneGraph(g);
677 
678  // Joint does not exist
679  EXPECT_FALSE(g.moveJoint("joint_4", "link_does_not_exist"));
680 
681  // Check Graph
682  checkSceneGraph(g);
683 }
684 
685 TEST(TesseractSceneGraphUnit, TesseractSceneGraphAddJointUnit) // NOLINT
686 {
687  using namespace tesseract_scene_graph;
689 
690  Joint joint_6("joint_5");
691  joint_6.parent_to_joint_origin_transform.translation()(0) = 1.25;
692  joint_6.parent_link_name = "link_5";
693  joint_6.child_link_name = "link_6";
694  joint_6.type = JointType::FIXED;
695 
696  // Child does not exist
697  EXPECT_FALSE(g.addJoint(joint_6));
698  EXPECT_EQ(g.getLinks().size(), 5);
699  EXPECT_EQ(g.getJoints().size(), 4);
700 
701  Joint joint_7("joint_7");
702  joint_7.parent_to_joint_origin_transform.translation()(0) = 1.25;
703  joint_7.parent_link_name = "link_6";
704  joint_7.child_link_name = "link_5";
705  joint_7.type = JointType::FIXED;
706 
707  // Parent does not exist
708  EXPECT_FALSE(g.addJoint(joint_7));
709  EXPECT_EQ(g.getLinks().size(), 5);
710  EXPECT_EQ(g.getJoints().size(), 4);
711 
712  Joint joint_4("joint_4");
713  joint_4.parent_to_joint_origin_transform.translation()(0) = 1.25;
714  joint_4.parent_link_name = "link_4";
715  joint_4.child_link_name = "link_5";
716  joint_4.type = JointType::FIXED;
717 
718  // Joint already exist
719  EXPECT_FALSE(g.addJoint(joint_4));
720  EXPECT_EQ(g.getLinks().size(), 5);
721  EXPECT_EQ(g.getJoints().size(), 4);
722 
723  // Add Joint with no joint limits
724  Link link_6("link_6");
725  EXPECT_TRUE(g.addLink(link_6));
726  joint_7.type = JointType::PRISMATIC;
727  EXPECT_FALSE(g.addJoint(joint_7));
728  EXPECT_EQ(g.getLinks().size(), 6);
729  EXPECT_EQ(g.getJoints().size(), 4);
730 
731  joint_7.type = JointType::CONTINUOUS;
732  EXPECT_TRUE(g.addJoint(joint_7));
733  EXPECT_EQ(g.getJoints().size(), 5);
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);
740 
741  Link link_7("link_7");
742  EXPECT_TRUE(g.addLink(link_7));
743  EXPECT_EQ(g.getLinks().size(), 7);
744  EXPECT_EQ(g.getJoints().size(), 5);
745 
746  Joint joint_8("joint_8");
747  joint_8.parent_to_joint_origin_transform.translation()(0) = 1.75;
748  joint_8.parent_link_name = "link_7";
749  joint_8.child_link_name = "link_6";
750  joint_8.type = JointType::CONTINUOUS;
751  joint_8.limits = std::make_shared<JointLimits>(0, 0, 0, 2, 1, 0.5);
752  EXPECT_TRUE(g.addJoint(joint_8));
753  EXPECT_EQ(g.getJoints().size(), 6);
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);
760 }
761 
762 TEST(TesseractSceneGraphUnit, TesseractSceneGraphRemoveJointUnit) // NOLINT
763 {
764  using namespace tesseract_scene_graph;
765  {
767 
768  EXPECT_EQ(g.getLinks().size(), 5);
769  EXPECT_EQ(g.getJoints().size(), 4);
770  EXPECT_TRUE(g.removeJoint("joint_4"));
771  EXPECT_TRUE(g.getJoint("joint_4") == nullptr);
772  EXPECT_TRUE(g.getLink("link_5") != nullptr); // The child link should remain
773  EXPECT_EQ(g.getLinks().size(), 5);
774  EXPECT_EQ(g.getJoints().size(), 3);
775  }
776 
777  { // Try to remove joint which does not exist
779  EXPECT_EQ(g.getLinks().size(), 5);
780  EXPECT_EQ(g.getJoints().size(), 4);
781  EXPECT_FALSE(g.removeJoint("joint_does_not_exist"));
782  EXPECT_EQ(g.getLinks().size(), 5);
783  EXPECT_EQ(g.getJoints().size(), 4);
784 
785  // Check Graph
786  checkSceneGraph(g);
787  }
788 
789  { // Make sure all children are removed if enabled
791  EXPECT_EQ(g.getLinks().size(), 5);
792  EXPECT_EQ(g.getJoints().size(), 4);
793  EXPECT_TRUE(g.removeJoint("joint_2", true));
794  EXPECT_EQ(g.getLinks().size(), 3);
795  EXPECT_EQ(g.getJoints().size(), 2);
796 
797  // Check Graph
798  checkSceneGraph(g);
799  }
800 }
801 
802 void printKDLTree(const KDL::SegmentMap::const_iterator& link, const std::string& prefix)
803 {
804  std::cout << prefix << "- Segment " << GetTreeElementSegment(link->second).getName() << " has "
805  << GetTreeElementChildren(link->second).size() << " children\n";
806 
807  for (auto child : GetTreeElementChildren(link->second))
808  printKDLTree(child, prefix + " ");
809 }
810 
812 {
813  using namespace tesseract_scene_graph;
814  SceneGraph g;
815 
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");
822 
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));
829 
830  Joint base_joint("base_joint");
831  base_joint.parent_link_name = "base_link";
832  base_joint.child_link_name = "link_1";
833  base_joint.type = JointType::FIXED;
834  EXPECT_TRUE(g.addJoint(base_joint));
835 
836  Joint joint_1("joint_1");
837  joint_1.parent_link_name = "link_1";
838  joint_1.child_link_name = "link_2";
839  joint_1.type = JointType::REVOLUTE;
840  joint_1.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
841  EXPECT_TRUE(g.addJoint(joint_1));
842 
843  Joint joint_2("joint_2");
844  joint_2.parent_to_joint_origin_transform.translation()(0) = 1.25;
845  joint_2.parent_link_name = "link_2";
846  joint_2.child_link_name = "link_3";
847  joint_2.type = JointType::REVOLUTE;
848  joint_2.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
849  EXPECT_TRUE(g.addJoint(joint_2));
850 
851  Joint joint_3("joint_3");
852  joint_3.parent_to_joint_origin_transform.translation()(0) = 1.25;
853  joint_3.parent_link_name = "link_3";
854  joint_3.child_link_name = "link_4";
855  joint_3.type = JointType::REVOLUTE;
856  joint_3.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
857  EXPECT_TRUE(g.addJoint(joint_3));
858 
859  Joint joint_4("joint_4");
860  joint_4.parent_to_joint_origin_transform.translation()(1) = 1.25;
861  joint_4.parent_link_name = "link_2";
862  joint_4.child_link_name = "link_5";
863  joint_4.type = JointType::REVOLUTE;
864  joint_4.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
865  EXPECT_TRUE(g.addJoint(joint_4));
866 
867  return g;
868 }
869 
871 {
872  using namespace tesseract_scene_graph;
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" };
875  SceneGraph g;
876 
877  EXPECT_TRUE(g.addLink(Link("world")));
878 
879  for (const auto& p : prefix)
880  {
881  for (const auto& link_name : link_names)
882  {
883  EXPECT_TRUE(g.addLink(Link(p + link_name)));
884  }
885  }
886 
887  for (const auto& p : prefix)
888  {
889  Joint world_joint(p + "word_joint");
890  if (p == prefix[0])
891  world_joint.parent_to_joint_origin_transform.translation()(0) = 1;
892  else
893  world_joint.parent_to_joint_origin_transform.translation()(0) = -1;
894 
895  world_joint.parent_link_name = "world";
896  world_joint.child_link_name = p + "base_link";
897  world_joint.type = JointType::FIXED;
898  EXPECT_TRUE(g.addJoint(world_joint));
899 
900  Joint base_joint(p + "base_joint");
901  base_joint.parent_link_name = p + "base_link";
902  base_joint.child_link_name = p + "link_1";
903  base_joint.type = JointType::FIXED;
904  EXPECT_TRUE(g.addJoint(base_joint));
905 
906  Joint joint_1(p + "joint_1");
907  joint_1.parent_link_name = p + "link_1";
908  joint_1.child_link_name = p + "link_2";
909  joint_1.type = JointType::REVOLUTE;
910  joint_1.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
911  EXPECT_TRUE(g.addJoint(joint_1));
912 
913  Joint joint_2(p + "joint_2");
914  joint_2.parent_to_joint_origin_transform.translation()(0) = 1.25;
915  joint_2.parent_link_name = p + "link_2";
916  joint_2.child_link_name = p + "link_3";
917  joint_2.type = JointType::REVOLUTE;
918  joint_2.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
919  EXPECT_TRUE(g.addJoint(joint_2));
920 
921  Joint joint_3(p + "joint_3");
922  joint_3.parent_to_joint_origin_transform.translation()(0) = 1.25;
923  joint_3.parent_link_name = p + "link_3";
924  joint_3.child_link_name = p + "link_4";
925  joint_3.type = JointType::REVOLUTE;
926  joint_3.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
927  EXPECT_TRUE(g.addJoint(joint_3));
928 
929  Joint joint_4(p + "joint_4");
930  joint_4.parent_to_joint_origin_transform.translation()(1) = 1.25;
931  joint_4.parent_link_name = p + "link_2";
932  joint_4.child_link_name = p + "link_5";
933  joint_4.type = JointType::REVOLUTE;
934  joint_4.limits = std::make_shared<JointLimits>(-1, 1, 0, 2, 3, 4);
935  EXPECT_TRUE(g.addJoint(joint_4));
936  }
937 
938  return g;
939 }
940 
941 void testSceneGraphKDLTree(KDL::Tree& tree)
942 {
943  KDL::TreeFkSolverPos_recursive solver(tree);
944  KDL::JntArray joints;
945  joints.resize(4);
946  for (unsigned int i = 0; i < 4; ++i)
947  joints(i) = 0;
948 
949  {
950  KDL::Frame frame;
951  solver.JntToCart(joints, frame, "base_link");
952  Eigen::Isometry3d e_frame = tesseract_scene_graph::convert(frame);
953  EXPECT_TRUE(e_frame.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
954  }
955 
956  {
957  KDL::Frame frame;
958  solver.JntToCart(joints, frame, "link_1");
959  Eigen::Isometry3d e_frame = tesseract_scene_graph::convert(frame);
960  EXPECT_TRUE(e_frame.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
961  }
962 
963  {
964  KDL::Frame frame;
965  solver.JntToCart(joints, frame, "link_2");
966  Eigen::Isometry3d e_frame = tesseract_scene_graph::convert(frame);
967  EXPECT_TRUE(e_frame.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
968  }
969 
970  {
971  KDL::Frame frame;
972  solver.JntToCart(joints, frame, "link_3");
973  Eigen::Isometry3d e_frame = tesseract_scene_graph::convert(frame);
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));
977  }
978 
979  {
980  KDL::Frame frame;
981  solver.JntToCart(joints, frame, "link_4");
982  Eigen::Isometry3d e_frame = tesseract_scene_graph::convert(frame);
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));
986  }
987 
988  {
989  KDL::Frame frame;
990  solver.JntToCart(joints, frame, "link_5");
991  Eigen::Isometry3d e_frame = tesseract_scene_graph::convert(frame);
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));
995  }
996 }
997 
1000  const std::unordered_map<std::string, double>& joint_values)
1001 {
1002  std::vector<std::string> prefix{ "left_", "right_" };
1003  KDL::TreeFkSolverPos_recursive solver(data.tree);
1004  KDL::TreeFkSolverPos_recursive full_solver(data.tree);
1005 
1006  KDL::JntArray joints;
1007  joints.resize(data.tree.getNrOfJoints());
1008  for (unsigned int i = 0; i < data.tree.getNrOfJoints(); ++i)
1009  joints(i) = joint_values.at(data.active_joint_names[i]);
1010 
1011  KDL::JntArray full_joints;
1012  joints.resize(full_data.tree.getNrOfJoints());
1013  for (unsigned int i = 0; i < full_data.tree.getNrOfJoints(); ++i)
1014  joints(i) = joint_values.at(full_data.active_joint_names[i]);
1015 
1016  EXPECT_EQ(data.tree.getRootSegment()->first, "world");
1017  EXPECT_EQ(full_data.tree.getRootSegment()->first, "world");
1018 
1019  for (const auto& p : prefix)
1020  {
1021  {
1022  KDL::Frame frame;
1023  solver.JntToCart(joints, frame, p + "link_2");
1024 
1025  KDL::Frame c_frame;
1026  full_solver.JntToCart(full_joints, c_frame, p + "link_2");
1027 
1028  EXPECT_TRUE(tesseract_scene_graph::convert(frame).isApprox(tesseract_scene_graph::convert(c_frame), 1e-8));
1029  }
1030 
1031  {
1032  KDL::Frame frame;
1033  solver.JntToCart(joints, frame, p + "link_3");
1034 
1035  KDL::Frame c_frame;
1036  full_solver.JntToCart(full_joints, c_frame, p + "link_3");
1037 
1038  EXPECT_TRUE(tesseract_scene_graph::convert(frame).isApprox(tesseract_scene_graph::convert(c_frame), 1e-8));
1039  }
1040 
1041  {
1042  KDL::Frame frame;
1043  solver.JntToCart(joints, frame, p + "link_4");
1044 
1045  KDL::Frame c_frame;
1046  full_solver.JntToCart(full_joints, c_frame, p + "link_4");
1047 
1048  EXPECT_TRUE(tesseract_scene_graph::convert(frame).isApprox(tesseract_scene_graph::convert(c_frame), 1e-8));
1049  }
1050 
1051  {
1052  KDL::Frame frame;
1053  solver.JntToCart(joints, frame, p + "link_5");
1054 
1055  KDL::Frame c_frame;
1056  full_solver.JntToCart(full_joints, c_frame, p + "link_5");
1057 
1058  EXPECT_TRUE(tesseract_scene_graph::convert(frame).isApprox(tesseract_scene_graph::convert(c_frame), 1e-8));
1059  }
1060  }
1061 }
1062 
1063 TEST(TesseractSceneGraphUnit, GetSourceLinkUnit) // NOLINT
1064 {
1065  using namespace tesseract_scene_graph;
1067 
1068  for (int i = 1; i <= 3; ++i)
1069  {
1070  std::string link_name = "link_" + std::to_string(i);
1071  std::string joint_name = "joint_" + std::to_string(i);
1072  Link::ConstPtr l = g.getSourceLink(joint_name);
1073  Joint::ConstPtr j = g.getJoint(joint_name);
1074  EXPECT_EQ(l->getName(), link_name);
1075  EXPECT_EQ(j->parent_link_name, link_name);
1076  EXPECT_TRUE(g.getLink(link_name) == l);
1077  }
1078 }
1079 
1080 TEST(TesseractSceneGraphUnit, GetTargetLinkUnit) // NOLINT
1081 {
1082  using namespace tesseract_scene_graph;
1084 
1085  for (int i = 1; i <= 3; ++i)
1086  {
1087  std::string link_name = "link_" + std::to_string(i + 1);
1088  std::string joint_name = "joint_" + std::to_string(i);
1089  Link::ConstPtr l = g.getTargetLink(joint_name);
1090  Joint::ConstPtr j = g.getJoint(joint_name);
1091  EXPECT_EQ(l->getName(), link_name);
1092  EXPECT_EQ(j->child_link_name, link_name);
1093  EXPECT_TRUE(g.getLink(link_name) == l);
1094  }
1095 }
1096 
1097 TEST(TesseractSceneGraphUnit, GetInboundJointsUnit) // NOLINT
1098 {
1099  using namespace tesseract_scene_graph;
1101 
1102  for (int i = 2; i <= 4; ++i)
1103  {
1104  std::string link_name = "link_" + std::to_string(i);
1105  std::string joint_name = "joint_" + std::to_string(i - 1);
1106  std::vector<Joint::ConstPtr> j = g.getInboundJoints(link_name);
1107  Link::ConstPtr l = g.getLink(link_name);
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]);
1112  }
1113 }
1114 
1115 TEST(TesseractSceneGraphUnit, GetOutboundJointsUnit) // NOLINT
1116 {
1117  using namespace tesseract_scene_graph;
1119 
1120  for (int i = 1; i <= 3; ++i)
1121  {
1122  std::string link_name = "link_" + std::to_string(i);
1123  std::string joint_name = "joint_" + std::to_string(i);
1124  std::vector<Joint::ConstPtr> j = g.getOutboundJoints(link_name);
1125  Link::ConstPtr l = g.getLink(link_name);
1126  if (i == 2)
1127  {
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]);
1132 
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]);
1136  }
1137  else
1138  {
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]);
1143  }
1144  }
1145 }
1146 
1147 TEST(TesseractSceneGraphUnit, LoadKDLUnit) // NOLINT
1148 {
1149  using namespace tesseract_scene_graph;
1151 
1152  // Check to make sure all links are enabled
1153  for (const auto& link : g.getLinks())
1154  {
1155  EXPECT_TRUE(g.getLinkCollisionEnabled(link->getName()));
1156  EXPECT_TRUE(g.getLinkVisibility(link->getName()));
1157  }
1158 
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" };
1163  {
1164  KDLTreeData data = parseSceneGraph(g);
1165 
1166  EXPECT_TRUE(tesseract_common::isIdentical(data.link_names, link_names, false));
1167  EXPECT_TRUE(tesseract_common::isIdentical(data.static_link_names, static_link_names, false));
1168  EXPECT_TRUE(tesseract_common::isIdentical(data.active_joint_names, joint_names, false));
1169  EXPECT_TRUE(tesseract_common::isIdentical(data.active_link_names, active_link_names, false));
1170 
1172 
1173  // walk through tree
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();
1178  printKDLTree(root, "");
1179 
1180  EXPECT_EQ(data.tree.getNrOfJoints(), 4);
1181  EXPECT_EQ(data.tree.getNrOfSegments(), 5);
1182  }
1183 
1184  SceneGraph::Ptr g_clone = g.clone();
1185 
1186  // Check to make sure all links are enabled
1187  for (const auto& link : g_clone->getLinks())
1188  {
1189  EXPECT_TRUE(g_clone->getLinkCollisionEnabled(link->getName()));
1190  EXPECT_TRUE(g_clone->getLinkVisibility(link->getName()));
1191  }
1192 
1193  {
1194  KDLTreeData data = parseSceneGraph(*g_clone);
1195 
1196  EXPECT_TRUE(tesseract_common::isIdentical(data.link_names, link_names, false));
1197  EXPECT_TRUE(tesseract_common::isIdentical(data.static_link_names, static_link_names, false));
1198  EXPECT_TRUE(tesseract_common::isIdentical(data.active_joint_names, joint_names, false));
1199  EXPECT_TRUE(tesseract_common::isIdentical(data.active_link_names, active_link_names, false));
1200 
1202 
1203  // walk through tree
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();
1208  printKDLTree(root, "");
1209 
1210  EXPECT_EQ(data.tree.getNrOfJoints(), 4);
1211  EXPECT_EQ(data.tree.getNrOfSegments(), 5);
1212  }
1213 }
1214 
1215 TEST(TesseractSceneGraphUnit, LoadSubKDLUnit) // NOLINT
1216 {
1217  using namespace tesseract_scene_graph;
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" };
1225 
1226  std::vector<std::string> static_link_names{ "world", "left_link_2", "right_link_2" };
1227 
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" };
1230 
1231  std::unordered_map<std::string, double> joint_values;
1232  for (const auto& joint_name : joint_names)
1233  {
1234  auto jnt = g.getJoint(joint_name);
1235  std::uniform_real_distribution<double> sample(jnt->limits->lower, jnt->limits->upper);
1236  joint_values[joint_name] = sample(tesseract_common::mersenne);
1237  }
1238 
1239  {
1240  KDLTreeData full_data = parseSceneGraph(g);
1241  KDLTreeData data = parseSceneGraph(g, sub_joint_names, joint_values, tesseract_common::TransformMap());
1242 
1243  EXPECT_TRUE(tesseract_common::isIdentical(data.link_names, link_names, false));
1244  EXPECT_TRUE(tesseract_common::isIdentical(data.static_link_names, static_link_names, false));
1245  EXPECT_TRUE(tesseract_common::isIdentical(data.active_joint_names, sub_joint_names, false));
1246  EXPECT_TRUE(tesseract_common::isIdentical(data.active_link_names, active_link_names, false));
1247 
1248  testSubSceneGraphKDLTree(data, full_data, joint_values);
1249 
1250  // walk through tree
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();
1255  printKDLTree(root, "");
1256 
1257  EXPECT_EQ(data.tree.getNrOfJoints(), 6);
1258  EXPECT_EQ(data.tree.getNrOfSegments(), 8);
1259  }
1260 
1261  SceneGraph::Ptr g_clone = g.clone();
1262 
1263  // Check to make sure all links are enabled
1264  for (const auto& link : g_clone->getLinks())
1265  {
1266  EXPECT_TRUE(g_clone->getLinkCollisionEnabled(link->getName()));
1267  EXPECT_TRUE(g_clone->getLinkVisibility(link->getName()));
1268  }
1269 
1270  {
1271  KDLTreeData full_data = parseSceneGraph(g);
1272  KDLTreeData data = parseSceneGraph(*g_clone, sub_joint_names, joint_values, tesseract_common::TransformMap());
1273 
1274  EXPECT_TRUE(tesseract_common::isIdentical(data.link_names, link_names, false));
1275  EXPECT_TRUE(tesseract_common::isIdentical(data.static_link_names, static_link_names, false));
1276  EXPECT_TRUE(tesseract_common::isIdentical(data.active_joint_names, sub_joint_names, false));
1277  EXPECT_TRUE(tesseract_common::isIdentical(data.active_link_names, active_link_names, false));
1278 
1279  testSubSceneGraphKDLTree(data, full_data, joint_values);
1280 
1281  // walk through tree
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();
1286  printKDLTree(root, "");
1287 
1288  EXPECT_EQ(data.tree.getNrOfJoints(), 6);
1289  EXPECT_EQ(data.tree.getNrOfSegments(), 8);
1290  }
1291 }
1292 
1293 TEST(TesseractSceneGraphUnit, TestChangeJointOrigin) // NOLINT
1294 {
1295  using namespace tesseract_scene_graph;
1296  SceneGraph g;
1297 
1298  Link link_1("link_n1");
1299  Link link_2("link_n2");
1300 
1301  Joint joint_1("joint_n1");
1302  joint_1.parent_link_name = "link_n1";
1303  joint_1.child_link_name = "link_n2";
1304  joint_1.type = JointType::FIXED;
1305 
1306  g.addLink(link_1);
1307  g.addLink(link_2);
1308  g.addJoint(joint_1);
1309 
1310  Eigen::Isometry3d new_origin = Eigen::Isometry3d::Identity();
1311  new_origin.translation()(0) += 1.234;
1312  g.changeJointOrigin("joint_n1", new_origin);
1313 
1314  // Check that the transform got updated and the edge was recalculated.
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());
1319 }
1320 
1321 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertEmptyUnit) // NOLINT
1322 {
1323  // Test inserting graph into empty graph
1326  acm.addAllowedCollision("link1", "link2", "test");
1327  acm.addAllowedCollision("link1", "link3", "test");
1328  g.getAllowedCollisionMatrix()->insertAllowedCollisionMatrix(acm);
1329  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1330 
1332  EXPECT_TRUE(ng.insertSceneGraph(g));
1333 
1334  // Check Graph
1335  checkSceneGraph(ng);
1336 
1337  EXPECT_EQ(g.getLinks().size(), ng.getLinks().size());
1338  EXPECT_EQ(g.getJoints().size(), ng.getJoints().size());
1339  EXPECT_EQ(g.getRoot(), ng.getRoot());
1340  EXPECT_EQ(ng.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1341 
1342  for (const auto& l : g.getLinks())
1343  {
1344  EXPECT_TRUE(ng.getLink(l->getName()) != nullptr);
1345  }
1346 
1347  for (const auto& j : g.getJoints())
1348  {
1349  EXPECT_TRUE(ng.getJoint(j->getName()) != nullptr);
1350  }
1351 
1352  for (const auto& entry : g.getAllowedCollisionMatrix()->getAllAllowedCollisions())
1353  {
1354  EXPECT_TRUE(ng.getAllowedCollisionMatrix()->isCollisionAllowed(entry.first.first, entry.first.second));
1355  }
1356 
1357  // Save Graph
1358  ng.saveDOT(tesseract_common::getTempPath() + "graph_insert_empty_example.dot");
1359 }
1360 
1361 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertWithoutJointNoPrefixUnit) // NOLINT
1362 {
1363  // Test inserting graph into empty graph
1366  acm.addAllowedCollision("link1", "link2", "test");
1367  acm.addAllowedCollision("link1", "link3", "test");
1368  g.getAllowedCollisionMatrix()->insertAllowedCollisionMatrix(acm);
1369  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1370 
1372  ng.getAllowedCollisionMatrix()->insertAllowedCollisionMatrix(acm);
1373  EXPECT_EQ(ng.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1374 
1375  // Insert without prefix which should fail leaving the original graph
1376  EXPECT_FALSE(ng.insertSceneGraph(g));
1377  EXPECT_EQ(g.getLinks().size(), ng.getLinks().size());
1378  EXPECT_EQ(g.getJoints().size(), ng.getJoints().size());
1379  EXPECT_EQ(g.getRoot(), ng.getRoot());
1380  EXPECT_EQ(ng.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1381 
1382  for (const auto& l : g.getLinks())
1383  {
1384  EXPECT_TRUE(ng.getLink(l->getName()) != nullptr);
1385  }
1386 
1387  for (const auto& j : g.getJoints())
1388  {
1389  EXPECT_TRUE(ng.getJoint(j->getName()) != nullptr);
1390  }
1391 
1392  for (const auto& entry : g.getAllowedCollisionMatrix()->getAllAllowedCollisions())
1393  {
1394  EXPECT_TRUE(ng.getAllowedCollisionMatrix()->isCollisionAllowed(entry.first.first, entry.first.second));
1395  }
1396 }
1397 
1398 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertWithoutJointWithPrefixUnit) // NOLINT
1399 {
1400  // Test inserting graph into empty graph
1403  acm.addAllowedCollision("link1", "link2", "test");
1404  acm.addAllowedCollision("link1", "link3", "test");
1405  g.getAllowedCollisionMatrix()->insertAllowedCollisionMatrix(acm);
1406  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1407 
1409  ng.getAllowedCollisionMatrix()->insertAllowedCollisionMatrix(acm);
1410  EXPECT_EQ(ng.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1411 
1412  std::string prefix = "r1::";
1413  EXPECT_TRUE(ng.insertSceneGraph(g, prefix));
1414  EXPECT_FALSE(ng.isTree());
1415 
1416  // Check Graph
1417  checkSceneGraph(ng);
1418 
1419  EXPECT_EQ(2 * g.getLinks().size(), ng.getLinks().size());
1420  EXPECT_EQ(2 * g.getJoints().size(), ng.getJoints().size());
1421  EXPECT_EQ(g.getRoot(), ng.getRoot());
1422  EXPECT_EQ(ng.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 4);
1423 
1424  for (const auto& l : g.getLinks())
1425  {
1426  EXPECT_TRUE(ng.getLink(l->getName()) != nullptr);
1427  EXPECT_TRUE(ng.getLink(prefix + l->getName()) != nullptr);
1428  }
1429 
1430  for (const auto& j : g.getJoints())
1431  {
1432  EXPECT_TRUE(ng.getJoint(j->getName()) != nullptr);
1433  EXPECT_TRUE(ng.getJoint(prefix + j->getName()) != nullptr);
1434  }
1435 
1436  for (const auto& entry : g.getAllowedCollisionMatrix()->getAllAllowedCollisions())
1437  {
1438  EXPECT_TRUE(ng.getAllowedCollisionMatrix()->isCollisionAllowed(entry.first.first, entry.first.second));
1439  EXPECT_TRUE(
1440  ng.getAllowedCollisionMatrix()->isCollisionAllowed(prefix + entry.first.first, prefix + entry.first.second));
1441  }
1442 
1443  // Save Graph
1444  ng.saveDOT(tesseract_common::getTempPath() + "graph_insert_example.dot");
1445 }
1446 
1447 TEST(TesseractSceneGraphUnit, TesseractSceneGraphInsertWithJointWithPrefixUnit) // NOLINT
1448 {
1449  // Test inserting graph into empty graph
1452  acm.addAllowedCollision("link1", "link2", "test");
1453  acm.addAllowedCollision("link1", "link3", "test");
1454  g.getAllowedCollisionMatrix()->insertAllowedCollisionMatrix(acm);
1455  EXPECT_EQ(g.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1456  EXPECT_TRUE(g.isCollisionAllowed("link1", "link2"));
1457  EXPECT_TRUE(g.isCollisionAllowed("link1", "link3"));
1458 
1460  ng.getAllowedCollisionMatrix()->insertAllowedCollisionMatrix(acm);
1461  EXPECT_EQ(ng.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 2);
1462  EXPECT_TRUE(ng.isCollisionAllowed("link1", "link2"));
1463  EXPECT_TRUE(ng.isCollisionAllowed("link1", "link3"));
1464 
1465  std::string prefix = "r1::";
1466 
1467  tesseract_scene_graph::Joint new_joint("insert_graph_joint");
1468  new_joint.parent_link_name = "base_link";
1469  new_joint.child_link_name = prefix + new_joint.parent_link_name;
1471  new_joint.parent_to_joint_origin_transform = Eigen::Translation3d(1, 0, 0) * Eigen::Isometry3d::Identity();
1472  EXPECT_TRUE(ng.insertSceneGraph(g, new_joint, prefix));
1473  EXPECT_TRUE(ng.isTree());
1474 
1475  // Check Graph
1476  checkSceneGraph(ng);
1477 
1478  EXPECT_EQ(2 * g.getLinks().size(), ng.getLinks().size());
1479  EXPECT_EQ((2 * g.getJoints().size()) + 1, ng.getJoints().size());
1480  EXPECT_EQ(g.getRoot(), ng.getRoot());
1481  EXPECT_EQ(ng.getAllowedCollisionMatrix()->getAllAllowedCollisions().size(), 4);
1482 
1483  for (const auto& l : g.getLinks())
1484  {
1485  EXPECT_TRUE(ng.getLink(l->getName()) != nullptr);
1486  EXPECT_TRUE(ng.getLink(prefix + l->getName()) != nullptr);
1487  }
1488 
1489  for (const auto& j : g.getJoints())
1490  {
1491  EXPECT_TRUE(ng.getJoint(j->getName()) != nullptr);
1492  EXPECT_TRUE(ng.getJoint(prefix + j->getName()) != nullptr);
1493  }
1494 
1495  for (const auto& entry : g.getAllowedCollisionMatrix()->getAllAllowedCollisions())
1496  {
1497  EXPECT_TRUE(ng.getAllowedCollisionMatrix()->isCollisionAllowed(entry.first.first, entry.first.second));
1498  EXPECT_TRUE(
1499  ng.getAllowedCollisionMatrix()->isCollisionAllowed(prefix + entry.first.first, prefix + entry.first.second));
1500  }
1501 
1502  // Save Graph
1503  ng.saveDOT(tesseract_common::getTempPath() + "graph_insert_with_joint_example.dot");
1504 }
1505 
1506 TEST(TesseractSceneGraphUnit, TesseractSceneState) // NOLINT
1507 {
1509  state.joints["j1"] = 1;
1510  state.joints["j2"] = 2;
1511  state.joints["j3"] = 3;
1512  state.joints["j4"] = 4;
1513  state.joints["j5"] = 5;
1514  state.joints["j6"] = 6;
1515 
1516  Eigen::VectorXd jv = state.getJointValues({ "j2", "j3", "j6" });
1517 
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);
1521 }
1522 
1523 TEST(TesseractSceneGraphUnit, TesseractSceneGraphKDLConversions) // NOLINT
1524 {
1525  { // Eigen to KDL
1526  Eigen::Isometry3d t = Eigen::Isometry3d::Identity();
1527  t.translation() = Eigen::Vector3d(1, 2, 3);
1528  KDL::Frame kdl_t = tesseract_scene_graph::convert(t);
1529  for (int i = 0; i < 4; ++i)
1530  {
1531  for (int j = 0; j < 4; ++j)
1532  {
1533  EXPECT_DOUBLE_EQ(kdl_t(i, j), t(i, j)); // NOLINT
1534  }
1535  }
1536  }
1537 
1538  { // KDL to Eigen
1539  KDL::Frame kdl_t = KDL::Frame::Identity();
1540  kdl_t.p = KDL::Vector(1, 2, 3);
1541  Eigen::Isometry3d t = tesseract_scene_graph::convert(kdl_t);
1542  for (int i = 0; i < 4; ++i)
1543  {
1544  for (int j = 0; j < 4; ++j)
1545  {
1546  EXPECT_DOUBLE_EQ(kdl_t(i, j), t(i, j));
1547  }
1548  }
1549  }
1550 
1551  { // Eigen to KDL
1552  Eigen::Vector3d v(1, 2, 3);
1553  KDL::Vector kdl_v = tesseract_scene_graph::convert(v);
1554  for (int i = 0; i < 3; ++i)
1555  {
1556  EXPECT_DOUBLE_EQ(kdl_v(i), v(i));
1557  }
1558  }
1559 
1560  { // KDL to Eigen
1561  KDL::Vector kdl_v(1, 2, 3);
1562  Eigen::Vector3d v = tesseract_scene_graph::convert(kdl_v);
1563  for (int i = 0; i < 3; ++i)
1564  {
1565  EXPECT_DOUBLE_EQ(kdl_v(i), v(i));
1566  }
1567  }
1568 
1569  { // Eigen to KDL
1570  Eigen::MatrixXd t = Eigen::MatrixXd::Random(6, 6);
1571  KDL::Jacobian kdl_t = tesseract_scene_graph::convert(t);
1572  for (int i = 0; i < 6; ++i)
1573  {
1574  for (int j = 0; j < 6; ++j)
1575  {
1576  EXPECT_DOUBLE_EQ(kdl_t(static_cast<unsigned>(i), static_cast<unsigned>(j)), t(i, j));
1577  }
1578  }
1579 
1580  Eigen::MatrixXd t_wrong_size = Eigen::MatrixXd::Random(7, 7);
1581  EXPECT_ANY_THROW(tesseract_scene_graph::convert(t_wrong_size)); // NOLINT
1582  }
1583 
1584  { // KDL to Eigen
1585  KDL::Jacobian kdl_t;
1586  kdl_t.resize(6);
1587  kdl_t.data = Eigen::MatrixXd::Random(6, 6);
1588  Eigen::MatrixXd t = tesseract_scene_graph::convert(kdl_t);
1589  EXPECT_EQ(t.cols(), 6);
1590  EXPECT_EQ(t.rows(), 6);
1591  for (int i = 0; i < 6; ++i)
1592  {
1593  for (int j = 0; j < 6; ++j)
1594  {
1595  EXPECT_DOUBLE_EQ(kdl_t(static_cast<unsigned>(i), static_cast<unsigned>(j)), t(i, j));
1596  }
1597  }
1598  }
1599 
1600  { // KDL to Eigen
1601  KDL::Jacobian kdl_t;
1602  kdl_t.resize(6);
1603  kdl_t.data = Eigen::MatrixXd::Random(6, 6);
1604 
1605  std::vector<int> q_nrs{ 0, 2, 5 };
1606  Eigen::MatrixXd t = tesseract_scene_graph::convert(kdl_t, q_nrs);
1607  EXPECT_EQ(t.cols(), 3);
1608  EXPECT_EQ(t.rows(), 6);
1609  for (int i = 0; i < 6; ++i)
1610  {
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));
1614  }
1615  }
1616 }
1617 
1618 int main(int argc, char** argv)
1619 {
1620  testing::InitGoogleTest(&argc, argv);
1621 
1622  return RUN_ALL_TESTS();
1623 }
tesseract_scene_graph::JointType::REVOLUTE
@ REVOLUTE
tesseract_scene_graph::SceneGraph::setRoot
bool setRoot(const std::string &name)
Sets the root link name (aka. World Coordinate Frame)
Definition: graph.cpp:256
tesseract_common::getTempPath
std::string getTempPath()
tesseract_scene_graph::JointType::FLOATING
@ FLOATING
tesseract_scene_graph::SceneGraph::getLinkCollisionEnabled
bool getLinkCollisionEnabled(const std::string &name) const
Get whether a link should be considered during collision checking.
Definition: graph.cpp:453
tesseract_scene_graph::SceneGraph::clone
SceneGraph::UPtr clone() const
Clone the scene graph.
Definition: graph.cpp:216
tesseract_scene_graph::SceneGraph::saveDOT
void saveDOT(const std::string &path) const
Saves Graph as Graph Description Language (DOT)
Definition: graph.cpp:977
tesseract_common::isIdentical
bool isIdentical(const std::vector< T > &vec1, const std::vector< T > &vec2, bool ordered=true, const std::function< bool(const T &, const T &)> &equal_pred=[](const T &v1, const T &v2) { return v1==v2;}, const std::function< bool(const T &, const T &)> &comp=[](const T &v1, const T &v2) { return v1< v2;})
tesseract_scene_graph::SceneGraph::changeJointVelocityLimits
bool changeJointVelocityLimits(const std::string &name, double limit)
Changes the velocity limits associated with a joint.
Definition: graph.cpp:684
tesseract_scene_graph::SceneGraph::getLinks
std::vector< std::shared_ptr< const Link > > getLinks() const
Get a vector links in the scene graph.
Definition: graph.cpp:341
tesseract_scene_graph::SceneGraph::changeJointLimits
bool changeJointLimits(const std::string &name, const JointLimits &limits)
Changes the limits of a joint. The JointLimits::Ptr remains the same, but the values passed in are as...
Definition: graph.cpp:631
tesseract_scene_graph::Joint::clone
Joint clone() const
Clone the joint keeping the name.
Definition: joint.cpp:275
tesseract_scene_graph::KDLTreeData::active_joint_names
std::vector< std::string > active_joint_names
Definition: kdl_parser.h:164
tesseract_scene_graph::KDLTreeData::static_link_names
std::vector< std::string > static_link_names
Definition: kdl_parser.h:168
tesseract_scene_graph::SceneGraph::isTree
bool isTree() const
Determine if the graph is a tree.
Definition: graph.cpp:879
utils.h
tesseract_scene_graph::SceneGraph::changeJointPositionLimits
bool changeJointPositionLimits(const std::string &name, double lower, double upper)
Changes the position limits associated with a joint.
Definition: graph.cpp:661
tesseract_scene_graph::SceneGraph::getJoints
std::vector< std::shared_ptr< const Joint > > getJoints() const
Get a vector of joints in the scene graph.
Definition: graph.cpp:585
boost::vertex_link
@ vertex_link
Definition: graph.h:53
tesseract_scene_graph::SceneGraph::getAllowedCollisionMatrix
std::shared_ptr< const tesseract_common::AllowedCollisionMatrix > getAllowedCollisionMatrix() const
Get the allowed collision matrix.
Definition: graph.cpp:798
tesseract_scene_graph::SceneGraph::addAllowedCollision
void addAllowedCollision(const std::string &link_name1, const std::string &link_name2, const std::string &reason)
Disable collision between two collision objects.
Definition: graph.cpp:777
tesseract_scene_graph::JointLimits::ConstPtr
std::shared_ptr< const JointLimits > ConstPtr
Definition: joint.h:96
tesseract_scene_graph::SceneGraph::getJointLimits
std::shared_ptr< const JointLimits > getJointLimits(const std::string &name)
Gets the limits of the joint specified by name.
Definition: graph.cpp:758
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_scene_graph::Joint::parent_to_joint_origin_transform
Eigen::Isometry3d parent_to_joint_origin_transform
transform from Parent Link frame to Joint frame
Definition: joint.h:314
tesseract_scene_graph::convert
KDL::Frame convert(const Eigen::Isometry3d &transform)
Convert Eigen::Isometry3d to KDL::Frame.
Definition: kdl_parser.cpp:83
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::SceneGraph::moveJoint
bool moveJoint(const std::string &name, const std::string &parent_link)
Move joint to new parent link.
Definition: graph.cpp:557
tesseract_scene_graph::SceneGraph
Definition: graph.h:125
tesseract_scene_graph::Joint::ConstPtr
std::shared_ptr< const Joint > ConstPtr
Definition: joint.h:278
tesseract_scene_graph::SceneGraph::getOutboundJoints
std::vector< std::shared_ptr< const Joint > > getOutboundJoints(const std::string &link_name) const
Get outbound joints for a link.
Definition: graph.cpp:839
tesseract_scene_graph::SceneGraph::addLink
bool addLink(const Link &link, bool replace_allowed=false)
Adds a link to the graph.
Definition: graph.cpp:273
tesseract_scene_graph::KDLTreeData::link_names
std::vector< std::string > link_names
Definition: kdl_parser.h:166
joint.h
tesseract_scene_graph::SceneGraph::getAdjacentLinkNames
std::vector< std::string > getAdjacentLinkNames(const std::string &name) const
Get a vector of adjacent link names provided a link name.
Definition: graph.cpp:897
tesseract_scene_graph::parseSceneGraph
KDLTreeData parseSceneGraph(const SceneGraph &scene_graph)
Convert a Tesseract SceneGraph into a KDL Tree.
Definition: kdl_parser.cpp:491
geometries.h
tesseract_scene_graph::SceneGraph::getName
const std::string & getName() const
Sets the graph name.
Definition: graph.cpp:251
tesseract_scene_graph::SceneGraph::getInvAdjacentLinkNames
std::vector< std::string > getInvAdjacentLinkNames(const std::string &name) const
Geta a vectpr pf inverse adjacent link names provided a link name.
Definition: graph.cpp:907
tesseract_scene_graph::SceneGraph::removeAllowedCollision
void removeAllowedCollision(const std::string &link_name1, const std::string &link_name2)
Remove disabled collision pair from allowed collision matrix.
Definition: graph.cpp:784
tesseract_scene_graph::JointType::PLANAR
@ PLANAR
tesseract_scene_graph::SceneState
This holds a state of the scene.
Definition: scene_state.h:59
testSceneGraphKDLTree
void testSceneGraphKDLTree(KDL::Tree &tree)
Definition: tesseract_scene_graph_unit.cpp:941
tesseract_scene_graph::SceneGraph::isCollisionAllowed
bool isCollisionAllowed(const std::string &link_name1, const std::string &link_name2) const
Check if two links are allowed to be in collision.
Definition: graph.cpp:793
tesseract_scene_graph::SceneGraph::removeJoint
bool removeJoint(const std::string &name, bool recursive=false)
Removes a joint from the graph.
Definition: graph.cpp:534
tesseract_scene_graph::JointLimits::upper
double upper
Definition: joint.h:108
tesseract_scene_graph::SceneGraph::changeJointOrigin
bool changeJointOrigin(const std::string &name, const Eigen::Isometry3d &new_origin)
Changes the "origin" transform of the joint and recomputes the associated edge.
Definition: graph.cpp:608
tesseract_scene_graph::SceneGraph::moveLink
bool moveLink(const Joint &joint)
Move link defined by provided joint This deletes all inbound joints on the parent link defined by the...
Definition: graph.cpp:408
buildTestSceneGraphForSubTree
tesseract_scene_graph::SceneGraph buildTestSceneGraphForSubTree()
Definition: tesseract_scene_graph_unit.cpp:870
tesseract_scene_graph::Joint::child_link_name
std::string child_link_name
Definition: joint.h:307
tesseract_scene_graph::Joint::limits
JointLimits::Ptr limits
Joint Limits.
Definition: joint.h:320
runTest
void runTest(tesseract_scene_graph::SceneGraph &g)
Definition: tesseract_scene_graph_unit.cpp:95
tesseract_scene_graph::SceneGraph::getEdge
Edge getEdge(const std::string &name) const
Get the graph edge by name.
Definition: graph.cpp:1118
tesseract_scene_graph::SceneGraph::getShortestPath
ShortestPath getShortestPath(const std::string &root, const std::string &tip) const
Get the shortest path between two links.
Definition: graph.cpp:1008
tesseract_scene_graph::SceneGraph::addJoint
bool addJoint(const Joint &joint)
Adds joint to the graph.
Definition: graph.cpp:460
tesseract_scene_graph::SceneGraph::getInboundJoints
std::vector< std::shared_ptr< const Joint > > getInboundJoints(const std::string &link_name) const
Get inbound joints for a link.
Definition: graph.cpp:819
tesseract_common::mersenne
static std::mt19937 mersenne
tesseract_scene_graph::JointType::PRISMATIC
@ PRISMATIC
tesseract_scene_graph::SceneState::joints
std::unordered_map< std::string, double > joints
The joint values used for calculating the joint and link transforms.
Definition: scene_state.h:71
tesseract_scene_graph::KDLTreeData::active_link_names
std::vector< std::string > active_link_names
Definition: kdl_parser.h:167
tesseract_scene_graph::SceneGraph::getLinkVisibility
bool getLinkVisibility(const std::string &name) const
Get a given links visibility setting.
Definition: graph.cpp:439
tesseract_scene_graph::SceneGraph::getSourceLink
std::shared_ptr< const Link > getSourceLink(const std::string &joint_name) const
Get the source link (parent link) for a joint.
Definition: graph.cpp:805
tesseract_scene_graph::SceneGraph::getJointChildrenNames
std::vector< std::string > getJointChildrenNames(const std::string &name) const
Get all children link names for a given joint name.
Definition: graph.cpp:927
tesseract_scene_graph::SceneGraph::insertSceneGraph
bool insertSceneGraph(const tesseract_scene_graph::SceneGraph &scene_graph, const std::string &prefix="")
Merge a graph into the current graph.
Definition: graph.cpp:1158
testSubSceneGraphKDLTree
void testSubSceneGraphKDLTree(tesseract_scene_graph::KDLTreeData &data, tesseract_scene_graph::KDLTreeData &full_data, const std::unordered_map< std::string, double > &joint_values)
Definition: tesseract_scene_graph_unit.cpp:998
kdl_parser.h
tesseract_scene_graph::SceneGraph::getActiveJoints
std::vector< std::shared_ptr< const Joint > > getActiveJoints() const
Get a vector of active joints in the scene graph.
Definition: graph.cpp:595
tesseract_scene_graph::SceneGraph::getTargetLink
std::shared_ptr< const Link > getTargetLink(const std::string &joint_name) const
Get the target link (child link) for a joint.
Definition: graph.cpp:812
tesseract_scene_graph::ShortestPath
Holds the shortest path information.
Definition: graph.h:113
tesseract_scene_graph::JointLimits
Definition: joint.h:92
main
int main(int argc, char **argv)
Definition: tesseract_scene_graph_unit.cpp:1618
tesseract_scene_graph::KDLTreeData
The KDLTreeData populated when parsing scene graph.
Definition: kdl_parser.h:157
tesseract_scene_graph::JointType::CONTINUOUS
@ CONTINUOUS
tesseract_scene_graph::Joint
Definition: joint.h:272
graph.h
A basic scene graph using boost.
tesseract_scene_graph::SceneGraph::clearAllowedCollisions
void clearAllowedCollisions()
Remove all allowed collisions.
Definition: graph.cpp:791
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_scene_graph::SceneState::getJointValues
Eigen::VectorXd getJointValues(const std::vector< std::string > &joint_names) const
Definition: scene_state.cpp:45
tesseract_scene_graph::SceneGraph::getRoot
const std::string & getRoot() const
Gets the root link name (aka. World Coordinate Frame)
Definition: graph.cpp:268
tesseract_common::AllowedCollisionMatrix
tesseract_scene_graph::SceneGraph::getJoint
std::shared_ptr< const Joint > getJoint(const std::string &name) const
Get a joint in the graph.
Definition: graph.cpp:525
tesseract_scene_graph::SceneGraph::changeJointJerkLimits
bool changeJointJerkLimits(const std::string &name, double limit)
Changes the jerk limits associated with a joint.
Definition: graph.cpp:732
tesseract_scene_graph::SceneGraph::getLeafLinks
std::vector< std::shared_ptr< const Link > > getLeafLinks() const
Get a vector leaf links in the scene graph.
Definition: graph.cpp:351
tesseract_scene_graph::SceneGraph::removeLink
bool removeLink(const std::string &name, bool recursive=false)
Removes a link from the graph.
Definition: graph.cpp:364
tesseract_common::AllowedCollisionMatrix::addAllowedCollision
virtual void addAllowedCollision(const std::string &link_name1, const std::string &link_name2, const std::string &reason)
tesseract_scene_graph::SceneGraph::changeJointAccelerationLimits
bool changeJointAccelerationLimits(const std::string &name, double limit)
Changes the acceleration limits associated with a joint.
Definition: graph.cpp:705
buildTestSceneGraph
tesseract_scene_graph::SceneGraph buildTestSceneGraph()
Definition: tesseract_scene_graph_unit.cpp:811
tesseract_scene_graph::Joint::type
JointType type
The type of joint.
Definition: joint.h:293
tesseract_scene_graph::SceneGraph::getLink
std::shared_ptr< const Link > getLink(const std::string &name) const
Get a link in the graph.
Definition: graph.cpp:332
scene_state.h
This holds a state of the scene.
tesseract_scene_graph::SceneGraph::getAdjacencyMap
std::unordered_map< std::string, std::string > getAdjacencyMap(const std::vector< std::string > &link_names) const
Create mapping between links in the scene to the provided links if they are directly affected if the ...
Definition: graph.cpp:948
tesseract_scene_graph::SceneGraph::getVertex
Vertex getVertex(const std::string &name) const
Get the graph vertex by name.
Definition: graph.cpp:1109
macros.h
tesseract_scene_graph::SceneGraph::Ptr
std::shared_ptr< SceneGraph > Ptr
Definition: graph.h:135
createTestSceneGraph
tesseract_scene_graph::SceneGraph createTestSceneGraph()
Definition: tesseract_scene_graph_unit.cpp:40
tesseract_scene_graph::JointLimits::lower
double lower
Definition: joint.h:107
TEST
TEST(TesseractSceneGraphUnit, TesseractSceneGraphUnit)
Definition: tesseract_scene_graph_unit.cpp:273
tesseract_scene_graph
Definition: fwd.h:32
tesseract_scene_graph::SceneGraph::isAcyclic
bool isAcyclic() const
Determine if the graph contains cycles.
Definition: graph.cpp:861
printKDLTree
void printKDLTree(const KDL::SegmentMap::const_iterator &link, const std::string &prefix)
Definition: tesseract_scene_graph_unit.cpp:802
tesseract_scene_graph::KDLTreeData::tree
EIGEN_MAKE_ALIGNED_OPERATOR_NEW KDL::Tree tree
Definition: kdl_parser.h:161
tesseract_scene_graph::Joint::parent_link_name
std::string parent_link_name
Definition: joint.h:311
tesseract_scene_graph::JointType::FIXED
@ FIXED
tesseract_scene_graph::SceneGraph::clear
void clear()
Clear the scene graph.
Definition: graph.cpp:238
tesseract_scene_graph::SceneGraph::getLinkChildrenNames
std::vector< std::string > getLinkChildrenNames(const std::string &name) const
Get all children for a given link name.
Definition: graph.cpp:917
checkSceneGraph
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH TESSERACT_COMMON_IGNORE_WARNINGS_POP void checkSceneGraph(tesseract_scene_graph::SceneGraph &scene_graph)
Definition: tesseract_scene_graph_unit.cpp:20


tesseract_scene_graph
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:49