.. _program_listing_file__tmp_ws_src_hpp-fcl_include_hpp_fcl_internal_traversal_node_base.h: Program Listing for File traversal_node_base.h ============================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/hpp-fcl/include/hpp/fcl/internal/traversal_node_base.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* * Software License Agreement (BSD License) * * Copyright (c) 2011-2014, Willow Garage, Inc. * Copyright (c) 2014-2015, Open Source Robotics Foundation * 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. * * Neither the name of Open Source Robotics Foundation nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * 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. */ #ifndef HPP_FCL_TRAVERSAL_NODE_BASE_H #define HPP_FCL_TRAVERSAL_NODE_BASE_H #include #include #include namespace hpp { namespace fcl { class TraversalNodeBase { public: TraversalNodeBase() : enable_statistics(false) {} virtual ~TraversalNodeBase() {} virtual void preprocess() {} virtual void postprocess() {} virtual bool isFirstNodeLeaf(unsigned int /*b*/) const { return true; } virtual bool isSecondNodeLeaf(unsigned int /*b*/) const { return true; } virtual bool firstOverSecond(unsigned int /*b1*/, unsigned int /*b2*/) const { return true; } virtual int getFirstLeftChild(unsigned int b) const { return (int)b; } virtual int getFirstRightChild(unsigned int b) const { return (int)b; } virtual int getSecondLeftChild(unsigned int b) const { return (int)b; } virtual int getSecondRightChild(unsigned int b) const { return (int)b; } void enableStatistics(bool enable) { enable_statistics = enable; } Transform3f tf1; Transform3f tf2; bool enable_statistics; }; class CollisionTraversalNodeBase : public TraversalNodeBase { public: CollisionTraversalNodeBase(const CollisionRequest& request_) : request(request_), result(NULL) {} virtual ~CollisionTraversalNodeBase() {} virtual bool BVDisjoints(unsigned int b1, unsigned int b2, FCL_REAL& sqrDistLowerBound) const = 0; virtual void leafCollides(unsigned int /*b1*/, unsigned int /*b2*/, FCL_REAL& /*sqrDistLowerBound*/) const = 0; bool canStop() const { return this->request.isSatisfied(*(this->result)); } const CollisionRequest& request; CollisionResult* result; }; class DistanceTraversalNodeBase : public TraversalNodeBase { public: DistanceTraversalNodeBase() : result(NULL) {} virtual ~DistanceTraversalNodeBase() {} virtual FCL_REAL BVDistanceLowerBound(unsigned int /*b1*/, unsigned int /*b2*/) const { return (std::numeric_limits::max)(); } virtual void leafComputeDistance(unsigned int b1, unsigned int b2) const = 0; virtual bool canStop(FCL_REAL /*c*/) const { return false; } DistanceRequest request; DistanceResult* result; }; } // namespace fcl } // namespace hpp #endif