44 #include <urdf_parser/urdf_parser.h> 48 #include <gtest/gtest.h> 49 #include <boost/filesystem/path.hpp> 63 std::string
xml_string, robot_description_, robot_description_semantic_;
70 ROS_ERROR(
"Move group not available within 30 seconds, did you start the demo ?");
73 if (!nh.
searchParam(
"robot_description", robot_description_) || !nh.
getParam(robot_description_, xml_string))
75 ROS_ERROR(
"Robot model parameter not found! Did you remap '%s' ?", robot_description_.c_str());
80 if (!nh.
searchParam(
"robot_description_semantic", robot_description_semantic_) ||
81 !nh.
getParam(robot_description_semantic_, xml_string))
83 ROS_ERROR(
"Robot model semantic parameter not found! Did you remap '%s' ?", robot_description_semantic_.c_str());
109 const std::vector<const moveit::core::JointModelGroup*> &jmgs =
robot_model->getJointModelGroups();
110 for (std::size_t i = 0 ; i < jmgs.size() ; ++i)
112 const std::vector< std::string > &ee_names = jmgs[i]->getAttachedEndEffectorNames();
113 if (jmgs[i]->isChain())
115 ASSERT_GT(ee_names.size(), 0) << jmgs[i]->
getName();
116 for (std::size_t j = 0 ; j < ee_names.size() ; ++j)
118 ASSERT_GT(ee_names[j].
size(), 0) << jmgs[i]->getName();
125 int main(
int argc,
char **argv)
127 testing::InitGoogleTest(&argc, argv);
129 ros::init(argc, argv,
"end_effector_tester");
130 return RUN_ALL_TESTS();
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 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()
boost::shared_ptr< urdf::ModelInterface > urdf_model