Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
fcl_discrete_managers.h
Go to the documentation of this file.
1
42#ifndef TESSERACT_COLLISION_FCL_DISCRETE_MANAGERS_H
43#define TESSERACT_COLLISION_FCL_DISCRETE_MANAGERS_H
44
47
49{
52{
53public:
54 using Ptr = std::shared_ptr<FCLDiscreteBVHManager>;
55 using ConstPtr = std::shared_ptr<const FCLDiscreteBVHManager>;
56 using UPtr = std::unique_ptr<FCLDiscreteBVHManager>;
57 using ConstUPtr = std::unique_ptr<const FCLDiscreteBVHManager>;
58
59 FCLDiscreteBVHManager(std::string name = "FCLDiscreteBVHManager");
60 ~FCLDiscreteBVHManager() override = default;
65
66 std::string getName() const override final;
67
68 DiscreteContactManager::UPtr clone() const override final;
69
70 bool addCollisionObject(const std::string& name,
71 const int& mask_id,
72 const CollisionShapesConst& shapes,
73 const tesseract_common::VectorIsometry3d& shape_poses,
74 bool enabled = true) override final;
75
76 const CollisionShapesConst& getCollisionObjectGeometries(const std::string& name) const override final;
77
78 const tesseract_common::VectorIsometry3d&
79 getCollisionObjectGeometriesTransforms(const std::string& name) const override final;
80
81 bool hasCollisionObject(const std::string& name) const override final;
82
83 bool removeCollisionObject(const std::string& name) override final;
84
85 bool enableCollisionObject(const std::string& name) override final;
86
87 bool disableCollisionObject(const std::string& name) override final;
88
89 bool isCollisionObjectEnabled(const std::string& name) const override final;
90
91 void setCollisionObjectsTransform(const std::string& name, const Eigen::Isometry3d& pose) override final;
92
93 void setCollisionObjectsTransform(const std::vector<std::string>& names,
94 const tesseract_common::VectorIsometry3d& poses) override final;
95
96 void setCollisionObjectsTransform(const tesseract_common::TransformMap& transforms) override final;
97
98 const std::vector<std::string>& getCollisionObjects() const override final;
99
100 void setActiveCollisionObjects(const std::vector<std::string>& names) override final;
101
102 const std::vector<std::string>& getActiveCollisionObjects() const override final;
103
105 CollisionMarginData collision_margin_data,
106 CollisionMarginOverrideType override_type = CollisionMarginOverrideType::REPLACE) override final;
107
108 void setDefaultCollisionMarginData(double default_collision_margin) override final;
109
110 void setPairCollisionMarginData(const std::string& name1,
111 const std::string& name2,
112 double collision_margin) override final;
113
114 const CollisionMarginData& getCollisionMarginData() const override final;
115
116 void setIsContactAllowedFn(IsContactAllowedFn fn) override final;
117
118 IsContactAllowedFn getIsContactAllowedFn() const override final;
119
120 void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;
121
126 void addCollisionObject(const COW::Ptr& cow);
127
128private:
129 std::string name_;
130
132 std::unique_ptr<fcl::BroadPhaseCollisionManagerd> static_manager_;
133
135 std::unique_ptr<fcl::BroadPhaseCollisionManagerd> dynamic_manager_;
136
138 std::vector<std::string> active_;
139 std::vector<std::string> collision_objects_;
142 std::size_t fcl_co_count_{ 0 };
145 std::vector<CollisionObjectRawPtr> static_update_;
146
148 std::vector<CollisionObjectRawPtr> dynamic_update_;
149
152};
153
154} // namespace tesseract_collision::tesseract_collision_fcl
155#endif // TESSERACT_COLLISION_FCL_DISCRETE_MANAGERS_H
#define vector(a, b, c)
Definition: FloatMath.inl:3227
This structure hold contact results for link pairs.
Definition: types.h:154
Definition: discrete_contact_manager.h:41
This is a Tesseract link collision object wrapper which add items specific to tesseract....
Definition: fcl_utils.h:79
A FCL implementation of the discrete contact manager.
Definition: fcl_discrete_managers.h:52
void contactTest(ContactResultMap &collisions, const ContactRequest &request) override final
Perform a contact test for all objects based.
Definition: fcl_discrete_managers.cpp:314
const tesseract_common::VectorIsometry3d & getCollisionObjectGeometriesTransforms(const std::string &name) const override final
Get a collision objects collision geometries transforms.
Definition: fcl_discrete_managers.cpp:99
Link2COW link2cow_
A map of all (static and active) collision objects being managed.
Definition: fcl_discrete_managers.h:137
void setCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose) override final
Set a single collision object's transforms.
Definition: fcl_discrete_managers.cpp:176
IsContactAllowedFn getIsContactAllowedFn() const override final
Get the active function for determining if two links are allowed to be in collision.
Definition: fcl_discrete_managers.cpp:312
void setDefaultCollisionMarginData(double default_collision_margin) override final
Set the default collision margin.
Definition: fcl_discrete_managers.cpp:296
bool removeCollisionObject(const std::string &name) override final
Remove an object from the checker.
Definition: fcl_discrete_managers.cpp:111
std::vector< std::string > active_
A list of the active collision objects.
Definition: fcl_discrete_managers.h:138
void setActiveCollisionObjects(const std::vector< std::string > &names) override final
Set which collision objects can move.
Definition: fcl_discrete_managers.cpp:276
std::size_t fcl_co_count_
The number fcl collision objects.
Definition: fcl_discrete_managers.h:142
std::shared_ptr< const FCLDiscreteBVHManager > ConstPtr
Definition: fcl_discrete_managers.h:55
FCLDiscreteBVHManager & operator=(FCLDiscreteBVHManager &&)=delete
std::string name_
Definition: fcl_discrete_managers.h:129
std::unique_ptr< fcl::BroadPhaseCollisionManagerd > static_manager_
Broad-phase Collision Manager for active collision objects.
Definition: fcl_discrete_managers.h:132
void onCollisionMarginDataChanged()
This function will update internal data when margin data has changed.
Definition: fcl_discrete_managers.cpp:370
std::unique_ptr< const FCLDiscreteBVHManager > ConstUPtr
Definition: fcl_discrete_managers.h:57
std::unique_ptr< fcl::BroadPhaseCollisionManagerd > dynamic_manager_
Broad-phase Collision Manager for active collision objects.
Definition: fcl_discrete_managers.h:135
std::shared_ptr< FCLDiscreteBVHManager > Ptr
Definition: fcl_discrete_managers.h:54
const CollisionShapesConst & getCollisionObjectGeometries(const std::string &name) const override final
Get a collision objects collision geometries.
Definition: fcl_discrete_managers.cpp:91
IsContactAllowedFn fn_
The is allowed collision function.
Definition: fcl_discrete_managers.h:141
FCLDiscreteBVHManager & operator=(const FCLDiscreteBVHManager &)=delete
const CollisionMarginData & getCollisionMarginData() const override final
Get the contact distance threshold.
Definition: fcl_discrete_managers.cpp:310
const std::vector< std::string > & getActiveCollisionObjects() const override final
Get which collision objects can move.
Definition: fcl_discrete_managers.cpp:288
DiscreteContactManager::UPtr clone() const override final
Clone the manager.
Definition: fcl_discrete_managers.cpp:58
std::vector< CollisionObjectRawPtr > dynamic_update_
This is used to store dynamic collision objects to update.
Definition: fcl_discrete_managers.h:148
std::vector< std::string > collision_objects_
A list of the collision objects.
Definition: fcl_discrete_managers.h:139
std::unique_ptr< FCLDiscreteBVHManager > UPtr
Definition: fcl_discrete_managers.h:56
void setPairCollisionMarginData(const std::string &name1, const std::string &name2, double collision_margin) override final
Set the margin for a given contact pair.
Definition: fcl_discrete_managers.cpp:302
bool hasCollisionObject(const std::string &name) const override final
Find if a collision object already exists.
Definition: fcl_discrete_managers.cpp:106
bool addCollisionObject(const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true) override final
Add a object to the checker.
Definition: fcl_discrete_managers.cpp:72
void setIsContactAllowedFn(IsContactAllowedFn fn) override final
Set the active function for determining if two links are allowed to be in collision.
Definition: fcl_discrete_managers.cpp:311
bool enableCollisionObject(const std::string &name) override final
Enable an object.
Definition: fcl_discrete_managers.cpp:145
std::string getName() const override final
Get the name of the contact manager.
Definition: fcl_discrete_managers.cpp:56
std::vector< CollisionObjectRawPtr > static_update_
This is used to store static collision objects to update.
Definition: fcl_discrete_managers.h:145
bool isCollisionObjectEnabled(const std::string &name) const override final
Check if collision object is enabled.
Definition: fcl_discrete_managers.cpp:167
const std::vector< std::string > & getCollisionObjects() const override final
Get all collision objects.
Definition: fcl_discrete_managers.cpp:274
CollisionMarginData collision_margin_data_
The contact distance threshold.
Definition: fcl_discrete_managers.h:140
void setCollisionMarginData(CollisionMarginData collision_margin_data, CollisionMarginOverrideType override_type=CollisionMarginOverrideType::REPLACE) override final
Set the contact distance thresholds for which collision should be considered on a per pair basis.
Definition: fcl_discrete_managers.cpp:289
bool disableCollisionObject(const std::string &name) override final
Disable an object.
Definition: fcl_discrete_managers.cpp:156
Stores information about how the margins allowed between collision objects.
Definition: collision_margin_data.h:74
This is the discrete contact manager base class.
Tesseract ROS FCL Utility Functions.
Definition: fcl_collision_object_wrapper.h:36
std::map< std::string, COW::Ptr > Link2COW
Definition: fcl_utils.h:194
std::vector< tesseract_geometry::Geometry::ConstPtr > CollisionShapesConst
Definition: types.h:47
std::function< bool(const std::string &, const std::string &)> IsContactAllowedFn
Should return true if contact allowed, otherwise false.
Definition: types.h:59
Definition: allowed_collision_matrix.h:16
CollisionMarginOverrideType
Identifies how the provided contact margin data should be applied.
Definition: collision_margin_data.h:46
The ContactRequest struct.
Definition: types.h:294
auto pose
Definition: tesseract_environment_collision.cpp:118