moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_fcl_env.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 
40 
44 
47 
48 #include <urdf_parser/urdf_parser.h>
49 #include <geometric_shapes/shape_operations.h>
50 
52 inline void setToHome(moveit::core::RobotState& panda_state)
53 {
54  panda_state.setToDefaultValues();
55  double joint2 = -0.785;
56  double joint4 = -2.356;
57  double joint6 = 1.571;
58  double joint7 = 0.785;
59  panda_state.setJointPositions("panda_joint2", &joint2);
60  panda_state.setJointPositions("panda_joint4", &joint4);
61  panda_state.setJointPositions("panda_joint6", &joint6);
62  panda_state.setJointPositions("panda_joint7", &joint7);
63  panda_state.update();
64 }
65 
66 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection_fcl.test.test_fcl_env");
67 
68 class CollisionDetectionEnvTest : public testing::Test
69 {
70 protected:
71  void SetUp() override
72  {
74  robot_model_ok_ = static_cast<bool>(robot_model_);
75 
76  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(robot_model_->getLinkModelNames(), false);
77 
78  acm_->setEntry("panda_link0", "panda_link1", true);
79  acm_->setEntry("panda_link1", "panda_link2", true);
80  acm_->setEntry("panda_link2", "panda_link3", true);
81  acm_->setEntry("panda_link3", "panda_link4", true);
82  acm_->setEntry("panda_link4", "panda_link5", true);
83  acm_->setEntry("panda_link5", "panda_link6", true);
84  acm_->setEntry("panda_link6", "panda_link7", true);
85  acm_->setEntry("panda_link7", "panda_hand", true);
86  acm_->setEntry("panda_hand", "panda_rightfinger", true);
87  acm_->setEntry("panda_hand", "panda_leftfinger", true);
88  acm_->setEntry("panda_rightfinger", "panda_leftfinger", true);
89  acm_->setEntry("panda_link5", "panda_link7", true);
90  acm_->setEntry("panda_link6", "panda_hand", true);
91 
92  c_env_ = std::make_shared<collision_detection::CollisionEnvFCL>(robot_model_);
93 
94  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
95 
97  }
98 
99  void TearDown() override
100  {
101  }
102 
103 protected:
105 
106  moveit::core::RobotModelPtr robot_model_;
107 
108  collision_detection::CollisionEnvPtr c_env_;
109 
110  collision_detection::AllowedCollisionMatrixPtr acm_;
111 
112  moveit::core::RobotStatePtr robot_state_;
113 };
114 
117 {
118  ASSERT_TRUE(robot_model_ok_);
119 }
120 
122 TEST_F(CollisionDetectionEnvTest, DefaultNotInCollision)
123 {
126  c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
127  ASSERT_FALSE(res.collision);
128 }
129 
132 {
133  // Sets the joint values to zero which is a colliding configuration
134  robot_state_->setToDefaultValues();
135  robot_state_->update();
136 
139  c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
140  ASSERT_TRUE(res.collision);
141 }
142 
144 TEST_F(CollisionDetectionEnvTest, RobotWorldCollision_1)
145 {
148 
149  shapes::Shape* shape = new shapes::Box(.1, .1, .1);
150  shapes::ShapeConstPtr shape_ptr(shape);
151 
152  Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
153  pos1.translation().z() = 0.3;
154  c_env_->getWorld()->addToObject("box", shape_ptr, pos1);
155 
156  c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
157  ASSERT_FALSE(res.collision);
158  res.clear();
159 
160  c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
161  ASSERT_TRUE(res.collision);
162  res.clear();
163 
164  c_env_->getWorld()->moveObject("box", pos1);
165  c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
166  ASSERT_TRUE(res.collision);
167  res.clear();
168 
169  c_env_->getWorld()->moveObject("box", pos1);
170  ASSERT_FALSE(res.collision);
171 }
172 
174 TEST_F(CollisionDetectionEnvTest, RobotWorldCollision_2)
175 {
178  req.max_contacts = 10;
179  req.contacts = true;
180  req.verbose = true;
181 
182  shapes::Shape* shape = new shapes::Box(.4, .4, .4);
183  shapes::ShapeConstPtr shape_ptr(shape);
184 
185  Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
186  pos1.translation().z() = 0.3;
187  c_env_->getWorld()->addToObject("box", shape_ptr, pos1);
188  c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
189  ASSERT_TRUE(res.collision);
190  ASSERT_GE(res.contact_count, 3u);
191  res.clear();
192 }
193 
196 {
198  req.contacts = true;
199  req.max_contacts = 10;
201 
202  c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
203  ASSERT_FALSE(res.collision);
204  res.clear();
205 
206  // Adding the box right in front of the robot hand
207  shapes::Shape* shape = new shapes::Box(0.1, 0.1, 0.1);
208  shapes::ShapeConstPtr shape_ptr(shape);
209 
210  Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
211  pos.translation().x() = 0.43;
212  pos.translation().y() = 0;
213  pos.translation().z() = 0.55;
214  c_env_->getWorld()->addToObject("box", shape_ptr, pos);
215 
216  c_env_->setLinkPadding("panda_hand", 0.08);
217  c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
218  ASSERT_TRUE(res.collision);
219  res.clear();
220 
221  c_env_->setLinkPadding("panda_hand", 0.0);
222  c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
223  ASSERT_FALSE(res.collision);
224 }
225 
229 TEST_F(CollisionDetectionEnvTest, DISABLED_ContinuousCollisionSelf)
230 {
233 
234  moveit::core::RobotState state1(robot_model_);
235  moveit::core::RobotState state2(robot_model_);
236 
237  setToHome(state1);
238  double joint2 = 0.15;
239  double joint4 = -3.0;
240  double joint5 = -0.8;
241  double joint7 = -0.785;
242  state1.setJointPositions("panda_joint2", &joint2);
243  state1.setJointPositions("panda_joint4", &joint4);
244  state1.setJointPositions("panda_joint5", &joint5);
245  state1.setJointPositions("panda_joint7", &joint7);
246  state1.update();
247 
248  c_env_->checkSelfCollision(req, res, state1, *acm_);
249  ASSERT_FALSE(res.collision);
250  res.clear();
251 
252  setToHome(state2);
253  double joint_5_other = 0.8;
254  state2.setJointPositions("panda_joint2", &joint2);
255  state2.setJointPositions("panda_joint4", &joint4);
256  state2.setJointPositions("panda_joint5", &joint_5_other);
257  state2.setJointPositions("panda_joint7", &joint7);
258  state2.update();
259 
260  c_env_->checkSelfCollision(req, res, state2, *acm_);
261  ASSERT_FALSE(res.collision);
262  res.clear();
263 
264  // c_env_->checkSelfCollision(req, res, state1, state2, *acm_);
265  RCLCPP_INFO(LOGGER, "Continuous to continuous collisions are not supported yet, therefore fail here.");
266  ASSERT_TRUE(res.collision);
267  res.clear();
268 }
269 
273 TEST_F(CollisionDetectionEnvTest, DISABLED_ContinuousCollisionWorld)
274 {
276  req.contacts = true;
277  req.max_contacts = 10;
279 
280  moveit::core::RobotState state1(robot_model_);
281  moveit::core::RobotState state2(robot_model_);
282 
283  setToHome(state1);
284  state1.update();
285 
286  setToHome(state2);
287  double joint_2{ 0.05 };
288  double joint_4{ -1.6 };
289  state2.setJointPositions("panda_joint2", &joint_2);
290  state2.setJointPositions("panda_joint4", &joint_4);
291  state2.update();
292 
293  c_env_->checkRobotCollision(req, res, state1, state2, *acm_);
294  ASSERT_FALSE(res.collision);
295  res.clear();
296 
297  // Adding the box which is not in collision with the individual states but sits right between them.
298  shapes::Shape* shape = new shapes::Box(0.1, 0.1, 0.1);
299  shapes::ShapeConstPtr shape_ptr(shape);
300 
301  Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
302  pos.translation().x() = 0.43;
303  pos.translation().y() = 0;
304  pos.translation().z() = 0.55;
305  c_env_->getWorld()->addToObject("box", shape_ptr, pos);
306 
307  c_env_->checkRobotCollision(req, res, state1, *acm_);
308  ASSERT_FALSE(res.collision);
309  res.clear();
310 
311  c_env_->checkRobotCollision(req, res, state2, *acm_);
312  ASSERT_FALSE(res.collision);
313  res.clear();
314 
315  c_env_->checkRobotCollision(req, res, state1, state2, *acm_);
316  ASSERT_TRUE(res.collision);
317  ASSERT_EQ(res.contact_count, 4u);
318  res.clear();
319 }
320 
321 int main(int argc, char** argv)
322 {
323  testing::InitGoogleTest(&argc, argv);
324  return RUN_ALL_TESTS();
325 }
moveit::core::RobotStatePtr robot_state_
moveit::core::RobotModelPtr robot_model_
collision_detection::CollisionEnvPtr c_env_
collision_detection::AllowedCollisionMatrixPtr acm_
void TearDown() override
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
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
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.
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.
int main(int argc, char **argv)
void setToHome(moveit::core::RobotState &panda_state)
Brings the panda robot in user defined home position.
TEST_F(CollisionDetectionEnvTest, InitOK)
Correct setup testing.