Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
collision_octomap_mesh_unit.hpp
Go to the documentation of this file.
1#ifndef TESSERACT_COLLISION_COLLISION_OCTOMAP_MESH_UNIT_HPP
2#define TESSERACT_COLLISION_COLLISION_OCTOMAP_MESH_UNIT_HPP
3
6#include <octomap/octomap.h>
7#include <console_bridge/console.h>
10
14
16{
17namespace detail
18{
19inline void addCollisionObjects(DiscreteContactManager& checker)
20{
22 // Add Octomap
24 std::string path = std::string(TESSERACT_SUPPORT_DIR) + "/meshes/box_2m.bt";
25 auto ot = std::make_shared<octomap::OcTree>(path);
26 CollisionShapePtr dense_octomap = std::make_shared<tesseract_geometry::Octree>(ot, tesseract_geometry::Octree::BOX);
27 Eigen::Isometry3d octomap_pose;
28 octomap_pose.setIdentity();
29
30 CollisionShapesConst obj1_shapes;
32 obj1_shapes.push_back(dense_octomap);
33 obj1_poses.push_back(octomap_pose);
34
35 checker.addCollisionObject("octomap_link", 0, obj1_shapes, obj1_poses);
36
38 // Add plane mesh to checker.
40 CollisionShapePtr sphere = tesseract_geometry::createMeshFromPath<tesseract_geometry::Mesh>(
41 std::string(TESSERACT_SUPPORT_DIR) + "/meshes/plane_4m.stl", Eigen::Vector3d(1, 1, 1), true)[0];
42
43 Eigen::Isometry3d sphere_pose;
44 sphere_pose.setIdentity();
45
46 CollisionShapesConst obj2_shapes;
48 obj2_shapes.push_back(sphere);
49 obj2_poses.push_back(sphere_pose);
50
51 checker.addCollisionObject("plane_link", 0, obj2_shapes, obj2_poses);
52
53 EXPECT_TRUE(checker.getCollisionObjects().size() == 2);
54 for (const auto& co : checker.getCollisionObjects())
55 {
56 EXPECT_TRUE(checker.getCollisionObjectGeometries(co).size() == 1);
57 EXPECT_TRUE(checker.getCollisionObjectGeometriesTransforms(co).size() == 1);
58 for (const auto& cgt : checker.getCollisionObjectGeometriesTransforms(co))
59 {
60 EXPECT_TRUE(cgt.isApprox(Eigen::Isometry3d::Identity(), 1e-5));
61 }
62 }
63}
64} // namespace detail
65
66inline void runTest(DiscreteContactManager& checker, const std::string& file_path)
67{
68 // Add collision object
70
71 // Call it again to test adding same object
73
75 // Test when object is in collision
77 std::vector<std::string> active_links{ "octomap_link", "plane_link" };
79 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
81
82 EXPECT_TRUE(checker.getIsContactAllowedFn() == nullptr);
83
86
87 checker.setPairCollisionMarginData("octomap_link", "plane_link", 0.1);
88
89 // Set the collision object transforms
91 location["octomap_link"] = Eigen::Isometry3d::Identity();
92 location["plane_link"] = Eigen::Isometry3d::Identity();
93 location["plane_link"].translation() = Eigen::Vector3d(0, 0, 0);
94 checker.setCollisionObjectsTransform(location);
95
96 // Perform collision check
97 ContactResultMap result;
99
102
104 const auto& mesh = std::static_pointer_cast<const tesseract_geometry::Mesh>(geom.at(0));
105 const auto& mesh_vertices = mesh->getVertices();
106 const auto& mesh_triangles = mesh->getFaces();
107
108 // default color is green
109 std::vector<Eigen::Vector3i> mesh_vertices_color(mesh_vertices->size(), Eigen::Vector3i(0, 128, 0));
110
111 for (auto& r : result_vector)
112 {
113 int idx = 0;
114 if (r.link_names[0] != "plane_link")
115 idx = 1;
116
117 mesh_vertices_color[static_cast<std::size_t>(
118 (*mesh_triangles)[4 * r.subshape_id[static_cast<std::size_t>(idx)] + 1])] = Eigen::Vector3i(255, 0, 0);
119 mesh_vertices_color[static_cast<std::size_t>(
120 (*mesh_triangles)[4 * r.subshape_id[static_cast<std::size_t>(idx)] + 2])] = Eigen::Vector3i(255, 0, 0);
121 mesh_vertices_color[static_cast<std::size_t>(
122 (*mesh_triangles)[4 * r.subshape_id[static_cast<std::size_t>(idx)] + 3])] = Eigen::Vector3i(255, 0, 0);
123 }
124
125 writeSimplePlyFile(file_path, *mesh_vertices, mesh_vertices_color, *mesh_triangles, mesh->getFaceCount());
126
127 EXPECT_TRUE(!result_vector.empty());
128 EXPECT_TRUE(result_vector.size() == 2712);
129}
130} // namespace tesseract_collision::test_suite
131
132#endif // TESSERACT_COLLISION_COLLISION_OCTOMAP_MESH_UNIT_HPP
This structure hold contact results for link pairs.
Definition: types.h:154
void flattenMoveResults(ContactResultVector &v)
Definition: types.cpp:215
Definition: discrete_contact_manager.h:41
virtual void setActiveCollisionObjects(const std::vector< std::string > &names)=0
Set which collision objects can move.
virtual void contactTest(ContactResultMap &collisions, const ContactRequest &request)=0
Perform a contact test for all objects based.
virtual void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose)=0
Set a single collision object's transforms.
virtual void setPairCollisionMarginData(const std::string &name1, const std::string &name2, double collision_margin)=0
Set the margin for a given contact pair.
virtual const std::vector< std::string > & getActiveCollisionObjects() const =0
Get which collision objects can move.
virtual const CollisionMarginData & getCollisionMarginData() const =0
Get the contact distance threshold.
virtual void setCollisionMarginData(CollisionMarginData collision_margin_data, CollisionMarginOverrideType override_type=CollisionMarginOverrideType::REPLACE)=0
Set the contact distance thresholds for which collision should be considered on a per pair basis.
virtual IsContactAllowedFn getIsContactAllowedFn() const =0
Get the active function for determining if two links are allowed to be in collision.
virtual const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const =0
Get a collision objects collision geometries.
double getMaxCollisionMargin() const
Get the largest collision margin.
Definition: collision_margin_data.h:165
@ BOX
Definition: octree.h:50
EXPECT_NEAR(config.contact_manager_config.margin_data.getDefaultCollisionMargin(), 5, 1e-6)
tesseract_collision::ContactResultVector result_vector
Definition: collision_core_unit.cpp:410
EXPECT_TRUE(tesseract_common::isIdentical< tesseract_collision::ObjectPairKey >(pairs, check_pairs, false))
This is a collection of common methods.
This is the discrete contact manager base class.
Tesseract Geometries.
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
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
bool writeSimplePlyFile(const std::string &path, const tesseract_common::VectorVector3d &vertices, const std::vector< Eigen::Vector3i > &vectices_color, const Eigen::VectorXi &faces, int num_faces)
Write a simple ply file given vertices and faces.
Definition: common.cpp:170
tesseract_common::AlignedVector< ContactResult > ContactResultVector
Definition: types.h:134
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
tesseract_common::fs::path file_path(__FILE__)
The ContactRequest struct.
Definition: types.h:294
std::vector< std::string > active_links
Definition: tesseract_environment_collision.cpp:112
auto geom
Definition: tesseract_geometry_unit.cpp:51
auto sphere
Definition: tesseract_geometry_unit.cpp:23
auto mesh
Definition: tesseract_geometry_unit.cpp:25
tesseract_common::fs::path path
Definition: tesseract_srdf_unit.cpp:1992