1#ifndef TESSERACT_COLLISION_COLLISION_BOX_BOX_CAST_UNIT_H
2#define TESSERACT_COLLISION_COLLISION_BOX_BOX_CAST_UNIT_H
16 CollisionShapePtr static_box = std::make_shared<tesseract_geometry::Box>(1, 1, 1);
17 Eigen::Isometry3d static_box_pose;
18 static_box_pose.setIdentity();
22 obj1_shapes.push_back(static_box);
23 obj1_poses.push_back(static_box_pose);
31 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
32 Eigen::Isometry3d thin_box_pose;
33 thin_box_pose.setIdentity();
37 obj2_shapes.push_back(thin_box);
38 obj2_poses.push_back(thin_box_pose);
46 CollisionShapePtr moving_box = std::make_shared<tesseract_geometry::Box>(0.25, 0.25, 0.25);
47 Eigen::Isometry3d moving_box_pose;
48 moving_box_pose.setIdentity();
49 moving_box_pose.translation() = Eigen::Vector3d(0.5, -0.5, 0);
53 obj3_shapes.push_back(moving_box);
54 obj3_poses.push_back(moving_box_pose);
61 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
62 Eigen::Isometry3d remove_box_pose;
63 thin_box_pose.setIdentity();
67 obj4_shapes.push_back(remove_box);
68 obj4_poses.push_back(remove_box_pose);
94 for (std::size_t i = 0; i < co.size(); ++i)
101 EXPECT_TRUE(cgt[0].isApprox(Eigen::Isometry3d::Identity(), 1e-5));
105 EXPECT_TRUE(cgt[0].isApprox(moving_box_pose, 1e-5));
127 std::vector<std::string>
active_links{
"moving_box_link" };
138 std::vector<std::string> names = {
"static_box_link" };
143 Eigen::Isometry3d start_pos, end_pos;
144 start_pos.setIdentity();
145 start_pos.translation()(0) = -1.9;
146 start_pos.translation()(1) = 0.0;
147 end_pos.setIdentity();
148 end_pos.translation()(0) = 1.9;
149 end_pos.translation()(1) = 3.8;
150 start_poses.push_back(start_pos);
151 end_poses.push_back(end_pos);
157 for (
const auto& t : test_types)
double getMaxCollisionMargin() const
Get the largest collision margin.
Definition: collision_margin_data.h:165
EXPECT_NEAR(config.contact_manager_config.margin_data.getDefaultCollisionMargin(), 5, 1e-6)
tesseract_collision::ContactResultVector result_vector
Definition: collision_core_unit.cpp:410
results distance
Definition: collision_core_unit.cpp:139
results cc_type[0]
Definition: collision_core_unit.cpp:157
results cc_time[0]
Definition: collision_core_unit.cpp:155
EXPECT_FALSE(tesseract_collision::isContactAllowed("base_link", "link_2", acm, false))
results nearest_points[0]
Definition: collision_core_unit.cpp:140
EXPECT_TRUE(tesseract_common::isIdentical< tesseract_collision::ObjectPairKey >(pairs, check_pairs, false))
void addCollisionObjects(ContinuousContactManager &checker)
Definition: collision_box_box_cast_unit.hpp:11
Definition: large_dataset_benchmarks.hpp:17
void runTest(ContinuousContactManager &checker)
Definition: collision_box_box_cast_unit.hpp:111
tesseract_geometry::Geometry::Ptr CollisionShapePtr
Definition: types.h:49
std::vector< tesseract_geometry::Geometry::ConstPtr > CollisionShapesConst
Definition: types.h:47
tesseract_common::AlignedVector< ContactResult > ContactResultVector
Definition: types.h:134
template bool isIdentical< std::string >(const std::vector< std::string > &, const std::vector< std::string > &, bool, const std::function< bool(const std::string &, const std::string &)> &, const std::function< bool(const std::string &, const std::string &)> &)
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
Definition: types.h:62
std::vector< std::string > active_links
Definition: tesseract_environment_collision.cpp:112