test_collision_distance_field.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/robot_model/robot_model.h>
00038 #include <moveit/robot_state/robot_state.h>
00039 #include <moveit/transforms/transforms.h>
00040 #include <moveit/collision_distance_field/collision_distance_field_types.h>
00041 #include <moveit/collision_distance_field/collision_robot_distance_field.h>
00042 #include <moveit/collision_distance_field/collision_world_distance_field.h>
00043 #include <moveit_resources/config.h>
00044 
00045 #include <geometric_shapes/shape_operations.h>
00046 #include <urdf_parser/urdf_parser.h>
00047 
00048 #include <fstream>
00049 #include <gtest/gtest.h>
00050 #include <sstream>
00051 #include <algorithm>
00052 #include <ctype.h>
00053 #include <boost/filesystem.hpp>
00054 
00055 typedef collision_detection::CollisionWorldDistanceField DefaultCWorldType;
00056 typedef collision_detection::CollisionRobotDistanceField DefaultCRobotType;
00057 
00058 class DistanceFieldCollisionDetectionTester : public testing::Test
00059 {
00060 protected:
00061   virtual void SetUp()
00062   {
00063     srdf_model_.reset(new srdf::Model());
00064     std::string xml_string;
00065     std::fstream xml_file(MOVEIT_TEST_RESOURCES_DIR "/pr2_description/urdf/robot.xml", std::fstream::in);
00066     if (xml_file.is_open())
00067     {
00068       while (xml_file.good())
00069       {
00070         std::string line;
00071         std::getline(xml_file, line);
00072         xml_string += (line + "\n");
00073       }
00074       xml_file.close();
00075       urdf_model_ = urdf::parseURDF(xml_string);
00076       urdf_ok_ = urdf_model_ ? true : false;
00077     }
00078     else
00079       urdf_ok_ = false;
00080     srdf_ok_ = srdf_model_->initFile(*urdf_model_, MOVEIT_TEST_RESOURCES_DIR "/pr2_description/srdf/robot.xml");
00081 
00082     robot_model_.reset(new robot_model::RobotModel(urdf_model_, srdf_model_));
00083 
00084     acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), true));
00085 
00086     std::map<std::string, std::vector<collision_detection::CollisionSphere> > link_body_decompositions;
00087     crobot_.reset(new DefaultCRobotType(robot_model_, link_body_decompositions));
00088     cworld_.reset(new DefaultCWorldType());
00089   }
00090 
00091   virtual void TearDown()
00092   {
00093   }
00094 
00095 protected:
00096   bool urdf_ok_;
00097   bool srdf_ok_;
00098 
00099   boost::shared_ptr<urdf::ModelInterface> urdf_model_;
00100   boost::shared_ptr<srdf::Model> srdf_model_;
00101 
00102   robot_model::RobotModelPtr robot_model_;
00103 
00104   robot_state::TransformsPtr ftf_;
00105   robot_state::TransformsConstPtr ftf_const_;
00106 
00107   boost::shared_ptr<collision_detection::CollisionRobot> crobot_;
00108   boost::shared_ptr<collision_detection::CollisionWorld> cworld_;
00109 
00110   collision_detection::AllowedCollisionMatrixPtr acm_;
00111 };
00112 
00113 TEST_F(DistanceFieldCollisionDetectionTester, DefaultNotInCollision)
00114 {
00115   robot_state::RobotState kstate(robot_model_);
00116   kstate.setToDefaultValues();
00117   kstate.update();
00118 
00119   ASSERT_TRUE(urdf_ok_ && srdf_ok_);
00120 
00121   collision_detection::CollisionRequest req;
00122   collision_detection::CollisionResult res;
00123   req.group_name = "whole_body";
00124   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00125   ASSERT_FALSE(res.collision);
00126 }
00127 
00128 TEST_F(DistanceFieldCollisionDetectionTester, ChangeTorsoPosition)
00129 {
00130   robot_state::RobotState kstate(robot_model_);
00131   kstate.setToDefaultValues();
00132   kstate.update();
00133 
00134   collision_detection::CollisionRequest req;
00135   collision_detection::CollisionResult res1;
00136   collision_detection::CollisionResult res2;
00137 
00138   req.group_name = "right_arm";
00139   crobot_->checkSelfCollision(req, res1, kstate, *acm_);
00140   std::map<std::string, double> torso_val;
00141   torso_val["torso_lift_joint"] = .15;
00142   kstate.setVariablePositions(torso_val);
00143   kstate.update();
00144   crobot_->checkSelfCollision(req, res1, kstate, *acm_);
00145   crobot_->checkSelfCollision(req, res1, kstate, *acm_);
00146 }
00147 
00148 TEST_F(DistanceFieldCollisionDetectionTester, LinksInCollision)
00149 {
00150   collision_detection::CollisionRequest req;
00151   collision_detection::CollisionResult res1;
00152   collision_detection::CollisionResult res2;
00153   collision_detection::CollisionResult res3;
00154   // req.contacts = true;
00155   // req.max_contacts = 100;
00156   req.group_name = "whole_body";
00157 
00158   robot_state::RobotState kstate(robot_model_);
00159   kstate.setToDefaultValues();
00160 
00161   Eigen::Affine3d offset = Eigen::Affine3d::Identity();
00162   offset.translation().x() = .01;
00163 
00164   kstate.updateStateWithLinkAt("base_link", Eigen::Affine3d::Identity());
00165   kstate.updateStateWithLinkAt("base_bellow_link", offset);
00166 
00167   acm_->setEntry("base_link", "base_bellow_link", false);
00168   crobot_->checkSelfCollision(req, res1, kstate, *acm_);
00169   ASSERT_TRUE(res1.collision);
00170 
00171   acm_->setEntry("base_link", "base_bellow_link", true);
00172   crobot_->checkSelfCollision(req, res2, kstate, *acm_);
00173   ASSERT_FALSE(res2.collision);
00174 
00175   kstate.updateStateWithLinkAt("r_gripper_palm_link", Eigen::Affine3d::Identity());
00176   kstate.updateStateWithLinkAt("l_gripper_palm_link", offset);
00177 
00178   acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false);
00179   crobot_->checkSelfCollision(req, res3, kstate, *acm_);
00180   ASSERT_TRUE(res3.collision);
00181 }
00182 
00183 TEST_F(DistanceFieldCollisionDetectionTester, ContactReporting)
00184 {
00185   collision_detection::CollisionRequest req;
00186   req.contacts = true;
00187   req.max_contacts = 1;
00188   req.group_name = "whole_body";
00189 
00190   robot_state::RobotState kstate(robot_model_);
00191   kstate.setToDefaultValues();
00192 
00193   Eigen::Affine3d offset = Eigen::Affine3d::Identity();
00194   offset.translation().x() = .01;
00195 
00196   kstate.updateStateWithLinkAt("base_link", Eigen::Affine3d::Identity());
00197   kstate.updateStateWithLinkAt("base_bellow_link", offset);
00198 
00199   kstate.updateStateWithLinkAt("r_gripper_palm_link", Eigen::Affine3d::Identity());
00200   kstate.updateStateWithLinkAt("l_gripper_palm_link", offset);
00201 
00202   acm_->setEntry("base_link", "base_bellow_link", false);
00203   acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false);
00204 
00205   collision_detection::CollisionResult res;
00206   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00207   ASSERT_TRUE(res.collision);
00208   EXPECT_EQ(res.contacts.size(), 1);
00209   EXPECT_EQ(res.contacts.begin()->second.size(), 1);
00210 
00211   res.clear();
00212   req.max_contacts = 2;
00213   req.max_contacts_per_pair = 1;
00214   //  req.verbose = true;
00215   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00216   ASSERT_TRUE(res.collision);
00217   EXPECT_EQ(res.contact_count, 2);
00218   EXPECT_EQ(res.contacts.begin()->second.size(), 1);
00219 
00220   res.contacts.clear();
00221   res.contact_count = 0;
00222 
00223   req.max_contacts = 10;
00224   req.max_contacts_per_pair = 2;
00225   acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), false));
00226   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00227   ASSERT_TRUE(res.collision);
00228   EXPECT_LE(res.contacts.size(), 10);
00229   EXPECT_LE(res.contact_count, 10);
00230 }
00231 
00232 TEST_F(DistanceFieldCollisionDetectionTester, ContactPositions)
00233 {
00234   collision_detection::CollisionRequest req;
00235   req.contacts = true;
00236   req.max_contacts = 1;
00237   req.group_name = "whole_body";
00238 
00239   robot_state::RobotState kstate(robot_model_);
00240   kstate.setToDefaultValues();
00241 
00242   Eigen::Affine3d pos1 = Eigen::Affine3d::Identity();
00243   Eigen::Affine3d pos2 = Eigen::Affine3d::Identity();
00244 
00245   pos1.translation().x() = 5.0;
00246   pos2.translation().x() = 5.01;
00247 
00248   kstate.updateStateWithLinkAt("r_gripper_palm_link", pos1);
00249   kstate.updateStateWithLinkAt("l_gripper_palm_link", pos2);
00250 
00251   acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false);
00252 
00253   collision_detection::CollisionResult res;
00254   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00255   ASSERT_TRUE(res.collision);
00256   ASSERT_EQ(res.contacts.size(), 1);
00257   ASSERT_EQ(res.contacts.begin()->second.size(), 1);
00258 
00259   for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
00260        it != res.contacts.end(); it++)
00261   {
00262     EXPECT_NEAR(it->second[0].pos.x(), 5.0, .33);
00263   }
00264 
00265   pos1 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
00266   pos2 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond(0.965, 0.0, 0.258, 0.0));
00267 
00268   kstate.updateStateWithLinkAt("r_gripper_palm_link", pos1);
00269   kstate.updateStateWithLinkAt("l_gripper_palm_link", pos2);
00270 
00271   collision_detection::CollisionResult res2;
00272   crobot_->checkSelfCollision(req, res2, kstate, *acm_);
00273   ASSERT_TRUE(res2.collision);
00274   ASSERT_EQ(res2.contacts.size(), 1);
00275   ASSERT_EQ(res2.contacts.begin()->second.size(), 1);
00276 
00277   for (collision_detection::CollisionResult::ContactMap::const_iterator it = res2.contacts.begin();
00278        it != res2.contacts.end(); it++)
00279   {
00280     EXPECT_NEAR(it->second[0].pos.x(), 3.0, 0.33);
00281   }
00282 
00283   pos1 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
00284   pos2 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond(M_PI / 4.0, 0.0, M_PI / 4.0, 0.0));
00285 
00286   kstate.updateStateWithLinkAt("r_gripper_palm_link", pos1);
00287   kstate.updateStateWithLinkAt("l_gripper_palm_link", pos2);
00288 
00289   collision_detection::CollisionResult res3;
00290   crobot_->checkSelfCollision(req, res2, kstate, *acm_);
00291   ASSERT_FALSE(res3.collision);
00292 }
00293 
00294 TEST_F(DistanceFieldCollisionDetectionTester, AttachedBodyTester)
00295 {
00296   collision_detection::CollisionRequest req;
00297   collision_detection::CollisionResult res;
00298 
00299   req.group_name = "right_arm";
00300 
00301   acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), true));
00302 
00303   robot_state::RobotState kstate(robot_model_);
00304   kstate.setToDefaultValues();
00305   kstate.update();
00306 
00307   Eigen::Affine3d pos1 = Eigen::Affine3d::Identity();
00308   pos1.translation().x() = 1.0;
00309 
00310   kstate.updateStateWithLinkAt("r_gripper_palm_link", pos1);
00311   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00312   ASSERT_FALSE(res.collision);
00313 
00314   shapes::Shape* shape = new shapes::Box(.25, .25, .25);
00315   cworld_->getWorld()->addToObject("box", shapes::ShapeConstPtr(shape), pos1);
00316 
00317   res = collision_detection::CollisionResult();
00318   cworld_->checkRobotCollision(req, res, *crobot_, kstate, *acm_);
00319   ASSERT_TRUE(res.collision);
00320 
00321   // deletes shape
00322   cworld_->getWorld()->removeObject("box");
00323 
00324   std::vector<shapes::ShapeConstPtr> shapes;
00325   EigenSTL::vector_Affine3d poses;
00326   shapes.push_back(shapes::ShapeConstPtr(new shapes::Box(.25, .25, .25)));
00327   poses.push_back(Eigen::Affine3d::Identity());
00328   std::set<std::string> touch_links;
00329   trajectory_msgs::JointTrajectory empty_state;
00330   robot_state::AttachedBody* attached_body = new robot_state::AttachedBody(
00331       kstate.getLinkModel("r_gripper_palm_link"), "box", shapes, poses, touch_links, empty_state);
00332 
00333   kstate.attachBody(attached_body);
00334 
00335   res = collision_detection::CollisionResult();
00336   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00337   ASSERT_TRUE(res.collision);
00338 
00339   // deletes shape
00340   kstate.clearAttachedBody("box");
00341 
00342   touch_links.insert("r_gripper_palm_link");
00343   shapes[0].reset(new shapes::Box(.1, .1, .1));
00344 
00345   robot_state::AttachedBody* attached_body_1 = new robot_state::AttachedBody(
00346       kstate.getLinkModel("r_gripper_palm_link"), "box", shapes, poses, touch_links, empty_state);
00347   kstate.attachBody(attached_body_1);
00348 
00349   res = collision_detection::CollisionResult();
00350   crobot_->checkSelfCollision(req, res, kstate, *acm_);
00351   // ASSERT_FALSE(res.collision);
00352 
00353   pos1.translation().x() = 1.01;
00354   shapes::Shape* coll = new shapes::Box(.1, .1, .1);
00355   cworld_->getWorld()->addToObject("coll", shapes::ShapeConstPtr(coll), pos1);
00356   res = collision_detection::CollisionResult();
00357   cworld_->checkRobotCollision(req, res, *crobot_, kstate, *acm_);
00358   ASSERT_TRUE(res.collision);
00359 
00360   acm_->setEntry("coll", "r_gripper_palm_link", true);
00361   res = collision_detection::CollisionResult();
00362   cworld_->checkRobotCollision(req, res, *crobot_, kstate, *acm_);
00363   ASSERT_TRUE(res.collision);
00364 }
00365 
00366 int main(int argc, char** argv)
00367 {
00368   testing::InitGoogleTest(&argc, argv);
00369   return RUN_ALL_TESTS();
00370 }


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Wed Jun 19 2019 19:24:03