37#include <gtest/gtest.h>
38#include <rclcpp/rclcpp.hpp>
52#include <urdf_parser/urdf_parser.h>
53#include <geometric_shapes/shape_operations.h>
66 double joint2 = -0.785;
67 double joint4 = -2.356;
68 double joint6 = 1.571;
69 double joint7 = 0.785;
85 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(*
robot_model_->getSRDF());
103 collision_detection::CollisionEnvPtr
cenv_;
105 collision_detection::AllowedCollisionMatrixPtr
acm_;
115 shapes::ShapePtr static_box = std::make_shared<shapes::Box>(1, 1, 1);
116 Eigen::Isometry3d static_box_pose;
117 static_box_pose.setIdentity();
119 std::vector<shapes::ShapeConstPtr> obj1_shapes;
121 std::vector<cb::CollisionObjectType> obj1_types;
122 obj1_shapes.push_back(static_box);
123 obj1_poses.push_back(static_box_pose);
124 obj1_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
126 cb::CollisionObjectWrapperPtr cow_1 = std::make_shared<cb::CollisionObjectWrapper>(
127 "static_box_link", collision_detection::BodyType::WORLD_OBJECT, obj1_shapes, obj1_poses, obj1_types);
133 shapes::ShapePtr moving_box = std::make_shared<shapes::Box>(0.2, 0.2, 0.2);
134 Eigen::Isometry3d moving_box_pose;
136 moving_box_pose.setIdentity();
137 moving_box_pose.translation() = Eigen::Vector3d(0.5, -0.5, 0);
139 std::vector<shapes::ShapeConstPtr> obj2_shapes;
141 std::vector<cb::CollisionObjectType> obj2_types;
142 obj2_shapes.push_back(moving_box);
143 obj2_poses.push_back(moving_box_pose);
144 obj2_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
146 cb::CollisionObjectWrapperPtr cow_2 = std::make_shared<cb::CollisionObjectWrapper>(
147 "moving_box_link", collision_detection::BodyType::WORLD_OBJECT, obj2_shapes, obj2_poses, obj2_types);
156 shapes::ShapePtr static_box = std::make_shared<shapes::Box>(0.3, 0.3, 0.3);
157 Eigen::Isometry3d static_box_pose;
158 static_box_pose.setIdentity();
160 std::vector<shapes::ShapeConstPtr> obj1_shapes;
162 std::vector<cb::CollisionObjectType> obj1_types;
163 obj1_shapes.push_back(static_box);
164 obj1_poses.push_back(static_box_pose);
165 obj1_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
167 cb::CollisionObjectWrapperPtr cow_1 = std::make_shared<cb::CollisionObjectWrapper>(
168 "static_box_link", collision_detection::BodyType::WORLD_OBJECT, obj1_shapes, obj1_poses, obj1_types);
174 std::vector<shapes::ShapeConstPtr> obj2_shapes;
176 std::vector<cb::CollisionObjectType> obj2_types;
178 obj1_poses.push_back(static_box_pose);
179 obj1_types.push_back(cb::CollisionObjectType::USE_SHAPE_TYPE);
181 Eigen::Isometry3d s_pose;
182 s_pose.setIdentity();
184 std::string kinect =
"package://moveit_resources_panda_description/meshes/collision/hand.stl";
185 auto s = std::shared_ptr<shapes::Shape>{ shapes::createMeshFromResource(kinect) };
186 obj2_shapes.push_back(s);
187 obj2_types.push_back(cb::CollisionObjectType::CONVEX_HULL);
188 obj2_poses.push_back(s_pose);
190 cb::CollisionObjectWrapperPtr cow_2 = std::make_shared<cb::CollisionObjectWrapper>(
191 "moving_box_link", collision_detection::BodyType::WORLD_OBJECT, obj2_shapes, obj2_poses, obj2_types);
196 std::vector<collision_detection::Contact>& result_vector, Eigen::Isometry3d& start_pos,
197 Eigen::Isometry3d& end_pos)
213 checker.
contactTest(result, request,
nullptr,
false);
215 for (
const auto& contacts_all : result.
contacts)
217 for (
const auto& contact : contacts_all.second)
219 result_vector.push_back(contact);
235 double joint2 = 0.15;
236 double joint4 = -3.0;
237 double joint5 = -0.8;
238 double joint7 = -0.785;
245 cenv_->checkSelfCollision(req, res, state1, *acm_);
250 double joint_5_other = 0.8;
257 cenv_->checkSelfCollision(req, res, state2, *acm_);
261 RCLCPP_INFO(
getLogger(),
"Continuous to continuous collisions are not supported yet, therefore fail here.");
281 double joint_2{ 0.05 };
282 double joint_4{ -1.6 };
287 cenv_->checkRobotCollision(req, res, state1, state2, *acm_);
292 shapes::Shape* shape =
new shapes::Box(0.1, 0.1, 0.1);
293 shapes::ShapeConstPtr shape_ptr(shape);
295 Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
296 pos.translation().x() = 0.43;
297 pos.translation().y() = 0;
298 pos.translation().z() = 0.55;
299 cenv_->getWorld()->addToObject(
"box", shape_ptr, pos);
301 cenv_->checkRobotCollision(req, res, state1, *acm_);
305 cenv_->checkRobotCollision(req, res, state2, *acm_);
309 cenv_->checkRobotCollision(req, res, state1, state2, *acm_);
313 for (
auto& contact_pair : res.
contacts)
318 collision_detection::BodyType::WORLD_OBJECT :
319 collision_detection::BodyType::ROBOT_LINK;
321 collision_detection::BodyType::WORLD_OBJECT :
322 collision_detection::BodyType::ROBOT_LINK;
323 ASSERT_EQ(contact.body_type_1, contact_type1);
324 ASSERT_EQ(contact.body_type_2, contact_type2);
330TEST(ContinuousCollisionUnit, BulletCastBVHCollisionBoxBoxUnit)
333 std::vector<collision_detection::Contact> result_vector;
335 Eigen::Isometry3d start_pos, end_pos;
336 start_pos.setIdentity();
337 start_pos.translation().x() = -2;
338 end_pos.setIdentity();
339 end_pos.translation().x() = 2;
343 runTest(checker, result, result_vector, start_pos, end_pos);
346 EXPECT_NEAR(result_vector[0].depth, -0.6, 0.001);
347 EXPECT_NEAR(result_vector[0].percent_interpolation, 0.6, 0.001);
350TEST(ContinuousCollisionUnit, BulletCastMeshVsBox)
355 Eigen::Isometry3d start_pos, end_pos;
356 start_pos.setIdentity();
357 start_pos.translation().x() = -1.9;
358 end_pos.setIdentity();
359 end_pos.translation().x() = 1.9;
362 std::vector<collision_detection::Contact> result_vector;
364 runTest(checker, result, result_vector, start_pos, end_pos);
371 testing::InitGoogleTest(&argc, argv);
372 return RUN_ALL_TESTS();
moveit::core::RobotModelPtr robot_model_
collision_detection::CollisionEnvPtr cenv_
moveit::core::RobotStatePtr robot_state_
collision_detection::AllowedCollisionMatrixPtr acm_
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)
Set a single static collision object's transform.
void setContactDistanceThreshold(double contact_distance)
Set the contact distance threshold for which collision should be considered through expanding the AAB...
void setActiveCollisionObjects(const std::vector< std::string > &names)
Set which collision objects are active.
A bounding volume hierarchy (BVH) implementation of a tesseract contact manager.
void setCastCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)
Set a single cast (moving) collision object's transforms.
void contactTest(collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self) override
Perform a contact test for all objects.
void addCollisionObject(const CollisionObjectWrapperPtr &cow) override
Add a tesseract collision object to the manager.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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)
Type
The types of bodies that are considered for collision.
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
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.
Representation of a collision checking request.
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 addCollisionObjectsMesh(cb::BulletCastBVHManager &checker)
TEST(ContinuousCollisionUnit, BulletCastBVHCollisionBoxBoxUnit)
void runTest(cb::BulletCastBVHManager &checker, collision_detection::CollisionResult &result, std::vector< collision_detection::Contact > &result_vector, Eigen::Isometry3d &start_pos, Eigen::Isometry3d &end_pos)
void setToHome(moveit::core::RobotState &panda_state)
Brings the panda robot in user defined home position.
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.
void addCollisionObjects(cb::BulletCastBVHManager &checker)