test_aabb.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, 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: Martin Pecka */
00036 
00037 #include <moveit/robot_model/aabb.h>
00038 #include <moveit/robot_model/robot_model.h>
00039 #include <moveit/robot_state/robot_state.h>
00040 #include <moveit_resources/config.h>
00041 #include <urdf_parser/urdf_parser.h>
00042 #include <fstream>
00043 #include <boost/filesystem.hpp>
00044 #include <gtest/gtest.h>
00045 
00046 // To visualize bbox of the PR2, set this to 1.
00047 #ifndef VISUALIZE_PR2_RVIZ
00048 #define VISUALIZE_PR2_RVIZ 0
00049 #endif
00050 
00051 #if VISUALIZE_PR2_RVIZ
00052 #include <ros/ros.h>
00053 #include <visualization_msgs/Marker.h>
00054 #include <geometric_shapes/shape_operations.h>
00055 #endif
00056 
00057 class TestAABB : public testing::Test
00058 {
00059 protected:
00060   std::string readFileToString(boost::filesystem::path path) const
00061   {
00062     std::string file_string;
00063     std::fstream file(path.string().c_str(), std::fstream::in);
00064     if (file.is_open())
00065     {
00066       std::string line;
00067       while (file.good())
00068       {
00069         std::getline(file, line);
00070         file_string += (line + "\n");
00071       }
00072       file.close();
00073     }
00074     return file_string;
00075   }
00076 
00077   virtual void SetUp(){};
00078 
00079   robot_state::RobotState loadModel(const std::string urdf, const std::string srdf)
00080   {
00081     urdf::ModelInterfaceSharedPtr parsed_urdf(urdf::parseURDF(urdf));
00082     if (!parsed_urdf)
00083       throw std::runtime_error("Cannot parse URDF.");
00084 
00085     srdf::ModelSharedPtr parsed_srdf(new srdf::Model());
00086     bool srdf_ok = parsed_srdf->initString(*parsed_urdf, srdf);
00087     if (!srdf_ok)
00088       throw std::runtime_error("Cannot parse URDF.");
00089 
00090     robot_model::RobotModelPtr model(new robot_model::RobotModel(parsed_urdf, parsed_srdf));
00091     robot_state::RobotState robot_state = robot_state::RobotState(model);
00092     robot_state.setToDefaultValues();
00093     robot_state.update(true);
00094 
00095     return robot_state;
00096   }
00097 
00098   virtual void TearDown()
00099   {
00100   }
00101 };
00102 
00103 TEST_F(TestAABB, TestPR2)
00104 {
00105   // Contains a link with mesh geometry that is not centered
00106 
00107   boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
00108 
00109   const std::string PR2_URDF = this->readFileToString(res_path / "pr2_description/urdf/robot.xml");
00110   const std::string PR2_SRDF = this->readFileToString(res_path / "pr2_description/srdf/robot.xml");
00111 
00112   robot_state::RobotState pr2_state = this->loadModel(PR2_URDF, PR2_SRDF);
00113 
00114   const Eigen::Vector3d& extentsBaseFootprint = pr2_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin();
00115   // values taken from moveit_resources/pr2_description/urdf/robot.xml
00116   EXPECT_NEAR(extentsBaseFootprint[0], 0.001, 1e-4);
00117   EXPECT_NEAR(extentsBaseFootprint[1], 0.001, 1e-4);
00118   EXPECT_NEAR(extentsBaseFootprint[2], 0.001, 1e-4);
00119 
00120   const Eigen::Vector3d& offsetBaseFootprint = pr2_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset();
00121   EXPECT_NEAR(offsetBaseFootprint[0], 0.0, 1e-4);
00122   EXPECT_NEAR(offsetBaseFootprint[1], 0.0, 1e-4);
00123   EXPECT_NEAR(offsetBaseFootprint[2], 0.071, 1e-4);
00124 
00125   const Eigen::Vector3d& extentsBaseLink = pr2_state.getLinkModel("base_link")->getShapeExtentsAtOrigin();
00126   // values computed from moveit_resources/pr2_description/urdf/meshes/base_v0/base_L.stl in e.g. Meshlab
00127   EXPECT_NEAR(extentsBaseLink[0], 0.668242, 1e-4);
00128   EXPECT_NEAR(extentsBaseLink[1], 0.668242, 1e-4);
00129   EXPECT_NEAR(extentsBaseLink[2], 0.656175, 1e-4);
00130 
00131   const Eigen::Vector3d& offsetBaseLink = pr2_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset();
00132   EXPECT_NEAR(offsetBaseLink[0], 0.0, 1e-4);
00133   EXPECT_NEAR(offsetBaseLink[1], 0.0, 1e-4);
00134   EXPECT_NEAR(offsetBaseLink[2], 0.656175 / 2, 1e-4);  // The 3D mesh isn't centered, but is whole above z axis
00135 
00136   std::vector<double> pr2_aabb;
00137   pr2_state.computeAABB(pr2_aabb);
00138   ASSERT_EQ(pr2_aabb.size(), 6);
00139 
00140   EXPECT_NEAR(pr2_aabb[0], -0.3376, 1e-4);
00141   EXPECT_NEAR(pr2_aabb[1], 0.6499, 1e-4);
00142   EXPECT_NEAR(pr2_aabb[2], -0.6682 / 2, 1e-4);
00143   EXPECT_NEAR(pr2_aabb[3], 0.6682 / 2, 1e-4);
00144   EXPECT_NEAR(pr2_aabb[4], 0.0044, 1e-4);
00145   EXPECT_NEAR(pr2_aabb[5], 1.6328, 1e-4);
00146 
00147   // Test a specific link known to have some global rotation in the default pose
00148 
00149   const moveit::core::LinkModel* link = pr2_state.getLinkModel("l_forearm_link");
00150   Eigen::Affine3d transform = pr2_state.getGlobalLinkTransform(link);  // intentional copy, we will translate
00151   const Eigen::Vector3d& extents = link->getShapeExtentsAtOrigin();
00152   transform.translate(link->getCenteredBoundingBoxOffset());
00153   moveit::core::AABB aabb;
00154   aabb.extendWithTransformedBox(transform, extents);
00155 
00156   EXPECT_NEAR(aabb.center()[0], 0.5394, 1e-4);
00157   EXPECT_NEAR(aabb.center()[1], 0.1880, 1e-4);
00158   EXPECT_NEAR(aabb.center()[2], 1.1665, 1e-4);
00159   EXPECT_NEAR(aabb.sizes()[0], 0.2209, 1e-4);
00160   EXPECT_NEAR(aabb.sizes()[1], 0.1201, 1e-4);
00161   EXPECT_NEAR(aabb.sizes()[2], 0.2901, 1e-4);
00162 
00163 #if VISUALIZE_PR2_RVIZ
00164   std::cout << "Overall bounding box of PR2:" << std::endl;
00165   std::string dims[] = { "x", "y", "z" };
00166   for (std::size_t i = 0; i < 3; ++i)
00167   {
00168     double dim = pr2_aabb[2 * i + 1] - pr2_aabb[2 * i];
00169     double center = dim / 2;
00170     std::cout << dims[i] << ": size=" << dim << ", offset=" << (pr2_aabb[2 * i + 1] - center) << std::endl;
00171   }
00172 
00173   // Initialize a ROS publisher
00174   char* argv[0];
00175   int argc = 0;
00176   ros::init(argc, argv, "visualize_pr2");
00177   ros::NodeHandle nh;
00178   ros::Publisher pub_aabb = nh.advertise<visualization_msgs::Marker>("/visualization_aabb", 10);
00179   ros::Publisher pub_obb = nh.advertise<visualization_msgs::Marker>("/visualization_obb", 10);
00180 
00181   // Wait for the publishers to establish connections
00182   sleep(5);
00183 
00184   // Prepare the ROS message we will reuse throughout the rest of the function.
00185   visualization_msgs::Marker msg;
00186   msg.header.frame_id = pr2_state.getRobotModel()->getRootLinkName();
00187   msg.type = visualization_msgs::Marker::CUBE;
00188   msg.color.a = 0.5;
00189   msg.lifetime.sec = 3000;
00190 
00191   // Publish the AABB of the whole model
00192   msg.ns = "pr2";
00193   msg.pose.position.x = (pr2_aabb[0] + pr2_aabb[1]) / 2;
00194   msg.pose.position.y = (pr2_aabb[2] + pr2_aabb[3]) / 2;
00195   msg.pose.position.z = (pr2_aabb[4] + pr2_aabb[5]) / 2;
00196   msg.pose.orientation.x = msg.pose.orientation.y = msg.pose.orientation.z = 0;
00197   msg.pose.orientation.w = 1;
00198   msg.scale.x = pr2_aabb[1] - pr2_aabb[0];
00199   msg.scale.y = pr2_aabb[3] - pr2_aabb[2];
00200   msg.scale.z = pr2_aabb[5] - pr2_aabb[4];
00201   pub_aabb.publish(msg);
00202 
00203   // Publish BBs for all links
00204   std::vector<const moveit::core::LinkModel*> links = pr2_state.getRobotModel()->getLinkModelsWithCollisionGeometry();
00205   for (std::size_t i = 0; i < links.size(); ++i)
00206   {
00207     Eigen::Affine3d transform = pr2_state.getGlobalLinkTransform(links[i]);  // intentional copy, we will translate
00208     const Eigen::Vector3d& extents = links[i]->getShapeExtentsAtOrigin();
00209     transform.translate(links[i]->getCenteredBoundingBoxOffset());
00210     moveit::core::AABB aabb;
00211     aabb.extendWithTransformedBox(transform, extents);
00212 
00213     // Publish AABB
00214     msg.ns = links[i]->getName();
00215     msg.pose.position.x = transform.translation()[0];
00216     msg.pose.position.y = transform.translation()[1];
00217     msg.pose.position.z = transform.translation()[2];
00218     msg.pose.orientation.x = msg.pose.orientation.y = msg.pose.orientation.z = 0;
00219     msg.pose.orientation.w = 1;
00220     msg.color.r = 1;
00221     msg.color.b = 0;
00222     msg.scale.x = aabb.sizes()[0];
00223     msg.scale.y = aabb.sizes()[1];
00224     msg.scale.z = aabb.sizes()[2];
00225     pub_aabb.publish(msg);
00226 
00227     // Publish OBB (oriented BB)
00228     msg.ns += "-obb";
00229     msg.pose.position.x = transform.translation()[0];
00230     msg.pose.position.y = transform.translation()[1];
00231     msg.pose.position.z = transform.translation()[2];
00232     msg.scale.x = extents[0];
00233     msg.scale.y = extents[1];
00234     msg.scale.z = extents[2];
00235     msg.color.r = 0;
00236     msg.color.b = 1;
00237     Eigen::Quaterniond q(transform.rotation());
00238     msg.pose.orientation.x = q.x();
00239     msg.pose.orientation.y = q.y();
00240     msg.pose.orientation.z = q.z();
00241     msg.pose.orientation.w = q.w();
00242     pub_obb.publish(msg);
00243   }
00244 
00245   // Publish BBs for all attached bodies
00246   std::vector<const moveit::core::AttachedBody*> attached_bodies;
00247   pr2_state.getAttachedBodies(attached_bodies);
00248   for (std::vector<const moveit::core::AttachedBody*>::const_iterator it = attached_bodies.begin();
00249        it != attached_bodies.end(); ++it)
00250   {
00251     const EigenSTL::vector_Affine3d& transforms = (*it)->getGlobalCollisionBodyTransforms();
00252     const std::vector<shapes::ShapeConstPtr>& shapes = (*it)->getShapes();
00253     for (std::size_t i = 0; i < transforms.size(); ++i)
00254     {
00255       Eigen::Vector3d extents = shapes::computeShapeExtents(shapes[i].get());
00256       moveit::core::AABB aabb;
00257       aabb.extendWithTransformedBox(transforms[i], extents);
00258 
00259       // Publish AABB
00260       msg.ns = (*it)->getName() + boost::lexical_cast<std::string>(i);
00261       msg.pose.position.x = transforms[i].translation()[0];
00262       msg.pose.position.y = transforms[i].translation()[1];
00263       msg.pose.position.z = transforms[i].translation()[2];
00264       msg.pose.orientation.x = msg.pose.orientation.y = msg.pose.orientation.z = 0;
00265       msg.pose.orientation.w = 1;
00266       msg.color.r = 1;
00267       msg.color.b = 0;
00268       msg.scale.x = aabb.sizes()[0];
00269       msg.scale.y = aabb.sizes()[1];
00270       msg.scale.z = aabb.sizes()[2];
00271       pub_aabb.publish(msg);
00272 
00273       // Publish OBB (oriented BB)
00274       msg.ns += "-obb";
00275       msg.pose.position.x = transforms[i].translation()[0];
00276       msg.pose.position.y = transforms[i].translation()[1];
00277       msg.pose.position.z = transforms[i].translation()[2];
00278       msg.scale.x = extents[0];
00279       msg.scale.y = extents[1];
00280       msg.scale.z = extents[2];
00281       msg.color.r = 0;
00282       msg.color.b = 1;
00283       Eigen::Quaterniond q(transforms[i].rotation());
00284       msg.pose.orientation.x = q.x();
00285       msg.pose.orientation.y = q.y();
00286       msg.pose.orientation.z = q.z();
00287       msg.pose.orientation.w = q.w();
00288       pub_obb.publish(msg);
00289     }
00290   }
00291 #endif
00292 }
00293 
00294 TEST_F(TestAABB, TestSimple)
00295 {
00296   // Contains a link with simple geometry and an offset in the collision link
00297 
00298   const std::string SIMPLE_URDF =
00299       "<?xml version='1.0' ?>"
00300       "<robot name='simple'>"
00301       "  <link name='base_link'>"
00302       "    <collision>"
00303       "      <origin rpy='0 0 0' xyz='0 0 0'/>"
00304       "      <geometry>"
00305       "        <mesh filename='package://moveit_resources/pr2_description/urdf/meshes/base_v0/base_L.stl'/>"
00306       "      </geometry>"
00307       "    </collision>"
00308       "  </link>"
00309       "  <link name='base_footprint'>"
00310       "    <collision>"
00311       "      <origin rpy='0 0 0' xyz='0 0 0.071'/>"
00312       "      <geometry>"
00313       "        <box size='0.001 0.001 0.001'/>"
00314       "      </geometry>"
00315       "    </collision>"
00316       "  </link>"
00317       "  <joint name='base_footprint_joint' type='fixed'>"
00318       "    <origin rpy='0 0 0' xyz='0 0 0.051'/>"
00319       "    <child link='base_link'/>"
00320       "    <parent link='base_footprint'/>"
00321       "  </joint>"
00322       "</robot>";
00323 
00324   const std::string SIMPLE_SRDF =
00325       "<?xml version='1.0'?>"
00326       "<robot name='simple'>  "
00327       "  <virtual_joint name='world_joint' type='planar' parent_frame='odom_combined' child_link='base_footprint'/>   "
00328       "  <group name='base'>"
00329       "    <joint name='world_joint'/>"
00330       "  </group>    "
00331       "</robot>";
00332 
00333   robot_state::RobotState simple_state = this->loadModel(SIMPLE_URDF, SIMPLE_SRDF);
00334 
00335   std::vector<double> simple_aabb;
00336   simple_state.computeAABB(simple_aabb);
00337 
00338   ASSERT_EQ(simple_aabb.size(), 6);
00339   EXPECT_NEAR(simple_aabb[0], -0.6682 / 2, 1e-4);
00340   EXPECT_NEAR(simple_aabb[1], 0.6682 / 2, 1e-4);
00341   EXPECT_NEAR(simple_aabb[2], -0.6682 / 2, 1e-4);
00342   EXPECT_NEAR(simple_aabb[3], 0.6682 / 2, 1e-4);
00343   EXPECT_NEAR(simple_aabb[4], 0.0510, 1e-4);
00344   EXPECT_NEAR(simple_aabb[5], 0.7071, 1e-4);
00345 }
00346 
00347 TEST_F(TestAABB, TestComplex)
00348 {
00349   // Contains a link with simple geometry and an offset and rotation in the collision link
00350 
00351   const std::string COMPLEX_URDF = "<?xml version='1.0' ?>"
00352                                    "<robot name='complex'>"
00353                                    "  <link name='base_link'>"
00354                                    "    <collision>"
00355                                    "      <origin rpy='0 0 1.5708' xyz='5.0 0 1.0'/>"
00356                                    "      <geometry>"
00357                                    "        <box size='1.0 0.1 0.1' />"
00358                                    "      </geometry>"
00359                                    "    </collision>"
00360                                    "    <collision>"
00361                                    "      <origin rpy='0 0 1.5708' xyz='4.0 0 1.0'/>"
00362                                    "      <geometry>"
00363                                    "        <box size='1.0 0.1 0.1' />"
00364                                    "      </geometry>"
00365                                    "    </collision>"
00366                                    "  </link>"
00367                                    "  <link name='base_footprint'>"
00368                                    "    <collision>"
00369                                    "      <origin rpy='0 1.5708 0' xyz='-5.0 0 -1.0'/>"
00370                                    "      <geometry>"
00371                                    "        <box size='0.1 1.0 0.1' />"
00372                                    "      </geometry>"
00373                                    "    </collision>"
00374                                    "  </link>"
00375                                    "  <joint name='base_footprint_joint' type='fixed'>"
00376                                    "    <origin rpy='0 0 1.5708' xyz='0 0 1'/>"
00377                                    "    <child link='base_link'/>"
00378                                    "    <parent link='base_footprint'/>"
00379                                    "  </joint>"
00380                                    "</robot>";
00381 
00382   const std::string COMPLEX_SRDF =
00383       "<?xml version='1.0'?>"
00384       "<robot name='complex'>  "
00385       "  <virtual_joint name='world_joint' type='planar' parent_frame='odom_combined' child_link='base_footprint'/>   "
00386       "  <group name='base'>"
00387       "    <joint name='world_joint'/>"
00388       "  </group>    "
00389       "</robot>";
00390 
00391   robot_state::RobotState complex_state = this->loadModel(COMPLEX_URDF, COMPLEX_SRDF);
00392 
00393   EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin()[0], 0.1, 1e-4);
00394   EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin()[1], 1.0, 1e-4);
00395   EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getShapeExtentsAtOrigin()[2], 0.1, 1e-4);
00396   EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset()[0], -5.0, 1e-4);
00397   EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset()[1], 0.0, 1e-4);
00398   EXPECT_NEAR(complex_state.getLinkModel("base_footprint")->getCenteredBoundingBoxOffset()[2], -1.0, 1e-4);
00399 
00400   EXPECT_NEAR(complex_state.getLinkModel("base_link")->getShapeExtentsAtOrigin()[0], 1.1, 1e-4);
00401   EXPECT_NEAR(complex_state.getLinkModel("base_link")->getShapeExtentsAtOrigin()[1], 1.0, 1e-4);
00402   EXPECT_NEAR(complex_state.getLinkModel("base_link")->getShapeExtentsAtOrigin()[2], 0.1, 1e-4);
00403   EXPECT_NEAR(complex_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset()[0], 4.5, 1e-4);
00404   EXPECT_NEAR(complex_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset()[1], 0.0, 1e-4);
00405   EXPECT_NEAR(complex_state.getLinkModel("base_link")->getCenteredBoundingBoxOffset()[2], 1.0, 1e-4);
00406 
00407   std::vector<double> complex_aabb;
00408   complex_state.computeAABB(complex_aabb);
00409 
00410   ASSERT_EQ(complex_aabb.size(), 6);
00411   EXPECT_NEAR(complex_aabb[0], -5.05, 1e-4);
00412   EXPECT_NEAR(complex_aabb[1], 0.5, 1e-4);
00413   EXPECT_NEAR(complex_aabb[2], -0.5, 1e-4);
00414   EXPECT_NEAR(complex_aabb[3], 5.05, 1e-4);
00415   EXPECT_NEAR(complex_aabb[4], -1.05, 1e-4);
00416   EXPECT_NEAR(complex_aabb[5], 2.05, 1e-4);
00417 }
00418 
00419 int main(int argc, char** argv)
00420 {
00421   testing::InitGoogleTest(&argc, argv);
00422   return RUN_ALL_TESTS();
00423 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:49