Tesseract 0.28.4
Loading...
Searching...
No Matches
fcl_utils.h File Reference

Tesseract ROS FCL Utility Functions. More...

#include <tesseract/common/macros.h>
#include <fcl/broadphase/broadphase_dynamic_AABB_tree-inl.h>
#include <fcl/narrowphase/collision-inl.h>
#include <fcl/narrowphase/distance-inl.h>
#include <memory>
#include <console_bridge/console.h>
#include <tesseract/collision/types.h>
#include <tesseract/collision/common.h>
#include <tesseract/collision/fcl/fcl_collision_object_wrapper.h>

Classes

class  tesseract::collision::fcl_internal::CollisionObjectWrapper
 This is a Tesseract link collision object wrapper which add items specific to tesseract. It is a wrapper around a tesseract link which may contain several collision objects. More...
 

Typedefs

using tesseract::collision::fcl_internal::CollisionGeometryPtr = std::shared_ptr< fcl::CollisionGeometryd >
 
using tesseract::collision::fcl_internal::CollisionObjectPtr = std::shared_ptr< FCLCollisionObjectWrapper >
 
using tesseract::collision::fcl_internal::CollisionObjectRawPtr = fcl::CollisionObjectd *
 
using tesseract::collision::fcl_internal::CollisionObjectConstPtr = std::shared_ptr< const fcl::CollisionObjectd >
 
using tesseract::collision::fcl_internal::COW = CollisionObjectWrapper
 
using tesseract::collision::fcl_internal::Link2COW = std::map< std::string, COW::Ptr >
 
using tesseract::collision::fcl_internal::Link2ConstCOW = std::map< std::string, COW::ConstPtr >
 

Enumerations

enum  CollisionFilterGroups : std::int8_t { DefaultFilter = 1 , StaticFilter = 2 , KinematicFilter = 4 , AllFilter = -1 }
 

Functions

CollisionGeometryPtr tesseract::collision::fcl_internal::createShapePrimitive (const CollisionShapeConstPtr &geom)
 
COW::Ptr tesseract::collision::fcl_internal::createFCLCollisionObject (const std::string &name, const int &type_id, const CollisionShapesConst &shapes, const tesseract::common::VectorIsometry3d &shape_poses, bool enabled)
 
void tesseract::collision::fcl_internal::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.
 
bool tesseract::collision::fcl_internal::needsCollisionCheck (const CollisionObjectWrapper *cd1, const CollisionObjectWrapper *cd2, const std::shared_ptr< const tesseract::common::ContactAllowedValidator > &validator, bool verbose)
 This is used to check if a collision check is required between the provided two collision objects.
 
bool tesseract::collision::fcl_internal::collisionCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
 
bool tesseract::collision::fcl_internal::distanceCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
 

Detailed Description

Tesseract ROS FCL Utility Functions.

Author
Levi Armstrong
Date
Dec 18, 2017
License
Software License Agreement (BSD)
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
  • Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  • Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Function Documentation

◆ updateCollisionObjectFilters()

void tesseract::collision::fcl_internal::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 
)
inline

Update collision objects filters.

Parameters
activeThe active collision objects
cowThe collision object to update
static_managerBroadphasse manager for static objects
dynamic_managerBroadphase manager for dynamic objects

◆ needsCollisionCheck()

bool tesseract::collision::fcl_internal::needsCollisionCheck ( const CollisionObjectWrapper cd1,
const CollisionObjectWrapper cd2,
const std::shared_ptr< const tesseract::common::ContactAllowedValidator > &  validator,
bool  verbose 
)

This is used to check if a collision check is required between the provided two collision objects.

Parameters
cow1The first collision object
cow2The second collision object
validatorThe contact allowed validator
verboseIndicate if verbose information should be printed to the terminal
Returns
True if the two collision objects should be checked for collision, otherwise false