44 #include <urdf_parser/urdf_parser.h>
47 #include <gtest/gtest.h>
57 double joint2 = -0.785;
58 double joint4 = -2.356;
59 double joint6 = 1.571;
60 double joint7 = 0.785;
68 template <
class CollisionAllocatorType>
72 std::shared_ptr<CollisionAllocatorType>
value_;
77 value_ = std::make_shared<CollisionAllocatorType>();
81 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(*
robot_model_->getSRDF());
97 collision_detection::CollisionEnvPtr
cenv_;
99 collision_detection::AllowedCollisionMatrixPtr
acm_;
109 ASSERT_TRUE(this->robot_model_ok_);
117 this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
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();
133 this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
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());
150 this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
154 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
158 pos1.translation().z() = 0.25;
159 this->cenv_->getWorld()->moveObject(
"box", pos1);
160 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
164 pos1.translation().z() = 0.05;
165 this->cenv_->getWorld()->moveObject(
"box", pos1);
166 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
170 pos1.translation().z() = 0.25;
171 this->cenv_->getWorld()->moveObject(
"box", pos1);
172 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
176 this->cenv_->getWorld()->moveObject(
"box", pos1);
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());
196 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
210 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
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());
224 this->cenv_->setLinkPadding(
"panda_hand", 0.08);
225 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
229 this->cenv_->setLinkPadding(
"panda_hand", 0.0);
230 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
240 this->cenv_->checkSelfCollision(req, res, *this->robot_state_, *this->acm_);
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());
261 this->cenv_->setLinkPadding(
"panda_hand", 0.0);
262 this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
267 template <
class CollisionAllocatorType>
276 std::set<const moveit::core::LinkModel*> active_components{ this->robot_model_->getLinkModel(
"panda_hand") };
283 double min_distance = std::numeric_limits<double>::max();
284 for (
int i = 0; i < 10; ++i)
289 Eigen::Isometry3d pose{ Eigen::Isometry3d::Identity() };
294 pose.linear() = Eigen::Quaterniond(quat[0], quat[1], quat[2], quat[3]).toRotationMatrix();
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());
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";
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";
315 template <
class CollisionAllocatorType>
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);
336 req.
acm = &*this->acm_;
342 this->cenv_->distanceRobot(req, res, *this->robot_state_);
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);
360 if (pair.link_names[0] ==
"box")
361 check_in_box(pair.nearest_points[0]);
362 else if (pair.link_names[1] ==
"box")
363 check_in_box(pair.nearest_points[1]);
365 ADD_FAILURE() <<
"Unrecognized link names";
371 RobotWorldCollision_1, RobotWorldCollision_2, PaddingTest, DistanceSelf, DistanceWorld);