test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
38 #include <urdf_parser/urdf_parser.h>
39 #include <fstream>
40 #include <gtest/gtest.h>
41 #include <boost/filesystem/path.hpp>
43 #include <moveit_resources/config.h>
44 
45 class LoadPlanningModelsPr2 : public testing::Test
46 {
47 protected:
48  void SetUp() override
49  {
50  boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
51 
52  srdf_model.reset(new srdf::Model());
53  std::string xml_string;
54  std::fstream xml_file((res_path / "pr2_description/urdf/robot.xml").string().c_str(), std::fstream::in);
55  if (xml_file.is_open())
56  {
57  while (xml_file.good())
58  {
59  std::string line;
60  std::getline(xml_file, line);
61  xml_string += (line + "\n");
62  }
63  xml_file.close();
64  urdf_model = urdf::parseURDF(xml_string);
65  }
66  srdf_model->initFile(*urdf_model, (res_path / "pr2_description/srdf/robot.xml").string());
68  };
69 
70  void TearDown() override
71  {
72  }
73 
74 protected:
75  urdf::ModelInterfaceSharedPtr urdf_model;
77  moveit::core::RobotModelConstPtr robot_model;
78 };
79 
81 {
82  ASSERT_EQ(urdf_model->getName(), "pr2");
83  ASSERT_EQ(srdf_model->getName(), "pr2");
84 }
85 
87 {
88  // robot_model->printModelInfo(std::cout);
89 
90  const std::vector<const moveit::core::JointModel*>& joints = robot_model->getJointModels();
91  for (std::size_t i = 0; i < joints.size(); ++i)
92  {
93  ASSERT_EQ(joints[i]->getJointIndex(), i);
94  ASSERT_EQ(robot_model->getJointModel(joints[i]->getName()), joints[i]);
95  }
96  const std::vector<const moveit::core::LinkModel*>& links = robot_model->getLinkModels();
97  for (std::size_t i = 0; i < links.size(); ++i)
98  {
99  ASSERT_EQ(links[i]->getLinkIndex(), i);
100  // std::cout << joints[i]->getName() << std::endl;
101  }
103 }
104 
105 TEST(SiblingAssociateLinks, SimpleYRobot)
106 {
107  /* base_link - a - b - c
108  \
109  - d ~ e */
110  const std::string MODEL = "<?xml version=\"1.0\" ?>"
111  "<robot name=\"one_robot\">"
112  "<link name=\"base_link\"/>"
113  "<joint name=\"joint_a\" type=\"continuous\">"
114  " <parent link=\"base_link\"/>"
115  " <child link=\"link_a\"/>"
116  " <axis xyz=\"0 0 1\"/>"
117  " <origin rpy=\" 0.0 0 0 \" xyz=\"0.0 0 0 \"/>"
118  "</joint>"
119  "<link name=\"link_a\"/>"
120  "<joint name=\"joint_b\" type=\"fixed\">"
121  " <parent link=\"link_a\"/>"
122  " <child link=\"link_b\"/>"
123  " <origin rpy=\" 0.0 -0.42 0 \" xyz=\"0.0 0.5 0 \"/>"
124  "</joint>"
125  "<link name=\"link_b\"/>"
126  "<joint name=\"joint_c\" type=\"fixed\">"
127  " <parent link=\"link_b\"/>"
128  " <child link=\"link_c\"/>"
129  " <origin rpy=\" 0.0 0.42 0.0 \" xyz=\"0.0 0.5 0 \"/>"
130  "</joint>"
131  "<link name=\"link_c\"/>"
132  "<joint name=\"joint_d\" type=\"fixed\">"
133  " <parent link=\"link_a\"/>"
134  " <child link=\"link_d\"/>"
135  " <origin rpy=\" 0.0 -0.42 0 \" xyz=\"0.0 0.5 0 \"/>"
136  "</joint>"
137  "<link name=\"link_d\"/>"
138  "<joint name=\"joint_e\" type=\"continuous\">"
139  " <parent link=\"link_d\"/>"
140  " <child link=\"link_e\"/>"
141  " <axis xyz=\"0 0 1\"/>"
142  " <origin rpy=\" 0.0 0 0 \" xyz=\"0.0 0 0 \"/>"
143  "</joint>"
144  "<link name=\"link_e\"/>"
145  "</robot>";
146 
147  const std::string SMODEL =
148  "<?xml version=\"1.0\" ?>"
149  "<robot name=\"one_robot\">"
150  "<virtual_joint name=\"base_joint\" child_link=\"base_link\" parent_frame=\"odom\" type=\"planar\"/>"
151  "<group name=\"base_joint\"><joint name=\"base_joint\"/></group>"
152  "</robot>";
153  urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(MODEL);
155  srdf_model->initString(*urdf_model, SMODEL);
156  moveit::core::RobotModelConstPtr robot_model;
157  robot_model.reset(new moveit::core::RobotModel(urdf_model, srdf_model));
158 
159  const std::string a = "link_a", b = "link_b", c = "link_c", d = "link_d";
160  auto connected = { a, b, c, d }; // these are rigidly connected with each other
162 
163  for (const std::string& root : connected)
164  {
165  SCOPED_TRACE("root: " + root);
166  std::set<std::string> expected_set(connected);
167  expected_set.erase(root);
168  std::set<std::string> actual_set;
169  for (const auto& item : robot_model->getLinkModel(root)->getAssociatedFixedTransforms())
170  actual_set.insert(item.first->getName());
171 
172  std::ostringstream expected, actual;
173  std::copy(expected_set.begin(), expected_set.end(), std::ostream_iterator<std::string>(expected, " "));
174  std::copy(actual_set.begin(), actual_set.end(), std::ostream_iterator<std::string>(actual, " "));
175 
176  EXPECT_EQ(expected.str(), actual.str());
177  }
178 }
179 
180 int main(int argc, char** argv)
181 {
182  testing::InitGoogleTest(&argc, argv);
183  return RUN_ALL_TESTS();
184 }
d
Core components of MoveIt!
void SetUp() override
Definition: test.cpp:48
TEST(SiblingAssociateLinks, SimpleYRobot)
Definition: test.cpp:105
std::map< const LinkModel *, Eigen::Affine3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Affine3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
Definition: link_model.h:69
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:67
#define EXPECT_EQ(a, b)
urdf::ModelInterfaceSharedPtr urdf_model
def xml_string(rootXml, addHeader=True)
int main(int argc, char **argv)
Definition: test.cpp:180
TEST_F(LoadPlanningModelsPr2, InitOK)
Definition: test.cpp:80
moveit::core::RobotModelConstPtr robot_model
Definition: test.cpp:77
static void Status(std::ostream &out=std::cout, bool merge=true)
Print the status of the profiled code chunks and events. Optionally, computation done by different th...
Definition: profiler.h:204
void TearDown() override
Definition: test.cpp:70


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:33