41 #include <moveit_resources/config.h> 43 #include <urdf_parser/urdf_parser.h> 46 #include <gtest/gtest.h> 52 #include <boost/filesystem.hpp> 62 boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
63 std::string urdf_file = (res_path /
"pr2_description/urdf/robot.xml").
string();
64 std::string srdf_file = (res_path /
"pr2_description/srdf/robot.xml").
string();
65 kinect_dae_resource_ =
"package://moveit_resources/pr2_description/urdf/meshes/sensors/kinect_v0/kinect.dae";
69 std::fstream xml_file(urdf_file.c_str(), std::fstream::in);
71 if (xml_file.is_open())
73 while (xml_file.good())
76 std::getline(xml_file, line);
77 xml_string += (line +
"\n");
85 EXPECT_EQ(
"FAILED TO OPEN FILE", urdf_file);
111 collision_detection::CollisionRobotPtr
crobot_;
112 collision_detection::CollisionWorldPtr
cworld_;
114 collision_detection::AllowedCollisionMatrixPtr
acm_;
133 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
150 Eigen::Affine3d offset = Eigen::Affine3d::Identity();
151 offset.translation().x() = .01;
159 acm_->setEntry(
"base_link",
"base_bellow_link",
false);
160 crobot_->checkSelfCollision(req, res1, kstate, *
acm_);
163 acm_->setEntry(
"base_link",
"base_bellow_link",
true);
164 crobot_->checkSelfCollision(req, res2, kstate, *
acm_);
174 acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
175 crobot_->checkSelfCollision(req, res3, kstate, *
acm_);
189 Eigen::Affine3d offset = Eigen::Affine3d::Identity();
190 offset.translation().x() = .01;
203 acm_->setEntry(
"base_link",
"base_bellow_link",
false);
204 acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
207 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
216 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
227 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
243 Eigen::Affine3d pos1 = Eigen::Affine3d::Identity();
244 Eigen::Affine3d pos2 = Eigen::Affine3d::Identity();
246 pos1.translation().x() = 5.0;
247 pos2.translation().x() = 5.01;
255 acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
258 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
261 ASSERT_EQ(res.
contacts.begin()->second.size(), 1);
263 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
269 pos1 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
270 pos2 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond(0.965, 0.0, 0.258, 0.0));
278 crobot_->checkSelfCollision(req, res2, kstate, *
acm_);
281 ASSERT_EQ(res2.
contacts.begin()->second.size(), 1);
283 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res2.
contacts.begin();
289 pos1 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
290 pos2 = Eigen::Affine3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond(
M_PI / 4.0, 0.0,
M_PI / 4.0, 0.0));
298 crobot_->checkSelfCollision(req, res2, kstate, *
acm_);
313 Eigen::Affine3d pos1 = Eigen::Affine3d::Identity();
314 pos1.translation().x() = 5.0;
319 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
330 cworld_->getWorld()->removeObject(
"box");
333 std::vector<shapes::ShapeConstPtr>
shapes;
336 poses.push_back(Eigen::Affine3d::Identity());
337 std::vector<std::string> touch_links;
338 kstate.
attachBody(
"box", shapes, poses, touch_links,
"r_gripper_palm_link");
341 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
347 touch_links.push_back(
"r_gripper_palm_link");
348 touch_links.push_back(
"r_gripper_motor_accelerometer_link");
350 kstate.
attachBody(
"box", shapes, poses, touch_links,
"r_gripper_palm_link");
354 crobot_->checkSelfCollision(req, res, kstate, *
acm_);
357 pos1.translation().x() = 5.01;
364 acm_->setEntry(
"coll",
"r_gripper_palm_link",
true);
380 *(dynamic_cast<collision_detection::CollisionRobotFCL*>(
crobot_.get())));
383 new_crobot.checkSelfCollision(req, res, kstate);
386 new_crobot.checkSelfCollision(req, res, kstate);
389 EXPECT_LT(fabs(first_check - second_check), .05);
391 std::vector<shapes::ShapeConstPtr>
shapes;
397 poses.push_back(Eigen::Affine3d::Identity());
399 std::vector<std::string> touch_links;
400 kstate.
attachBody(
"kinect", shapes, poses, touch_links,
"r_gripper_palm_link");
403 new_crobot.checkSelfCollision(req, res, kstate);
406 new_crobot.checkSelfCollision(req, res, kstate);
410 EXPECT_LT(second_check, .1);
413 *(dynamic_cast<collision_detection::CollisionRobotFCL*>(
crobot_.get())));
415 new_crobot.checkSelfCollision(req, res, kstate);
418 new_crobot.checkSelfCollision(req, res, kstate);
421 EXPECT_LT(fabs(first_check - second_check), .05);
430 Eigen::Affine3d pos1 = Eigen::Affine3d::Identity();
431 Eigen::Affine3d pos2 = Eigen::Affine3d::Identity();
432 pos2.translation().x() = 10.0;
434 cworld_->getWorld()->addToObject(
"kinect", shape, pos1);
447 EXPECT_LT(second_check, .05);
450 cworld_->getWorld()->removeObject(
"kinect");
459 std::vector<std::string> touch_links;
460 kstate1.
attachBody(
"kinect", object->shapes_, object->shape_poses_, touch_links,
"r_gripper_palm_link");
463 other_poses.push_back(pos2);
466 kstate2.
attachBody(
"kinect", object->shapes_, object->shape_poses_, touch_links,
"r_gripper_palm_link");
470 crobot_->checkSelfCollision(req, res, kstate1);
475 crobot_->checkSelfCollision(req, res, kstate1, *
acm_);
480 crobot_->checkSelfCollision(req, res, kstate2, *
acm_);
483 EXPECT_LT(first_check, .05);
484 EXPECT_LT(fabs(first_check - second_check), .1);
490 std::vector<shapes::ShapeConstPtr>
shapes;
491 for (
unsigned int i = 0; i < 10000; i++)
493 poses.push_back(Eigen::Affine3d::Identity());
497 cworld_->getWorld()->addToObject(
"map", shapes, poses);
502 ROS_INFO_NAMED(
"collision_detection.fcl",
"Adding boxes took %g", t);
511 Eigen::Affine3d kinect_pose;
512 kinect_pose.setIdentity();
516 cworld_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
519 for (
unsigned int i = 0; i < 5; i++)
521 np = Eigen::Translation3d(i * .001, i * .001, i * .001) * Eigen::Quaterniond::Identity();
522 cworld_->getWorld()->moveShapeInObject(
"kinect", kinect_shape, np);
541 std::vector<shapes::ShapeConstPtr>
shapes;
542 for (
unsigned int i = 0; i < 5; i++)
544 cworld_->getWorld()->removeObject(
"shape");
548 poses.push_back(Eigen::Affine3d::Identity());
549 cworld_->getWorld()->addToObject(
"shape", shapes, poses);
556 Eigen::Affine3d kinect_pose = Eigen::Affine3d::Identity();
559 cworld_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
564 for (
unsigned int i = 0; i < 5; i++)
566 cworld_->getWorld()->removeObject(
"shape");
570 poses.push_back(Eigen::Affine3d::Identity());
571 cworld_->getWorld()->addToObject(
"shape", shapes, poses);
579 int main(
int argc,
char** argv)
581 testing::InitGoogleTest(&argc, argv);
582 return RUN_ALL_TESTS();
collision_detection::CollisionRobotFCL DefaultCRobotType
Representation of a collision checking request.
int main(int argc, char **argv)
#define ROS_INFO_NAMED(name,...)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
TEST_F(FclCollisionDetectionTester, InitOK)
void attachBody(AttachedBody *attached_body)
Add an attached body to this state. Ownership of the memory for the attached body is assumed by the s...
ContactMap contacts
A map returning the pairs of ids of the bodies in contact, plus information about the contacts themse...
Representation of a collision checking result.
urdf::ModelInterfaceSharedPtr urdf_model_
#define EXPECT_NEAR(a, b, prec)
std::shared_ptr< Shape > ShapePtr
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
collision_detection::CollisionRobotPtr crobot_
robot_model::RobotModelPtr kmodel_
std::size_t contact_count
Number of contacts returned.
bool collision
True if collision was found, false otherwise.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
World::ObjectConstPtr ObjectConstPtr
collision_detection::AllowedCollisionMatrixPtr acm_
std::size_t max_contacts
Overall maximum number of contacts to compute.
bool verbose
Flag indicating whether information about detected collisions should be reported. ...
void update(bool force=false)
Update all transforms.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
collision_detection::CollisionWorldPtr cworld_
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Affine3d &transform, bool backward=false)
Update the state after setting a particular link to the input global transform pose.
bool contacts
If true, compute contacts.
def xml_string(rootXml, addHeader=True)
collision_detection::CollisionWorldFCL DefaultCWorldType
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
Mesh * createMeshFromResource(const std::string &resource)
srdf::ModelSharedPtr srdf_model_
std::string kinect_dae_resource_
Representation of a robot's state. This includes position, velocity, acceleration and effort...
#define EXPECT_TRUE(args)
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)...
std::shared_ptr< const Shape > ShapeConstPtr