1#ifndef TESSERACT_COLLISION_COLLISION_BOX_BOX_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_BOX_BOX_UNIT_HPP
20 Eigen::Isometry3d box_pose;
21 box_pose.setIdentity();
25 obj1_shapes.push_back(
box);
26 obj1_poses.push_back(box_pose);
34 CollisionShapePtr thin_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
35 Eigen::Isometry3d thin_box_pose;
36 thin_box_pose.setIdentity();
40 obj2_shapes.push_back(thin_box);
41 obj2_poses.push_back(thin_box_pose);
54 auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
55 auto mesh_faces = std::make_shared<Eigen::VectorXi>();
58 std::string(TESSERACT_SUPPORT_DIR) +
"/meshes/box2_2m.ply", *mesh_vertices, *mesh_faces,
true),
61 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
66 second_box = std::make_shared<tesseract_geometry::Box>(2, 2, 2);
69 Eigen::Isometry3d second_box_pose;
70 second_box_pose.setIdentity();
74 obj3_shapes.push_back(second_box);
75 obj3_poses.push_back(second_box_pose);
82 CollisionShapePtr remove_box = std::make_shared<tesseract_geometry::Box>(0.1, 1, 1);
83 Eigen::Isometry3d remove_box_pose;
84 thin_box_pose.setIdentity();
88 obj4_shapes.push_back(remove_box);
89 obj4_poses.push_back(remove_box_pose);
120 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
130 std::vector<std::string>
active_links{
"box_link",
"second_box_link" };
142 location[
"box_link"] = Eigen::Isometry3d::Identity();
143 location[
"box_link"].translation()(0) = 0.2;
144 location[
"box_link"].translation()(1) = 0.1;
145 location[
"second_box_link"] = Eigen::Isometry3d::Identity();
161 std::vector<int> idx = { 0, 1, 1 };
185 location[
"box_link"].translation() = Eigen::Vector3d(1.60, 0, 0);
190 std::vector<std::string> names = {
"box_link" };
203 data.setPairCollisionMargin(
"not_box_link",
"also_not_box_link", 1.7);
208 location[
"box_link"].translation() = Eigen::Vector3d(1.60, 0, 0);
213 std::vector<std::string> names = {
"box_link" };
229 data.setPairCollisionMargin(
"box_link",
"second_box_link", 0.25);
Stores information about how the margins allowed between collision objects.
Definition: collision_margin_data.h:74
double getMaxCollisionMargin() const
Get the largest collision margin.
Definition: collision_margin_data.h:165
double getPairCollisionMargin(const std::string &obj1, const std::string &obj2) const
Get the pairs collision margin data.
Definition: collision_margin_data.h:140
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 link_names[0]
Definition: collision_core_unit.cpp:146
EXPECT_EQ(results.distance, std::numeric_limits< double >::max())
results normal
Definition: collision_core_unit.cpp:154
EXPECT_FALSE(tesseract_collision::isContactAllowed("base_link", "link_2", acm, false))
results nearest_points[0]
Definition: collision_core_unit.cpp:140
results single_contact_point
Definition: collision_core_unit.cpp:161
EXPECT_TRUE(tesseract_common::isIdentical< tesseract_collision::ObjectPairKey >(pairs, check_pairs, false))
CollisionMarginData data(default_margin)
Definition: collision_margin_data_unit.cpp:34
This is a collection of common methods.
This is a collection of common methods.
EXPECT_GT(m.m.condition, 1e+20)
void runTestTyped(DiscreteContactManager &checker, ContactTestType test_type)
Definition: collision_box_box_unit.hpp:125
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_common::CollisionMarginData CollisionMarginData
Definition: types.h:50
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
int loadSimplePlyFile(const std::string &path, tesseract_common::VectorVector3d &vertices, Eigen::VectorXi &faces, bool triangles_only=false)
Loads a simple ply file given a path.
Definition: common.cpp:285
ContactTestType
Definition: types.h:70
tesseract_geometry::ConvexMesh::Ptr makeConvexMesh(const tesseract_geometry::Mesh &mesh)
Definition: convex_hull_utils.cpp:114
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
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
auto box
Definition: tesseract_geometry_unit.cpp:18
auto mesh
Definition: tesseract_geometry_unit.cpp:25