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