test_end_effector.cpp
Go to the documentation of this file.
1 
7 /*********************************************************************
8 * Software License Agreement (BSD License)
9 *
10 * Copyright (c) 2013, Willow Garage, Inc.
11 * All rights reserved.
12 *
13 * Redistribution and use in source and binary forms, with or without
14 * modification, are permitted provided that the following conditions
15 * are met:
16 *
17 * * Redistributions of source code must retain the above copyright
18 * notice, this list of conditions and the following disclaimer.
19 * * Redistributions in binary form must reproduce the above
20 * copyright notice, this list of conditions and the following
21 * disclaimer in the documentation and/or other materials provided
22 * with the distribution.
23 * * Neither the name of the Willow Garage nor the names of its
24 * contributors may be used to endorse or promote products derived
25 * from this software without specific prior written permission.
26 *
27 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
28 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
29 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
30 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
31 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
32 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
33 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
34 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
35 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
36 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
37 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
38 * POSSIBILITY OF SUCH DAMAGE.
39 *********************************************************************/
40 
41 /* Author: Ioan Sucan */
42 
44 #include <urdf_parser/urdf_parser.h>
45 #include <fstream>
46 #include <string>
47 #include <vector>
48 #include <gtest/gtest.h>
49 #include <boost/filesystem/path.hpp>
51 #include <ros/package.h>
52 #include <ros/ros.h>
53 
54 class LoadRobotModel : public testing::Test
55 {
56 protected:
57  virtual void SetUp()
58  {
59  ros::NodeHandle nh("~");
60 
61  srdf_model.reset(new srdf::Model());
62 
63  std::string xml_string, robot_description_, robot_description_semantic_;
64 
65  // wait for move_group to be ready
66  ros::WallDuration(30.0).sleep();
67  ros::spinOnce();
68  if (0)
69  {
70  ROS_ERROR("Move group not available within 30 seconds, did you start the demo ?");
71  return;
72  }
73  if (!nh.searchParam("robot_description", robot_description_) || !nh.getParam(robot_description_, xml_string))
74  {
75  ROS_ERROR("Robot model parameter not found! Did you remap '%s' ?", robot_description_.c_str());
76  return;
77  }
78  urdf_model = urdf::parseURDF(xml_string);
79 
80  if (!nh.searchParam("robot_description_semantic", robot_description_semantic_) ||
81  !nh.getParam(robot_description_semantic_, xml_string))
82  {
83  ROS_ERROR("Robot model semantic parameter not found! Did you remap '%s' ?", robot_description_semantic_.c_str());
84  return;
85  }
86  srdf_model->initString(*urdf_model, xml_string);
87 
89  };
90 
91  virtual void TearDown()
92  {
93  }
94 
95 protected:
98  moveit::core::RobotModelConstPtr robot_model;
99 };
100 
102 {
103  ASSERT_EQ(urdf_model->getName(), "ur10srh");
104  ASSERT_EQ(srdf_model->getName(), "ur10srh");
105 }
106 
108 {
109  const std::vector<const moveit::core::JointModelGroup*> &jmgs = robot_model->getJointModelGroups();
110  for (std::size_t i = 0 ; i < jmgs.size() ; ++i)
111  {
112  const std::vector< std::string > &ee_names = jmgs[i]->getAttachedEndEffectorNames();
113  if (jmgs[i]->isChain())
114  {
115  ASSERT_GT(ee_names.size(), 0) << jmgs[i]->getName();
116  for (std::size_t j = 0 ; j < ee_names.size() ; ++j)
117  {
118  ASSERT_GT(ee_names[j].size(), 0) << jmgs[i]->getName();
119  }
120  }
121  }
123 }
124 
125 int main(int argc, char **argv)
126 {
127  testing::InitGoogleTest(&argc, argv);
128  // do not forget to init ros because this is also a node
129  ros::init(argc, argv, "end_effector_tester");
130  return RUN_ALL_TESTS();
131 }
132 
133 
134 
135 
virtual void SetUp()
moveit::core::RobotModelConstPtr robot_model
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::size_t size(custom_string const &s)
std::string getName(void *handle)
bool sleep() const
virtual void TearDown()
bool searchParam(const std::string &key, std::string &result) const
TEST_F(LoadRobotModel, InitOK)
def xml_string(rootXml, addHeader=True)
boost::shared_ptr< srdf::Model > srdf_model
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
static void Status(std::ostream &out=std::cout, bool merge=true)
#define ROS_ERROR(...)
boost::shared_ptr< urdf::ModelInterface > urdf_model


sr_multi_moveit_test
Author(s): Beatriz Leon
autogenerated on Wed Oct 14 2020 04:05:26