moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_collision_common_panda.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Jens Petit
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Jens Petit */
36 
43 
44 #include <urdf_parser/urdf_parser.h>
45 #include <geometric_shapes/shape_operations.h>
46 
47 #include <gtest/gtest.h>
48 #include <sstream>
49 #include <algorithm>
50 #include <ctype.h>
51 #include <fstream>
52 
54 inline void setToHome(moveit::core::RobotState& panda_state)
55 {
56  panda_state.setToDefaultValues();
57  double joint2 = -0.785;
58  double joint4 = -2.356;
59  double joint6 = 1.571;
60  double joint7 = 0.785;
61  panda_state.setJointPositions("panda_joint2", &joint2);
62  panda_state.setJointPositions("panda_joint4", &joint4);
63  panda_state.setJointPositions("panda_joint6", &joint6);
64  panda_state.setJointPositions("panda_joint7", &joint7);
65  panda_state.update();
66 }
67 
68 template <class CollisionAllocatorType>
69 class CollisionDetectorPandaTest : public testing::Test
70 {
71 public:
72  std::shared_ptr<CollisionAllocatorType> value_;
73 
74 protected:
75  void SetUp() override
76  {
77  value_ = std::make_shared<CollisionAllocatorType>();
79  robot_model_ok_ = static_cast<bool>(robot_model_);
80 
81  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(*robot_model_->getSRDF());
82 
83  cenv_ = value_->allocateEnv(robot_model_);
84 
85  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
87  }
88 
89  void TearDown() override
90  {
91  }
92 
94 
95  moveit::core::RobotModelPtr robot_model_;
96 
97  collision_detection::CollisionEnvPtr cenv_;
98 
99  collision_detection::AllowedCollisionMatrixPtr acm_;
100 
101  moveit::core::RobotStatePtr robot_state_;
102 };
103 
105 
108 {
109  ASSERT_TRUE(this->robot_model_ok_);
110 }
111 
114 {
117  this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
118  ASSERT_FALSE(res.collision);
119 }
120 
123 {
124  // Sets the joints into a colliding configuration
125  double joint2 = 0.15;
126  double joint4 = -3.0;
127  this->robot_state_->setJointPositions("panda_joint2", &joint2);
128  this->robot_state_->setJointPositions("panda_joint4", &joint4);
129  this->robot_state_->update();
130 
133  this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
134  ASSERT_TRUE(res.collision);
135 }
136 
139 {
142 
143  shapes::Shape* shape = new shapes::Box(.1, .1, .1);
144  shapes::ShapeConstPtr shape_ptr(shape);
145 
146  Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
147  pos1.translation().z() = 0.3;
148  this->cenv_->getWorld()->addToObject("box", pos1, shape_ptr, Eigen::Isometry3d::Identity());
149 
150  this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
151  ASSERT_FALSE(res.collision);
152  res.clear();
153 
154  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
155  ASSERT_TRUE(res.collision);
156  res.clear();
157 
158  pos1.translation().z() = 0.25;
159  this->cenv_->getWorld()->moveObject("box", pos1);
160  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
161  ASSERT_FALSE(res.collision);
162  res.clear();
163 
164  pos1.translation().z() = 0.05;
165  this->cenv_->getWorld()->moveObject("box", pos1);
166  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
167  ASSERT_TRUE(res.collision);
168  res.clear();
169 
170  pos1.translation().z() = 0.25;
171  this->cenv_->getWorld()->moveObject("box", pos1);
172  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
173  ASSERT_FALSE(res.collision);
174  res.clear();
175 
176  this->cenv_->getWorld()->moveObject("box", pos1);
177  ASSERT_FALSE(res.collision);
178 }
179 
182 {
185  req.max_contacts = 10;
186  req.contacts = true;
187  req.verbose = true;
188 
189  shapes::Shape* shape = new shapes::Box(.4, .4, .4);
190  shapes::ShapeConstPtr shape_ptr(shape);
191 
192  Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
193  pos1.translation().z() = 0.3;
194  this->cenv_->getWorld()->addToObject("box", pos1, shape_ptr, Eigen::Isometry3d::Identity());
195 
196  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
197  ASSERT_TRUE(res.collision);
198  ASSERT_GE(res.contact_count, 3u);
199  res.clear();
200 }
201 
204 {
206  req.contacts = true;
207  req.max_contacts = 10;
209 
210  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
211  ASSERT_FALSE(res.collision);
212  res.clear();
213 
214  // Adding the box right in front of the robot hand
215  shapes::Shape* shape = new shapes::Box(0.1, 0.1, 0.1);
216  shapes::ShapeConstPtr shape_ptr(shape);
217 
218  Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
219  pos.translation().x() = 0.43;
220  pos.translation().y() = 0;
221  pos.translation().z() = 0.55;
222  this->cenv_->getWorld()->addToObject("box", pos, shape_ptr, Eigen::Isometry3d::Identity());
223 
224  this->cenv_->setLinkPadding("panda_hand", 0.08);
225  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
226  ASSERT_TRUE(res.collision);
227  res.clear();
228 
229  this->cenv_->setLinkPadding("panda_hand", 0.0);
230  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
231  ASSERT_FALSE(res.collision);
232 }
233 
236 {
238  req.distance = true;
240  this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
241  ASSERT_FALSE(res.collision);
242  EXPECT_NEAR(res.distance, 0.022, 0.001);
243 }
244 
246 {
248  req.distance = true;
250 
251  // Adding the box right in front of the robot hand
252  shapes::Shape* shape = new shapes::Box(0.1, 0.1, 0.1);
253  shapes::ShapeConstPtr shape_ptr(shape);
254 
255  Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
256  pos.translation().x() = 0.43;
257  pos.translation().y() = 0;
258  pos.translation().z() = 0.55;
259  this->cenv_->getWorld()->addToObject("box", pos, shape_ptr, Eigen::Isometry3d::Identity());
260 
261  this->cenv_->setLinkPadding("panda_hand", 0.0);
262  this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
263  ASSERT_FALSE(res.collision);
264  EXPECT_NEAR(res.distance, 0.029, 0.01);
265 }
266 
267 template <class CollisionAllocatorType>
268 class DistanceCheckPandaTest : public CollisionDetectorPandaTest<CollisionAllocatorType>
269 {
270 };
271 
273 
275 {
276  std::set<const moveit::core::LinkModel*> active_components{ this->robot_model_->getLinkModel("panda_hand") };
279  req.active_components_only = &active_components;
280  req.enable_signed_distance = true;
281 
282  random_numbers::RandomNumberGenerator rng(0x47110815);
283  double min_distance = std::numeric_limits<double>::max();
284  for (int i = 0; i < 10; ++i)
285  {
287 
288  shapes::ShapeConstPtr shape = std::make_shared<const shapes::Cylinder>(rng.uniform01(), rng.uniform01());
289  Eigen::Isometry3d pose{ Eigen::Isometry3d::Identity() };
290  pose.translation() =
291  Eigen::Vector3d(rng.uniformReal(0.1, 2.0), rng.uniformReal(0.1, 2.0), rng.uniformReal(1.2, 1.7));
292  double quat[4];
293  rng.quaternion(quat);
294  pose.linear() = Eigen::Quaterniond(quat[0], quat[1], quat[2], quat[3]).toRotationMatrix();
295 
296  this->cenv_->getWorld()->addToObject("collection", Eigen::Isometry3d::Identity(), shape, pose);
297  this->cenv_->getWorld()->removeObject("object");
298  this->cenv_->getWorld()->addToObject("object", pose, shape, Eigen::Isometry3d::Identity());
299 
300  this->cenv_->distanceRobot(req, res, *this->robot_state_);
301  auto& distances1 = res.distances[std::pair<std::string, std::string>("collection", "panda_hand")];
302  auto& distances2 = res.distances[std::pair<std::string, std::string>("object", "panda_hand")];
303  ASSERT_EQ(distances1.size(), 1u) << "no distance reported for collection/panda_hand";
304  ASSERT_EQ(distances2.size(), 1u) << "no distance reported for object/panda_hand";
305 
306  double collection_distance = distances1[0].distance;
307  min_distance = std::min(min_distance, distances2[0].distance);
308  ASSERT_NEAR(collection_distance, min_distance, 1e-5)
309  << "distance to collection is greater than distance to minimum of individual objects after " << i << " rounds";
310  }
311 }
312 
313 // FCL < 0.6 completely fails the DistancePoints test, so we have two test
314 // suites, one with and one without the test.
315 template <class CollisionAllocatorType>
316 class DistanceFullPandaTest : public DistanceCheckPandaTest<CollisionAllocatorType>
317 {
318 };
319 
321 
324 {
325  // Adding the box right in front of the robot hand
326  shapes::Box* shape = new shapes::Box(0.1, 0.1, 0.1);
327  shapes::ShapeConstPtr shape_ptr(shape);
328 
329  Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
330  pos.translation().x() = 0.43;
331  pos.translation().y() = 0;
332  pos.translation().z() = 0.55;
333  this->cenv_->getWorld()->addToObject("box", shape_ptr, pos);
334 
336  req.acm = &*this->acm_;
338  req.enable_nearest_points = true;
339  req.max_contacts_per_body = 1;
340 
342  this->cenv_->distanceRobot(req, res, *this->robot_state_);
343 
344  // Checks a particular point is inside the box
345  auto check_in_box = [&](const Eigen::Vector3d& p) {
346  Eigen::Vector3d in_box = pos.inverse() * p;
347 
348  constexpr double eps = 1e-5;
349  EXPECT_LE(std::abs(in_box.x()), shape->size[0] + eps);
350  EXPECT_LE(std::abs(in_box.y()), shape->size[1] + eps);
351  EXPECT_LE(std::abs(in_box.z()), shape->size[2] + eps);
352  };
353 
354  // Check that all points reported on "box" are actually on the box and not
355  // on the robot
356  for (auto& distance : res.distances)
357  {
358  for (auto& pair : distance.second)
359  {
360  if (pair.link_names[0] == "box")
361  {
362  check_in_box(pair.nearest_points[0]);
363  }
364  else if (pair.link_names[1] == "box")
365  {
366  check_in_box(pair.nearest_points[1]);
367  }
368  else
369  {
370  ADD_FAILURE() << "Unrecognized link names";
371  }
372  }
373  }
374 }
375 
376 REGISTER_TYPED_TEST_SUITE_P(CollisionDetectorPandaTest, InitOK, DefaultNotInCollision, LinksInCollision,
377  RobotWorldCollision_1, RobotWorldCollision_2, PaddingTest, DistanceSelf, DistanceWorld);
378 
380 
collision_detection::CollisionEnvPtr cenv_
moveit::core::RobotModelPtr robot_model_
std::shared_ptr< CollisionAllocatorType > value_
moveit::core::RobotStatePtr robot_state_
collision_detection::AllowedCollisionMatrixPtr acm_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
@ SINGLE
Find the global minimum for each pair.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:59
Representation of a collision checking request.
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
double distance
Closest distance between two bodies.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.
Representation of a distance-reporting request.
const std::set< const moveit::core::LinkModel * > * active_components_only
The set of active components to check.
std::size_t max_contacts_per_body
Maximum number of contacts to store for bodies (multiple bodies may be within distance threshold)
bool enable_signed_distance
Indicate if a signed distance should be calculated in a collision.
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
bool enable_nearest_points
Indicate if nearest point information should be calculated.
Result of a distance request.
DistanceMap distances
A map of distance data for each link in the req.active_components_only.
TYPED_TEST_CASE_P(CollisionDetectorPandaTest)
void setToHome(moveit::core::RobotState &panda_state)
Brings the panda robot in user defined home position.
TYPED_TEST_P(CollisionDetectorPandaTest, InitOK)
Correct setup testing.
REGISTER_TYPED_TEST_SUITE_P(CollisionDetectorPandaTest, InitOK, DefaultNotInCollision, LinksInCollision, RobotWorldCollision_1, RobotWorldCollision_2, PaddingTest, DistanceSelf, DistanceWorld)