moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_bullet_continuous_collision_checking.cpp
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 
37 #include <gtest/gtest.h>
38 #include <rclcpp/rclcpp.hpp>
39 
43 
47 
50 #include <moveit/utils/logger.hpp>
51 
52 #include <urdf_parser/urdf_parser.h>
53 #include <geometric_shapes/shape_operations.h>
54 
55 namespace cb = collision_detection_bullet;
56 
57 rclcpp::Logger getLogger()
58 {
59  return moveit::getLogger("collision_detection.bullet_test");
60 }
61 
63 inline void setToHome(moveit::core::RobotState& panda_state)
64 {
65  panda_state.setToDefaultValues();
66  double joint2 = -0.785;
67  double joint4 = -2.356;
68  double joint6 = 1.571;
69  double joint7 = 0.785;
70  panda_state.setJointPositions("panda_joint2", &joint2);
71  panda_state.setJointPositions("panda_joint4", &joint4);
72  panda_state.setJointPositions("panda_joint6", &joint6);
73  panda_state.setJointPositions("panda_joint7", &joint7);
74  panda_state.update();
75 }
76 
77 class BulletCollisionDetectionTester : public testing::Test
78 {
79 protected:
80  void SetUp() override
81  {
83  robot_model_ok_ = static_cast<bool>(robot_model_);
84 
85  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(*robot_model_->getSRDF());
86 
87  cenv_ = std::make_shared<collision_detection::CollisionEnvBullet>(robot_model_);
88 
89  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
90 
92  }
93 
94  void TearDown() override
95  {
96  }
97 
98 protected:
100 
101  moveit::core::RobotModelPtr robot_model_;
102 
103  collision_detection::CollisionEnvPtr cenv_;
104 
105  collision_detection::AllowedCollisionMatrixPtr acm_;
106 
107  moveit::core::RobotStatePtr robot_state_;
108 };
109 
111 {
113  // Add static box to checker
115  shapes::ShapePtr static_box = std::make_shared<shapes::Box>(1, 1, 1);
116  Eigen::Isometry3d static_box_pose;
117  static_box_pose.setIdentity();
118 
119  std::vector<shapes::ShapeConstPtr> obj1_shapes;
121  std::vector<cb::CollisionObjectType> obj1_types;
122  obj1_shapes.push_back(static_box);
123  obj1_poses.push_back(static_box_pose);
124  obj1_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
125 
126  cb::CollisionObjectWrapperPtr cow_1 = std::make_shared<cb::CollisionObjectWrapper>(
127  "static_box_link", collision_detection::BodyType::WORLD_OBJECT, obj1_shapes, obj1_poses, obj1_types);
128  checker.addCollisionObject(cow_1);
129 
131  // Add moving box to checker
133  shapes::ShapePtr moving_box = std::make_shared<shapes::Box>(0.2, 0.2, 0.2);
134  Eigen::Isometry3d moving_box_pose;
135 
136  moving_box_pose.setIdentity();
137  moving_box_pose.translation() = Eigen::Vector3d(0.5, -0.5, 0);
138 
139  std::vector<shapes::ShapeConstPtr> obj2_shapes;
141  std::vector<cb::CollisionObjectType> obj2_types;
142  obj2_shapes.push_back(moving_box);
143  obj2_poses.push_back(moving_box_pose);
144  obj2_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
145 
146  cb::CollisionObjectWrapperPtr cow_2 = std::make_shared<cb::CollisionObjectWrapper>(
147  "moving_box_link", collision_detection::BodyType::WORLD_OBJECT, obj2_shapes, obj2_poses, obj2_types);
148  checker.addCollisionObject(cow_2);
149 }
150 
152 {
154  // Add static box to checker
156  shapes::ShapePtr static_box = std::make_shared<shapes::Box>(0.3, 0.3, 0.3);
157  Eigen::Isometry3d static_box_pose;
158  static_box_pose.setIdentity();
159 
160  std::vector<shapes::ShapeConstPtr> obj1_shapes;
162  std::vector<cb::CollisionObjectType> obj1_types;
163  obj1_shapes.push_back(static_box);
164  obj1_poses.push_back(static_box_pose);
165  obj1_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
166 
167  cb::CollisionObjectWrapperPtr cow_1 = std::make_shared<cb::CollisionObjectWrapper>(
168  "static_box_link", collision_detection::BodyType::WORLD_OBJECT, obj1_shapes, obj1_poses, obj1_types);
169  checker.addCollisionObject(cow_1);
171  // Add moving mesh to checker
173 
174  std::vector<shapes::ShapeConstPtr> obj2_shapes;
176  std::vector<cb::CollisionObjectType> obj2_types;
177 
178  obj1_poses.push_back(static_box_pose);
179  obj1_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
180 
181  Eigen::Isometry3d s_pose;
182  s_pose.setIdentity();
183 
184  std::string kinect = "package://moveit_resources_panda_description/meshes/collision/hand.stl";
185  auto s = std::shared_ptr<shapes::Shape>{ shapes::createMeshFromResource(kinect) };
186  obj2_shapes.push_back(s);
187  obj2_types.push_back(cb::CollisionObjectType::CONVEX_HULL);
188  obj2_poses.push_back(s_pose);
189 
190  cb::CollisionObjectWrapperPtr cow_2 = std::make_shared<cb::CollisionObjectWrapper>(
191  "moving_box_link", collision_detection::BodyType::WORLD_OBJECT, obj2_shapes, obj2_poses, obj2_types);
192  checker.addCollisionObject(cow_2);
193 }
194 
196  std::vector<collision_detection::Contact>& result_vector, Eigen::Isometry3d& start_pos,
197  Eigen::Isometry3d& end_pos)
198 {
200  // Test when object is inside another
202  checker.setActiveCollisionObjects({ "moving_box_link" });
203  checker.setContactDistanceThreshold(0.1);
204 
205  // Set the collision object transforms
206  checker.setCollisionObjectsTransform("static_box_link", Eigen::Isometry3d::Identity());
207  checker.setCastCollisionObjectsTransform("moving_box_link", start_pos, end_pos);
208 
209  // Perform collision check
211  request.contacts = true;
212  // cb::ContactResultMap result;
213  checker.contactTest(result, request, nullptr, false);
214 
215  for (const auto& contacts_all : result.contacts)
216  {
217  for (const auto& contact : contacts_all.second)
218  {
219  result_vector.push_back(contact);
220  }
221  }
222 }
223 
224 // TODO(j-petit): Add continuous to continuous collision checking
226 TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
227 {
230 
231  moveit::core::RobotState state1(robot_model_);
232  moveit::core::RobotState state2(robot_model_);
233 
234  setToHome(state1);
235  double joint2 = 0.15;
236  double joint4 = -3.0;
237  double joint5 = -0.8;
238  double joint7 = -0.785;
239  state1.setJointPositions("panda_joint2", &joint2);
240  state1.setJointPositions("panda_joint4", &joint4);
241  state1.setJointPositions("panda_joint5", &joint5);
242  state1.setJointPositions("panda_joint7", &joint7);
243  state1.update();
244 
245  cenv_->checkSelfCollision(req, res, state1, *acm_);
246  ASSERT_FALSE(res.collision);
247  res.clear();
248 
249  setToHome(state2);
250  double joint_5_other = 0.8;
251  state2.setJointPositions("panda_joint2", &joint2);
252  state2.setJointPositions("panda_joint4", &joint4);
253  state2.setJointPositions("panda_joint5", &joint_5_other);
254  state2.setJointPositions("panda_joint7", &joint7);
255  state2.update();
256 
257  cenv_->checkSelfCollision(req, res, state2, *acm_);
258  ASSERT_FALSE(res.collision);
259  res.clear();
260 
261  RCLCPP_INFO(getLogger(), "Continuous to continuous collisions are not supported yet, therefore fail here.");
262  ASSERT_TRUE(res.collision);
263  res.clear();
264 }
265 
267 TEST_F(BulletCollisionDetectionTester, ContinuousCollisionWorld)
268 {
270  req.contacts = true;
271  req.max_contacts = 10;
273 
274  moveit::core::RobotState state1(robot_model_);
275  moveit::core::RobotState state2(robot_model_);
276 
277  setToHome(state1);
278  state1.update();
279 
280  setToHome(state2);
281  double joint_2{ 0.05 };
282  double joint_4{ -1.6 };
283  state2.setJointPositions("panda_joint2", &joint_2);
284  state2.setJointPositions("panda_joint4", &joint_4);
285  state2.update();
286 
287  cenv_->checkRobotCollision(req, res, state1, state2, *acm_);
288  ASSERT_FALSE(res.collision);
289  res.clear();
290 
291  // Adding the box which is not in collision with the individual states but with the casted one.
292  shapes::Shape* shape = new shapes::Box(0.1, 0.1, 0.1);
293  shapes::ShapeConstPtr shape_ptr(shape);
294 
295  Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
296  pos.translation().x() = 0.43;
297  pos.translation().y() = 0;
298  pos.translation().z() = 0.55;
299  cenv_->getWorld()->addToObject("box", shape_ptr, pos);
300 
301  cenv_->checkRobotCollision(req, res, state1, *acm_);
302  ASSERT_FALSE(res.collision);
303  res.clear();
304 
305  cenv_->checkRobotCollision(req, res, state2, *acm_);
306  ASSERT_FALSE(res.collision);
307  res.clear();
308 
309  cenv_->checkRobotCollision(req, res, state1, state2, *acm_);
310  ASSERT_TRUE(res.collision);
311  ASSERT_EQ(res.contact_count, 4u);
312  // test contact types
313  for (auto& contact_pair : res.contacts)
314  {
315  for (collision_detection::Contact& contact : contact_pair.second)
316  {
317  collision_detection::BodyType contact_type1 = contact.body_name_1 == "box" ?
320  collision_detection::BodyType contact_type2 = contact.body_name_2 == "box" ?
323  ASSERT_EQ(contact.body_type_1, contact_type1);
324  ASSERT_EQ(contact.body_type_2, contact_type2);
325  }
326  }
327  res.clear();
328 }
329 
330 TEST(ContinuousCollisionUnit, BulletCastBVHCollisionBoxBoxUnit)
331 {
333  std::vector<collision_detection::Contact> result_vector;
334 
335  Eigen::Isometry3d start_pos, end_pos;
336  start_pos.setIdentity();
337  start_pos.translation().x() = -2;
338  end_pos.setIdentity();
339  end_pos.translation().x() = 2;
340 
341  cb::BulletCastBVHManager checker;
342  addCollisionObjects(checker);
343  runTest(checker, result, result_vector, start_pos, end_pos);
344 
345  ASSERT_TRUE(result.collision);
346  EXPECT_NEAR(result_vector[0].depth, -0.6, 0.001);
347  EXPECT_NEAR(result_vector[0].percent_interpolation, 0.6, 0.001);
348 }
349 
350 TEST(ContinuousCollisionUnit, BulletCastMeshVsBox)
351 {
352  cb::BulletCastBVHManager checker;
353  addCollisionObjectsMesh(checker);
354 
355  Eigen::Isometry3d start_pos, end_pos;
356  start_pos.setIdentity();
357  start_pos.translation().x() = -1.9;
358  end_pos.setIdentity();
359  end_pos.translation().x() = 1.9;
360 
362  std::vector<collision_detection::Contact> result_vector;
363 
364  runTest(checker, result, result_vector, start_pos, end_pos);
365 
366  ASSERT_TRUE(result.collision);
367 }
368 
369 int main(int argc, char** argv)
370 {
371  testing::InitGoogleTest(&argc, argv);
372  return RUN_ALL_TESTS();
373 }
collision_detection::AllowedCollisionMatrixPtr acm_
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)
Set a single static collision object's transform.
void setContactDistanceThreshold(double contact_distance)
Set the contact distance threshold for which collision should be considered through expanding the AAB...
void setActiveCollisionObjects(const std::vector< std::string > &names)
Set which collision objects are active.
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
void setCastCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)
Set a single cast (moving) collision object's transforms.
void contactTest(collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self) override
Perform a contact test for all objects.
void addCollisionObject(const CollisionObjectWrapperPtr &cow) override
Add a tesseract collision object to the manager.
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
Type
The types of bodies that are considered for collision.
@ ROBOT_LINK
A link on the robot.
@ WORLD_OBJECT
A body in the environment.
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
Definition: basic_types.h:37
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
Representation of a collision checking request.
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.
Representation of a collision checking result.
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.
Definition of a contact point.
std::string body_name_2
The id of the second body involved in the contact.
std::string body_name_1
The id of the first body involved in the contact.
BodyType body_type_1
The type of the first body involved in the contact.
BodyType body_type_2
The type of the second body involved in the contact.
int main(int argc, char **argv)
rclcpp::Logger getLogger()
void addCollisionObjectsMesh(cb::BulletCastBVHManager &checker)
TEST(ContinuousCollisionUnit, BulletCastBVHCollisionBoxBoxUnit)
void runTest(cb::BulletCastBVHManager &checker, collision_detection::CollisionResult &result, std::vector< collision_detection::Contact > &result_vector, Eigen::Isometry3d &start_pos, Eigen::Isometry3d &end_pos)
void setToHome(moveit::core::RobotState &panda_state)
Brings the panda robot in user defined home position.
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.
void addCollisionObjects(cb::BulletCastBVHManager &checker)