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


ompl
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 11:12:03