fcl_utils.h
Go to the documentation of this file.
1 
42 #ifndef TESSERACT_COLLISION_FCL_UTILS_H
43 #define TESSERACT_COLLISION_FCL_UTILS_H
44 
50 #include <memory>
51 #include <console_bridge/console.h>
53 
57 
59 {
60 using CollisionGeometryPtr = std::shared_ptr<fcl::CollisionGeometryd>;
61 using CollisionObjectPtr = std::shared_ptr<FCLCollisionObjectWrapper>;
63 using CollisionObjectConstPtr = std::shared_ptr<const fcl::CollisionObjectd>;
64 
65 enum CollisionFilterGroups : std::int8_t
66 {
70  AllFilter = -1 // all bits sets: DefaultFilter | StaticFilter | KinematicFilter
71 };
72 
78 {
79 public:
80  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
81 
82  using Ptr = std::shared_ptr<CollisionObjectWrapper>;
83  using ConstPtr = std::shared_ptr<const CollisionObjectWrapper>;
84 
85  CollisionObjectWrapper() = default;
86  CollisionObjectWrapper(std::string name,
87  const int& type_id,
88  CollisionShapesConst shapes,
90 
93  bool m_enabled{ true };
94 
95  const std::string& getName() const { return name_; }
96  const int& getTypeID() const { return type_id_; }
98  bool sameObject(const CollisionObjectWrapper& other) const
99  {
100  return name_ == other.name_ && type_id_ == other.type_id_ && shapes_.size() == other.shapes_.size() &&
101  shape_poses_.size() == other.shape_poses_.size() &&
102  std::equal(shapes_.begin(), shapes_.end(), other.shapes_.begin()) &&
103  std::equal(shape_poses_.begin(),
104  shape_poses_.end(),
105  other.shape_poses_.begin(),
106  [](const Eigen::Isometry3d& t1, const Eigen::Isometry3d& t2) { return t1.isApprox(t2); });
107  }
108 
110 
112 
113  void setCollisionObjectsTransform(const Eigen::Isometry3d& pose)
114  {
115  world_pose_ = pose;
116  for (auto& co : collision_objects_)
117  {
118  co->setTransform(pose * shape_poses_[static_cast<std::size_t>(co->getShapeIndex())]);
119  co->updateAABB(); // This a tesseract function that updates abb to take into account contact distance
120  }
121  }
122 
123  void setContactDistanceThreshold(double contact_distance)
124  {
125  contact_distance_ = contact_distance;
126  for (auto& co : collision_objects_)
127  co->setContactDistanceThreshold(contact_distance_);
128  }
129 
131  const Eigen::Isometry3d& getCollisionObjectsTransform() const { return world_pose_; }
132  const std::vector<CollisionObjectPtr>& getCollisionObjects() const { return collision_objects_; }
133  std::vector<CollisionObjectPtr>& getCollisionObjects() { return collision_objects_; }
134  const std::vector<CollisionObjectRawPtr>& getCollisionObjectsRaw() const { return collision_objects_raw_; }
135  std::vector<CollisionObjectRawPtr>& getCollisionObjectsRaw() { return collision_objects_raw_; }
136  std::shared_ptr<CollisionObjectWrapper> clone() const
137  {
138  auto clone_cow = std::make_shared<CollisionObjectWrapper>();
139  clone_cow->name_ = name_;
140  clone_cow->type_id_ = type_id_;
141  clone_cow->shapes_ = shapes_;
142  clone_cow->shape_poses_ = shape_poses_;
143  clone_cow->collision_geometries_ = collision_geometries_;
144 
145  clone_cow->collision_objects_.reserve(collision_objects_.size());
146  clone_cow->collision_objects_raw_.reserve(collision_objects_.size());
147  for (const auto& co : collision_objects_)
148  {
149  assert(std::dynamic_pointer_cast<FCLCollisionObjectWrapper>(co) != nullptr);
150  auto collObj =
151  std::make_shared<FCLCollisionObjectWrapper>(*std::static_pointer_cast<FCLCollisionObjectWrapper>(co));
152  collObj->setUserData(clone_cow.get());
153  collObj->setTransform(co->getTransform());
154  collObj->updateAABB();
155  clone_cow->collision_objects_.push_back(collObj);
156  clone_cow->collision_objects_raw_.push_back(collObj.get());
157  }
158 
159  clone_cow->m_collisionFilterGroup = m_collisionFilterGroup;
160  clone_cow->m_collisionFilterMask = m_collisionFilterMask;
161  clone_cow->m_enabled = m_enabled;
162  return clone_cow;
163  }
164 
170  static int getShapeIndex(const fcl::CollisionObjectd* co);
171 
172 protected:
173  std::string name_; // name of the collision object
174  int type_id_{ -1 }; // user defined type id
175  Eigen::Isometry3d world_pose_{ Eigen::Isometry3d::Identity() };
178  std::vector<CollisionGeometryPtr> collision_geometries_;
179  std::vector<CollisionObjectPtr> collision_objects_;
184  std::vector<CollisionObjectRawPtr> collision_objects_raw_;
185 
186  double contact_distance_{ 0 };
187 };
188 
190 
192 using Link2COW = std::map<std::string, COW::Ptr>;
193 using Link2ConstCOW = std::map<std::string, COW::ConstPtr>;
194 
195 inline COW::Ptr createFCLCollisionObject(const std::string& name,
196  const int& type_id,
197  const CollisionShapesConst& shapes,
198  const tesseract_common::VectorIsometry3d& shape_poses,
199  bool enabled)
200 {
201  // dont add object that does not have geometry
202  if (shapes.empty() || shape_poses.empty() || (shapes.size() != shape_poses.size()))
203  {
204  CONSOLE_BRIDGE_logDebug("ignoring link %s", name.c_str());
205  return nullptr;
206  }
207 
208  auto new_cow = std::make_shared<COW>(name, type_id, shapes, shape_poses);
209 
210  new_cow->m_enabled = enabled;
211  CONSOLE_BRIDGE_logDebug("Created collision object for link %s", new_cow->getName().c_str());
212  return new_cow;
213 }
214 
222 inline void updateCollisionObjectFilters(const std::vector<std::string>& active,
223  const COW::Ptr& cow,
224  const std::unique_ptr<fcl::BroadPhaseCollisionManagerd>& static_manager,
225  const std::unique_ptr<fcl::BroadPhaseCollisionManagerd>& dynamic_manager)
226 {
227  // For descrete checks we can check static to kinematic and kinematic to
228  // kinematic
229  if (!isLinkActive(active, cow->getName()))
230  {
231  if (cow->m_collisionFilterGroup != CollisionFilterGroups::StaticFilter)
232  {
233  std::vector<CollisionObjectPtr>& objects = cow->getCollisionObjects();
234  // This link was dynamic but is now static
235  for (auto& co : objects)
236  dynamic_manager->unregisterObject(co.get());
237 
238  for (auto& co : objects)
239  static_manager->registerObject(co.get());
240  }
241  cow->m_collisionFilterGroup = CollisionFilterGroups::StaticFilter;
242  }
243  else
244  {
245  if (cow->m_collisionFilterGroup != CollisionFilterGroups::KinematicFilter)
246  {
247  std::vector<CollisionObjectPtr>& objects = cow->getCollisionObjects();
248  // This link was static but is now dynamic
249  for (auto& co : objects)
250  static_manager->unregisterObject(co.get());
251 
252  for (auto& co : objects)
253  dynamic_manager->registerObject(co.get());
254  }
255  cow->m_collisionFilterGroup = CollisionFilterGroups::KinematicFilter;
256  }
257 
258  // If the group is StaticFilter then the Mask is KinematicFilter, then StaticFilter groups can only collide with
259  // KinematicFilter groups. If the group is KinematicFilter then the mask is StaticFilter and KinematicFilter meaning
260  // that KinematicFilter groups can collide with both StaticFilter and KinematicFilter groups.
261  if (cow->m_collisionFilterGroup == CollisionFilterGroups::StaticFilter)
262  {
263  cow->m_collisionFilterMask = CollisionFilterGroups::KinematicFilter;
264  }
265  else
266  {
268  }
269 }
270 
272 
274 
275 } // namespace tesseract_collision::tesseract_collision_fcl
276 #endif // TESSERACT_COLLISION_FCL_UTILS_H
tesseract_common::VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::setContactDistanceThreshold
void setContactDistanceThreshold(double contact_distance)
Definition: fcl_utils.h:123
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::shapes_
CollisionShapesConst shapes_
Definition: fcl_utils.h:176
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getCollisionObjectsRaw
const std::vector< CollisionObjectRawPtr > & getCollisionObjectsRaw() const
Definition: fcl_utils.h:134
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::clone
std::shared_ptr< CollisionObjectWrapper > clone() const
Definition: fcl_utils.h:136
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::collision_objects_
std::vector< CollisionObjectPtr > collision_objects_
Definition: fcl_utils.h:179
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::type_id_
int type_id_
Definition: fcl_utils.h:174
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getCollisionGeometriesTransforms
const tesseract_common::VectorIsometry3d & getCollisionGeometriesTransforms() const
Definition: fcl_utils.h:111
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getCollisionObjectsTransform
const Eigen::Isometry3d & getCollisionObjectsTransform() const
Definition: fcl_utils.h:131
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::setCollisionObjectsTransform
void setCollisionObjectsTransform(const Eigen::Isometry3d &pose)
Definition: fcl_utils.h:113
types.h
Tesseracts Collision Forward Declarations.
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::collision_geometries_
std::vector< CollisionGeometryPtr > collision_geometries_
Definition: fcl_utils.h:178
collision-inl.h
tesseract_collision::isLinkActive
bool isLinkActive(const std::vector< std::string > &active, const std::string &name)
This will check if a link is active provided a list. If the list is empty the link is considered acti...
Definition: common.cpp:80
tesseract_collision::tesseract_collision_fcl::StaticFilter
@ StaticFilter
Definition: fcl_utils.h:68
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getShapeIndex
static int getShapeIndex(const fcl::CollisionObjectd *co)
Given fcl collision shape get the index to the links collision shape.
Definition: fcl_utils.cpp:406
tesseract_collision::tesseract_collision_fcl::DefaultFilter
@ DefaultFilter
Definition: fcl_utils.h:67
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_collision::tesseract_collision_fcl::collisionCallback
bool collisionCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
Definition: fcl_utils.cpp:219
tesseract_collision::tesseract_collision_fcl::Link2ConstCOW
std::map< std::string, COW::ConstPtr > Link2ConstCOW
Definition: fcl_utils.h:193
tesseract_collision::tesseract_collision_fcl::CollisionGeometryPtr
std::shared_ptr< fcl::CollisionGeometryd > CollisionGeometryPtr
Definition: fcl_utils.h:60
tesseract_collision::tesseract_collision_fcl::updateCollisionObjectFilters
void updateCollisionObjectFilters(const std::vector< std::string > &active, const COW::Ptr &cow, const std::unique_ptr< fcl::BroadPhaseCollisionManagerd > &static_manager, const std::unique_ptr< fcl::BroadPhaseCollisionManagerd > &dynamic_manager)
Update collision objects filters.
Definition: fcl_utils.h:222
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::m_enabled
bool m_enabled
Definition: fcl_utils.h:93
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::world_pose_
Eigen::Isometry3d world_pose_
Collision Object World Transformation.
Definition: fcl_utils.h:175
distance-inl.h
name
std::string name
tesseract_collision::tesseract_collision_fcl::AllFilter
@ AllFilter
Definition: fcl_utils.h:70
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::ConstPtr
std::shared_ptr< const CollisionObjectWrapper > ConstPtr
Definition: fcl_utils.h:83
tesseract_collision::tesseract_collision_fcl::CollisionObjectPtr
std::shared_ptr< FCLCollisionObjectWrapper > CollisionObjectPtr
Definition: fcl_utils.h:61
tesseract_collision::tesseract_collision_fcl::KinematicFilter
@ KinematicFilter
Definition: fcl_utils.h:69
tesseract_collision::tesseract_collision_fcl::distanceCallback
bool distanceCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
Definition: fcl_utils.cpp:287
tesseract_collision::tesseract_collision_fcl::createFCLCollisionObject
COW::Ptr createFCLCollisionObject(const std::string &name, const int &type_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled)
Definition: fcl_utils.h:195
tesseract_collision::tesseract_collision_fcl::Link2COW
std::map< std::string, COW::Ptr > Link2COW
Definition: fcl_utils.h:192
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getCollisionObjects
std::vector< CollisionObjectPtr > & getCollisionObjects()
Definition: fcl_utils.h:133
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getName
const std::string & getName() const
Definition: fcl_utils.h:95
tesseract_collision::tesseract_collision_fcl::createShapePrimitive
CollisionGeometryPtr createShapePrimitive(const CollisionShapeConstPtr &geom)
Definition: fcl_utils.cpp:208
tesseract_collision::tesseract_collision_fcl
Definition: fcl_collision_geometry_cache.h:42
tesseract_collision::CollisionShapesConst
std::vector< CollisionShapeConstPtr > CollisionShapesConst
Definition: types.h:51
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::Ptr
std::shared_ptr< CollisionObjectWrapper > Ptr
Definition: fcl_utils.h:82
fcl_collision_object_wrapper.h
Collision Object Wrapper to modify AABB with contact distance threshold.
TESSERACT_COMMON_IGNORE_WARNINGS_POP
Definition: create_convex_hull.cpp:37
broadphase_dynamic_AABB_tree-inl.h
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::CollisionObjectWrapper
CollisionObjectWrapper()=default
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::m_collisionFilterGroup
short int m_collisionFilterGroup
Definition: fcl_utils.h:91
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getTypeID
const int & getTypeID() const
Definition: fcl_utils.h:96
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::name_
std::string name_
Definition: fcl_utils.h:173
common.h
This is a collection of common methods.
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper
This is a Tesseract link collision object wrapper which add items specific to tesseract....
Definition: fcl_utils.h:77
tesseract_collision::CollisionShapeConstPtr
std::shared_ptr< const tesseract_geometry::Geometry > CollisionShapeConstPtr
Definition: types.h:49
tesseract_collision::tesseract_collision_fcl::CollisionObjectConstPtr
std::shared_ptr< const fcl::CollisionObjectd > CollisionObjectConstPtr
Definition: fcl_utils.h:63
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::contact_distance_
double contact_distance_
The contact distance threshold.
Definition: fcl_utils.h:186
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getContactDistanceThreshold
double getContactDistanceThreshold() const
Definition: fcl_utils.h:130
tesseract_collision::tesseract_collision_fcl::CollisionFilterGroups
CollisionFilterGroups
Definition: fcl_utils.h:65
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getCollisionObjects
const std::vector< CollisionObjectPtr > & getCollisionObjects() const
Definition: fcl_utils.h:132
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::m_collisionFilterMask
short int m_collisionFilterMask
Definition: fcl_utils.h:92
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getCollisionGeometries
const CollisionShapesConst & getCollisionGeometries() const
Definition: fcl_utils.h:109
macros.h
fcl::CollisionObject< double >
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::getCollisionObjectsRaw
std::vector< CollisionObjectRawPtr > & getCollisionObjectsRaw()
Definition: fcl_utils.h:135
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::sameObject
bool sameObject(const CollisionObjectWrapper &other) const
Check if two objects point to the same source object.
Definition: fcl_utils.h:98
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::shape_poses_
tesseract_common::VectorIsometry3d shape_poses_
Definition: fcl_utils.h:177
tesseract_collision::tesseract_collision_fcl::CollisionObjectWrapper::collision_objects_raw_
std::vector< CollisionObjectRawPtr > collision_objects_raw_
The raw pointer is also stored because FCL accepts vectors for batch process. Note: They are updating...
Definition: fcl_utils.h:184


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:52