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>
44 
45 class LoadPlanningModelsPr2 : public testing::Test
46 {
47 protected:
48  void SetUp() override
49  {
51  };
52 
53  void TearDown() override
54  {
55  }
56 
57 protected:
58  moveit::core::RobotModelConstPtr robot_model_;
59 };
60 
62 {
63  ASSERT_EQ(robot_model_->getURDF()->getName(), "pr2");
64  ASSERT_EQ(robot_model_->getSRDF()->getName(), "pr2");
65 }
66 
68 {
69  // robot_model_->printModelInfo(std::cout);
70 
71  const std::vector<const moveit::core::JointModel*>& joints = robot_model_->getJointModels();
72  for (std::size_t i = 0; i < joints.size(); ++i)
73  {
74  ASSERT_EQ(joints[i]->getJointIndex(), static_cast<int>(i));
75  ASSERT_EQ(robot_model_->getJointModel(joints[i]->getName()), joints[i]);
76  }
77  const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModels();
78  for (std::size_t i = 0; i < links.size(); ++i)
79  {
80  ASSERT_EQ(links[i]->getLinkIndex(), static_cast<int>(i));
81  }
83 }
84 
85 TEST(SiblingAssociateLinks, SimpleYRobot)
86 {
87  /* base_link - a - b - c
88  \
89  - d ~ e */
90  moveit::core::RobotModelBuilder builder("one_robot", "base_link");
91  builder.addChain("base_link->a", "continuous");
92  builder.addChain("a->b->c", "fixed");
93  builder.addChain("a->d", "fixed");
94  builder.addChain("d->e", "continuous");
95  builder.addVirtualJoint("odom", "base_link", "planar", "base_joint");
96  builder.addGroup({}, { "base_joint" }, "base_joint");
97  ASSERT_TRUE(builder.isValid());
98  moveit::core::RobotModelConstPtr robot_model = builder.build();
99 
100  const std::string a = "a", b = "b", c = "c", d = "d";
101  auto connected = { a, b, c, d }; // these are rigidly connected with each other
103 
104  for (const std::string& root : connected)
105  {
106  SCOPED_TRACE("root: " + root);
107  std::set<std::string> expected_set(connected);
108  expected_set.erase(root);
109  std::set<std::string> actual_set;
110  for (const auto& item : robot_model->getLinkModel(root)->getAssociatedFixedTransforms())
111  actual_set.insert(item.first->getName());
112 
113  std::ostringstream expected, actual;
114  std::copy(expected_set.begin(), expected_set.end(), std::ostream_iterator<std::string>(expected, " "));
115  std::copy(actual_set.begin(), actual_set.end(), std::ostream_iterator<std::string>(actual, " "));
116 
117  EXPECT_EQ(expected.str(), actual.str());
118  }
119 }
120 
121 TEST(RobotModel, CycleDetection)
122 {
123  static const std::string URDF = R"(<?xml version="1.0"?>
124  <robot name="test">
125  <link name="base"/>
126  <link name="a"/>
127  <link name="b"/>
128  <joint name="base_a" type="fixed">
129  <parent link="base"/>
130  <child link="a"/>
131  </joint>
132  <joint name="base_b" type="continuous">
133  <parent link="base"/>
134  <child link="b"/>
135  </joint>
136  <joint name="a_b" type="continuous">
137  <parent link="a"/>
138  <child link="b"/>
139  </joint>
140  </robot>)";
141 
142  auto urdf = std::make_shared<urdf::Model>();
143  // urdfdom will initialize the model, but mark one joint as "parent_joint" of "b"
144  ASSERT_TRUE(urdf->initString(URDF));
145  auto srdf = std::make_shared<srdf::Model>();
147 
148  // MoveIt ignores the second joint with child b
149  EXPECT_EQ(robot_model.getActiveJointModels().size(), 1u); // base_b?
150  EXPECT_EQ(robot_model.getLinkModelCount(), 3u); // base, a, b
151 }
152 
153 int main(int argc, char** argv)
154 {
155  testing::InitGoogleTest(&argc, argv);
156  return RUN_ALL_TESTS();
157 }
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
moveit::tools::Profiler::Status
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:203
URDF
URDF
moveit::core::RobotModel
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:143
LoadPlanningModelsPr2
Definition: test_constraint_samplers.cpp:57
robot_model.h
TEST
TEST(SiblingAssociateLinks, SimpleYRobot)
Definition: test.cpp:85
profiler.h
LoadPlanningModelsPr2::SetUp
void SetUp() override
Definition: test_constraint_samplers.cpp:106
LoadPlanningModelsPr2::robot_model_
moveit::core::RobotModelPtr robot_model_
Definition: test_constraint_samplers.cpp:137
setup.d
d
Definition: setup.py:8
moveit::core::LinkTransformMap
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
Definition: link_model.h:68
TEST_F
TEST_F(LoadPlanningModelsPr2, InitOK)
Definition: test.cpp:61
robot_model_test_utils.h
main
int main(int argc, char **argv)
Definition: test.cpp:153
LoadPlanningModelsPr2::TearDown
void TearDown() override
Definition: test_constraint_samplers.cpp:132
urdf
moveit::core::RobotModelBuilder
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
Definition: robot_model_test_utils.h:158
srdf
EXPECT_EQ
#define EXPECT_EQ(a, b)
moveit::core::loadTestingRobotModel
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
Definition: robot_model_test_utils.cpp:117


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:40