37 #include <gtest/gtest.h>
49 #include <urdf_parser/urdf_parser.h>
56 double joint2 = -0.785;
57 double joint4 = -2.356;
58 double joint6 = 1.571;
59 double joint7 = 0.785;
75 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
robot_model_->getLinkModelNames(),
false);
77 acm_->setEntry(
"panda_link0",
"panda_link1",
true);
78 acm_->setEntry(
"panda_link1",
"panda_link2",
true);
79 acm_->setEntry(
"panda_link2",
"panda_link3",
true);
80 acm_->setEntry(
"panda_link3",
"panda_link4",
true);
81 acm_->setEntry(
"panda_link4",
"panda_link5",
true);
82 acm_->setEntry(
"panda_link5",
"panda_link6",
true);
83 acm_->setEntry(
"panda_link6",
"panda_link7",
true);
84 acm_->setEntry(
"panda_link7",
"panda_hand",
true);
85 acm_->setEntry(
"panda_hand",
"panda_rightfinger",
true);
86 acm_->setEntry(
"panda_hand",
"panda_leftfinger",
true);
87 acm_->setEntry(
"panda_rightfinger",
"panda_leftfinger",
true);
88 acm_->setEntry(
"panda_link5",
"panda_link7",
true);
89 acm_->setEntry(
"panda_link6",
"panda_hand",
true);
107 collision_detection::CollisionEnvPtr
c_env_;
109 collision_detection::AllowedCollisionMatrixPtr
acm_;
117 ASSERT_TRUE(robot_model_ok_);
125 c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
133 robot_state_->setToDefaultValues();
134 robot_state_->update();
138 c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
151 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
152 pos1.translation().z() = 0.3;
153 c_env_->getWorld()->addToObject(
"box", shape_ptr, pos1);
155 c_env_->checkSelfCollision(req, res, *robot_state_, *acm_);
159 c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
163 c_env_->getWorld()->moveObject(
"box", pos1);
164 c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
168 c_env_->getWorld()->moveObject(
"box", pos1);
184 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
185 pos1.translation().z() = 0.3;
186 c_env_->getWorld()->addToObject(
"box", shape_ptr, pos1);
187 c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
201 c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
209 Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
210 pos.translation().x() = 0.43;
211 pos.translation().y() = 0;
212 pos.translation().z() = 0.55;
213 c_env_->getWorld()->addToObject(
"box", shape_ptr, pos);
215 c_env_->setLinkPadding(
"panda_hand", 0.08);
216 c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
220 c_env_->setLinkPadding(
"panda_hand", 0.0);
221 c_env_->checkRobotCollision(req, res, *robot_state_, *acm_);
237 double joint2 = 0.15;
238 double joint4 = -3.0;
239 double joint5 = -0.8;
240 double joint7 = -0.785;
247 c_env_->checkSelfCollision(req, res, state1, *acm_);
252 double joint_5_other = 0.8;
259 c_env_->checkSelfCollision(req, res, state2, *acm_);
264 ROS_INFO_STREAM(
"Continous to continous collisions are not supported yet, therefore fail here.");
286 double joint_2{ 0.05 };
287 double joint_4{ -1.6 };
292 c_env_->checkRobotCollision(req, res, state1, state2, *acm_);
300 Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
301 pos.translation().x() = 0.43;
302 pos.translation().y() = 0;
303 pos.translation().z() = 0.55;
304 c_env_->getWorld()->addToObject(
"box", shape_ptr, pos);
306 c_env_->checkRobotCollision(req, res, state1, *acm_);
310 c_env_->checkRobotCollision(req, res, state2, *acm_);
314 c_env_->checkRobotCollision(req, res, state1, state2, *acm_);
320 int main(
int argc,
char** argv)
322 testing::InitGoogleTest(&argc, argv);
323 return RUN_ALL_TESTS();