test_state_space.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, 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 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/ompl_interface/parameterization/joint_space/joint_model_state_space.h>
00038 #include <moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h>
00039 #include <moveit_resources/config.h>
00040 
00041 #include <urdf_parser/urdf_parser.h>
00042 
00043 #include <ompl/util/Exception.h>
00044 #include <moveit/robot_state/conversions.h>
00045 #include <gtest/gtest.h>
00046 #include <fstream>
00047 #include <boost/filesystem/path.hpp>
00048 
00049 class LoadPlanningModelsPr2 : public testing::Test
00050 {
00051 protected:
00052   virtual void SetUp()
00053   {
00054     boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
00055 
00056     srdf_model_.reset(new srdf::Model());
00057     std::string xml_string;
00058     std::fstream xml_file((res_path / "pr2_description/urdf/robot.xml").string().c_str(), std::fstream::in);
00059     if (xml_file.is_open())
00060     {
00061       while (xml_file.good())
00062       {
00063         std::string line;
00064         std::getline(xml_file, line);
00065         xml_string += (line + "\n");
00066       }
00067       xml_file.close();
00068       urdf_model_ = urdf::parseURDF(xml_string);
00069     }
00070     srdf_model_->initFile(*urdf_model_, (res_path / "pr2_description/srdf/robot.xml").string());
00071     robot_model_.reset(new moveit::core::RobotModel(urdf_model_, srdf_model_));
00072   };
00073 
00074   virtual void TearDown()
00075   {
00076   }
00077 
00078 protected:
00079   robot_model::RobotModelPtr robot_model_;
00080   boost::shared_ptr<urdf::ModelInterface> urdf_model_;
00081   boost::shared_ptr<srdf::Model> srdf_model_;
00082   bool urdf_ok_;
00083   bool srdf_ok_;
00084 };
00085 
00086 TEST_F(LoadPlanningModelsPr2, StateSpace)
00087 {
00088   ompl_interface::ModelBasedStateSpaceSpecification spec(robot_model_, "whole_body");
00089   ompl_interface::JointModelStateSpace ss(spec);
00090   ss.setPlanningVolume(-1, 1, -1, 1, -1, 1);
00091   ss.setup();
00092   std::ofstream fout("ompl_interface_test_state_space_diagram1.dot");
00093   ss.diagram(fout);
00094   bool passed = false;
00095   try
00096   {
00097     ss.sanityChecks();
00098     passed = true;
00099   }
00100   catch (ompl::Exception& ex)
00101   {
00102     logError("Sanity checks did not pass: %s", ex.what());
00103   }
00104   EXPECT_TRUE(passed);
00105 }
00106 
00107 TEST_F(LoadPlanningModelsPr2, StateSpaces)
00108 {
00109   ompl_interface::ModelBasedStateSpaceSpecification spec1(robot_model_, "right_arm");
00110   ompl_interface::ModelBasedStateSpace ss1(spec1);
00111   ss1.setup();
00112 
00113   ompl_interface::ModelBasedStateSpaceSpecification spec2(robot_model_, "left_arm");
00114   ompl_interface::ModelBasedStateSpace ss2(spec2);
00115   ss2.setup();
00116 
00117   ompl_interface::ModelBasedStateSpaceSpecification spec3(robot_model_, "whole_body");
00118   ompl_interface::ModelBasedStateSpace ss3(spec3);
00119   ss3.setup();
00120 
00121   ompl_interface::ModelBasedStateSpaceSpecification spec4(robot_model_, "arms");
00122   ompl_interface::ModelBasedStateSpace ss4(spec4);
00123   ss4.setup();
00124 
00125   std::ofstream fout("ompl_interface_test_state_space_diagram2.dot");
00126   ompl::base::StateSpace::Diagram(fout);
00127 }
00128 
00129 TEST_F(LoadPlanningModelsPr2, StateSpaceCopy)
00130 {
00131   ompl_interface::ModelBasedStateSpaceSpecification spec(robot_model_, "right_arm");
00132   ompl_interface::JointModelStateSpace ss(spec);
00133   ss.setPlanningVolume(-1, 1, -1, 1, -1, 1);
00134   ss.setup();
00135   std::ofstream fout("ompl_interface_test_state_space_diagram1.dot");
00136   ss.diagram(fout);
00137   bool passed = false;
00138   try
00139   {
00140     ss.sanityChecks();
00141     passed = true;
00142   }
00143   catch (ompl::Exception& ex)
00144   {
00145     logError("Sanity checks did not pass: %s", ex.what());
00146   }
00147   EXPECT_TRUE(passed);
00148 
00149   robot_state::RobotState kstate(robot_model_);
00150   kstate.setToRandomPositions();
00151   EXPECT_TRUE(kstate.distance(kstate) < 1e-12);
00152   ompl::base::State* state = ss.allocState();
00153   for (int i = 0; i < 10; ++i)
00154   {
00155     robot_state::RobotState kstate2(kstate);
00156     EXPECT_TRUE(kstate.distance(kstate2) < 1e-12);
00157     ss.copyToOMPLState(state, kstate);
00158     kstate.setToRandomPositions(kstate.getRobotModel()->getJointModelGroup(ss.getJointModelGroupName()));
00159     std::cout << (kstate.getGlobalLinkTransform("r_wrist_roll_link").translation() -
00160                   kstate2.getGlobalLinkTransform("r_wrist_roll_link").translation())
00161               << std::endl;
00162     EXPECT_TRUE(kstate.distance(kstate2) > 1e-12);
00163     ss.copyToRobotState(kstate, state);
00164     std::cout << (kstate.getGlobalLinkTransform("r_wrist_roll_link").translation() -
00165                   kstate2.getGlobalLinkTransform("r_wrist_roll_link").translation())
00166               << std::endl;
00167     EXPECT_TRUE(kstate.distance(kstate2) < 1e-12);
00168   }
00169 
00170   ss.freeState(state);
00171 }
00172 
00173 int main(int argc, char** argv)
00174 {
00175   testing::InitGoogleTest(&argc, argv);
00176   return RUN_ALL_TESTS();
00177 }


ompl
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:27