test.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2013, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/robot_model/robot_model.h>
00038 #include <urdf_parser/urdf_parser.h>
00039 #include <fstream>
00040 #include <gtest/gtest.h>
00041 #include <boost/filesystem/path.hpp>
00042 #include <moveit/profiler/profiler.h>
00043 #include <ros/package.h>
00044 
00045 class LoadPlanningModelsPr2 : public testing::Test
00046 {
00047 protected:
00048   
00049   virtual void SetUp()
00050   {
00051     srdf_model.reset(new srdf::Model());
00052     std::string xml_string;
00053     std::string resource_dir = ros::package::getPath("moveit_resources");
00054     if(resource_dir == "")
00055     {
00056       FAIL() << "Failed to find package moveit_resources.";
00057       return;
00058     }
00059     std::fstream xml_file((boost::filesystem::path(resource_dir) / "test/urdf/robot.xml").string().c_str(), std::fstream::in);
00060     if (xml_file.is_open())
00061     {
00062       while (xml_file.good())
00063       {
00064         std::string line;
00065         std::getline(xml_file, line);
00066         xml_string += (line + "\n");
00067       }
00068       xml_file.close();
00069       urdf_model = urdf::parseURDF(xml_string);
00070     }
00071     srdf_model->initFile(*urdf_model, (boost::filesystem::path(resource_dir) / "test/srdf/robot.xml").string());
00072     robot_model.reset(new moveit::core::RobotModel(urdf_model, srdf_model));
00073   };
00074   
00075   virtual void TearDown()
00076   {
00077   }
00078   
00079 protected:
00080   
00081   boost::shared_ptr<urdf::ModelInterface> urdf_model;
00082   boost::shared_ptr<srdf::Model> srdf_model;
00083   moveit::core::RobotModelConstPtr robot_model;
00084 };
00085 
00086 TEST_F(LoadPlanningModelsPr2, InitOK)
00087 {
00088   ASSERT_EQ(urdf_model->getName(), "pr2");
00089   ASSERT_EQ(srdf_model->getName(), "pr2");
00090 }
00091 
00092 TEST_F(LoadPlanningModelsPr2, Model)
00093 {
00094   robot_model->printModelInfo(std::cout);
00095   
00096   const std::vector<const moveit::core::JointModel*> &joints = robot_model->getJointModels();
00097   for (std::size_t i = 0 ; i < joints.size() ; ++i)
00098   {
00099     ASSERT_EQ(joints[i]->getJointIndex(), i);
00100     ASSERT_EQ(robot_model->getJointModel(joints[i]->getName()), joints[i]);
00101   }
00102   const std::vector<const moveit::core::LinkModel*> &links = robot_model->getLinkModels();
00103   for (std::size_t i = 0 ; i < links.size() ; ++i)
00104   {
00105     ASSERT_EQ(links[i]->getLinkIndex(), i);
00106     //    std::cout << joints[i]->getName() << std::endl;
00107     
00108   }
00109   moveit::tools::Profiler::Status();
00110   
00111 }
00112 
00113 
00114 int main(int argc, char **argv)
00115 {
00116     testing::InitGoogleTest(&argc, argv);
00117     return RUN_ALL_TESTS();
00118 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:53