diff --git a/CMakeModules/CompilerSettings.cmake b/CMakeModules/CompilerSettings.cmake index b2c0ee6fe..aae41305f 100644 --- a/CMakeModules/CompilerSettings.cmake +++ b/CMakeModules/CompilerSettings.cmake @@ -1,6 +1,6 @@ # GCC if(CMAKE_COMPILER_IS_GNUCXX) - add_definitions(-std=c++11 -W -Wall -Wextra -Wpedantic -Wno-unused-parameter) + add_definitions(-std=c++11 -W -Wall -Wextra -Wpedantic) if(FCL_TREAT_WARNINGS_AS_ERRORS) add_definitions(-Werror) endif() @@ -8,7 +8,7 @@ endif() # Clang if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") - add_definitions(-std=c++11 -W -Wall -Wextra -Wno-unused-parameter) + add_definitions(-std=c++11 -W -Wall -Wextra) if(FCL_TREAT_WARNINGS_AS_ERRORS) add_definitions(-Werror) endif() @@ -20,7 +20,7 @@ if(CMAKE_CXX_COMPILER_ID STREQUAL "AppleClang") if (CMAKE_CXX_COMPILER_VERSION VERSION_LESS 6.1) message(FATAL_ERROR "AppleClang version must be at least 6.1!") endif() - add_definitions(-std=c++11 -W -Wall -Wextra -Wno-unused-parameter) + add_definitions(-std=c++11 -W -Wall -Wextra) if(FCL_TREAT_WARNINGS_AS_ERRORS) add_definitions(-Werror) endif() diff --git a/include/fcl/broadphase/broadphase_collision_manager-inl.h b/include/fcl/broadphase/broadphase_collision_manager-inl.h index f03c864b9..1b5204bcf 100644 --- a/include/fcl/broadphase/broadphase_collision_manager-inl.h +++ b/include/fcl/broadphase/broadphase_collision_manager-inl.h @@ -31,7 +31,7 @@ * 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. - */ + */ /** @author Jia Pan */ @@ -40,6 +40,8 @@ #include "fcl/broadphase/broadphase_collision_manager.h" +#include "fcl/common/unused.h" + namespace fcl { //============================================================================== @@ -74,6 +76,8 @@ void BroadPhaseCollisionManager::registerObjects( template void BroadPhaseCollisionManager::update(CollisionObject* updated_obj) { + FCL_UNUSED(updated_obj); + update(); } @@ -82,6 +86,8 @@ template void BroadPhaseCollisionManager::update( const std::vector*>& updated_objs) { + FCL_UNUSED(updated_objs); + update(); } diff --git a/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h b/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h index 2e809413a..c5dee1140 100644 --- a/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h +++ b/include/fcl/broadphase/broadphase_continuous_collision_manager-inl.h @@ -31,7 +31,7 @@ * 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. - */ + */ /** @author Jia Pan */ @@ -40,6 +40,8 @@ #include "fcl/broadphase/broadphase_continuous_collision_manager.h" +#include "fcl/common/unused.h" + namespace fcl { //============================================================================== @@ -74,6 +76,8 @@ template void BroadPhaseContinuousCollisionManager::update( ContinuousCollisionObject* updated_obj) { + FCL_UNUSED(updated_obj); + update(); } @@ -82,6 +86,8 @@ template void BroadPhaseContinuousCollisionManager::update( const std::vector*>& updated_objs) { + FCL_UNUSED(updated_objs); + update(); } diff --git a/include/fcl/broadphase/detail/hierarchy_tree_array-inl.h b/include/fcl/broadphase/detail/hierarchy_tree_array-inl.h index 51c72bf9f..6e9d33498 100644 --- a/include/fcl/broadphase/detail/hierarchy_tree_array-inl.h +++ b/include/fcl/broadphase/detail/hierarchy_tree_array-inl.h @@ -40,6 +40,8 @@ #include "fcl/broadphase/detail/hierarchy_tree_array.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -342,6 +344,10 @@ bool HierarchyTree::update(size_t leaf, const BV& bv) template bool HierarchyTree::update(size_t leaf, const BV& bv, const Vector3& vel, S margin) { + FCL_UNUSED(bv); + FCL_UNUSED(vel); + FCL_UNUSED(margin); + if(nodes[leaf].bv.contain(bv)) return false; update_(leaf, bv); return true; @@ -351,6 +357,8 @@ bool HierarchyTree::update(size_t leaf, const BV& bv, const Vector3& vel, template bool HierarchyTree::update(size_t leaf, const BV& bv, const Vector3& vel) { + FCL_UNUSED(vel); + if(nodes[leaf].bv.contain(bv)) return false; update_(leaf, bv); return true; @@ -1071,11 +1079,21 @@ struct SelectImpl { static bool run(size_t query, size_t node1, size_t node2, NodeBase* nodes) { + FCL_UNUSED(query); + FCL_UNUSED(node1); + FCL_UNUSED(node2); + FCL_UNUSED(nodes); + return 0; } static bool run(const BV& query, size_t node1, size_t node2, NodeBase* nodes) { + FCL_UNUSED(query); + FCL_UNUSED(node1); + FCL_UNUSED(node2); + FCL_UNUSED(nodes); + return 0; } }; diff --git a/include/fcl/common/unused.h b/include/fcl/common/unused.h new file mode 100644 index 000000000..eba5e089f --- /dev/null +++ b/include/fcl/common/unused.h @@ -0,0 +1,41 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, 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 FCL_COMMON_UNUSED_H +#define FCL_COMMON_UNUSED_H + +// Macro to suppress -Wunused-parameter and -Wunused-variable warnings. +#define FCL_UNUSED(x) do { (void)(x); } while (0) + +#endif diff --git a/include/fcl/geometry/bvh/detail/BV_splitter-inl.h b/include/fcl/geometry/bvh/detail/BV_splitter-inl.h index b0ea97005..8bb3c0da7 100644 --- a/include/fcl/geometry/bvh/detail/BV_splitter-inl.h +++ b/include/fcl/geometry/bvh/detail/BV_splitter-inl.h @@ -40,6 +40,8 @@ #include "fcl/geometry/bvh/detail/BV_splitter.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -591,6 +593,8 @@ void computeSplitValue_mean( const Vector3& split_vector, S& split_value) { + FCL_UNUSED(bv); + S sum = 0.0; if(type == BVH_MODEL_TRIANGLES) { @@ -634,6 +638,8 @@ void computeSplitValue_median( const Vector3& split_vector, S& split_value) { + FCL_UNUSED(bv); + std::vector proj(num_primitives); if(type == BVH_MODEL_TRIANGLES) diff --git a/include/fcl/geometry/shape/utility-inl.h b/include/fcl/geometry/shape/utility-inl.h index 08ac58155..fa0057a72 100644 --- a/include/fcl/geometry/shape/utility-inl.h +++ b/include/fcl/geometry/shape/utility-inl.h @@ -40,6 +40,8 @@ #include "fcl/geometry/shape/utility.h" +#include "fcl/common/unused.h" + #include "fcl/math/bv/utility.h" #include "fcl/geometry/shape/capsule.h" @@ -359,6 +361,9 @@ struct ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, OBB& bv) { + FCL_UNUSED(s); + FCL_UNUSED(tf); + /// Half space can only have very rough OBB bv.axis.setIdentity(); bv.To.setZero(); @@ -372,6 +377,9 @@ struct ComputeBVImpl, Halfspace> { static void run(const Halfspace& s, const Transform3& tf, RSS& bv) { + FCL_UNUSED(s); + FCL_UNUSED(tf); + /// Half space can only have very rough RSS bv.axis.setIdentity(); bv.To.setZero(); @@ -1137,6 +1145,8 @@ void constructBox(const AABB& bv, const Transform3& tf_bv, Box& box, Tr template void constructBox(const OBB& bv, const Transform3& tf_bv, Box& box, Transform3& tf) { + FCL_UNUSED(tf_bv); + box = Box(bv.extent * 2); tf.linear() = bv.axis; tf.translation() = bv.To; @@ -1156,6 +1166,8 @@ void constructBox(const OBBRSS& bv, const Transform3& tf_bv, Box& box, template void constructBox(const kIOS& bv, const Transform3& tf_bv, Box& box, Transform3& tf) { + FCL_UNUSED(tf_bv); + box = Box(bv.obb.extent * 2); tf.linear() = bv.obb.axis; tf.translation() = bv.obb.To; diff --git a/include/fcl/math/bv/OBB-inl.h b/include/fcl/math/bv/OBB-inl.h index 0b9b132bc..489f34962 100644 --- a/include/fcl/math/bv/OBB-inl.h +++ b/include/fcl/math/bv/OBB-inl.h @@ -40,6 +40,8 @@ #include "fcl/math/bv/OBB.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -110,6 +112,8 @@ bool OBB::overlap(const OBB& other) const template bool OBB::overlap(const OBB& other, OBB& overlap_part) const { + FCL_UNUSED(overlap_part); + return overlap(other); } @@ -216,6 +220,10 @@ template S OBB::distance(const OBB& other, Vector3* P, Vector3* Q) const { + FCL_UNUSED(other); + FCL_UNUSED(P); + FCL_UNUSED(Q); + std::cerr << "OBB distance not implemented!" << std::endl; return 0.0; } diff --git a/include/fcl/math/bv/kDOP-inl.h b/include/fcl/math/bv/kDOP-inl.h index 5e0ccca5d..fdd71d949 100644 --- a/include/fcl/math/bv/kDOP-inl.h +++ b/include/fcl/math/bv/kDOP-inl.h @@ -40,6 +40,8 @@ #include "fcl/math/bv/kDOP.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -243,6 +245,10 @@ Vector3 KDOP::center() const template S KDOP::distance(const KDOP& other, Vector3* P, Vector3* Q) const { + FCL_UNUSED(other); + FCL_UNUSED(P); + FCL_UNUSED(Q); + std::cerr << "KDOP distance not implemented!" << std::endl; return 0.0; } diff --git a/include/fcl/math/bv/utility-inl.h b/include/fcl/math/bv/utility-inl.h index eda4efa3f..250626dc3 100644 --- a/include/fcl/math/bv/utility-inl.h +++ b/include/fcl/math/bv/utility-inl.h @@ -40,6 +40,8 @@ #include "fcl/math/bv/utility.h" +#include "fcl/common/unused.h" + #include "fcl/math/bv/AABB.h" #include "fcl/math/bv/kDOP.h" #include "fcl/math/bv/kIOS.h" @@ -661,6 +663,10 @@ class ConvertBVImpl private: static void run(const BV1& bv1, const Transform3& tf1, BV2& bv2) { + FCL_UNUSED(bv1); + FCL_UNUSED(tf1); + FCL_UNUSED(bv2); + // should only use the specialized version, so it is private. } }; diff --git a/include/fcl/math/motion/spline_motion-inl.h b/include/fcl/math/motion/spline_motion-inl.h index a51b35244..aa2c07038 100644 --- a/include/fcl/math/motion/spline_motion-inl.h +++ b/include/fcl/math/motion/spline_motion-inl.h @@ -40,6 +40,8 @@ #include "fcl/math/motion/spline_motion.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -93,6 +95,11 @@ SplineMotion::SplineMotion( const Matrix3& R2, const Vector3& T2) : MotionBase() { + FCL_UNUSED(R1); + FCL_UNUSED(T1); + FCL_UNUSED(R2); + FCL_UNUSED(T2); + // TODO } @@ -102,6 +109,9 @@ SplineMotion::SplineMotion( const Transform3& tf1, const Transform3& tf2) : MotionBase() { + FCL_UNUSED(tf1); + FCL_UNUSED(tf2); + // TODO } diff --git a/include/fcl/math/motion/tbv_motion_bound_visitor-inl.h b/include/fcl/math/motion/tbv_motion_bound_visitor-inl.h index 4adda321d..f33249d38 100644 --- a/include/fcl/math/motion/tbv_motion_bound_visitor-inl.h +++ b/include/fcl/math/motion/tbv_motion_bound_visitor-inl.h @@ -40,6 +40,8 @@ #include "fcl/math/motion/tbv_motion_bound_visitor.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -69,6 +71,8 @@ template typename BV::S TBVMotionBoundVisitor::visit( const MotionBase& motion) const { + FCL_UNUSED(motion); + return 0; } diff --git a/include/fcl/math/motion/translation_motion-inl.h b/include/fcl/math/motion/translation_motion-inl.h index 465ec4fed..7feffd1cc 100644 --- a/include/fcl/math/motion/translation_motion-inl.h +++ b/include/fcl/math/motion/translation_motion-inl.h @@ -40,6 +40,8 @@ #include "fcl/math/motion/translation_motion.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -113,6 +115,9 @@ void TranslationMotion::getCurrentTransform(Transform3& tf_) const template void TranslationMotion::getTaylorModel(TMatrix3& tm, TVector3& tv) const { + FCL_UNUSED(tm); + FCL_UNUSED(tv); + // Do nothing // TODO(JS): Not implemented? } diff --git a/include/fcl/math/motion/triangle_motion_bound_visitor.h b/include/fcl/math/motion/triangle_motion_bound_visitor.h index 4f5e0b482..c37a206a7 100644 --- a/include/fcl/math/motion/triangle_motion_bound_visitor.h +++ b/include/fcl/math/motion/triangle_motion_bound_visitor.h @@ -38,6 +38,8 @@ #ifndef FCL_CCD_TRIANGLEMOTIONBOUNDVISITOR_H #define FCL_CCD_TRIANGLEMOTIONBOUNDVISITOR_H +#include "fcl/common/unused.h" + #include "fcl/math/motion/taylor_model/taylor_matrix.h" #include "fcl/math/motion/taylor_model/taylor_vector.h" #include "fcl/math/bv/RSS.h" @@ -76,7 +78,7 @@ class TriangleMotionBoundVisitor const Vector3& a_, const Vector3& b_, const Vector3& c_, const Vector3& n_); - virtual S visit(const MotionBase& motion) const { return 0; } + virtual S visit(const MotionBase& motion) const { FCL_UNUSED(motion); return 0; } virtual S visit(const SplineMotion& motion) const; virtual S visit(const ScrewMotion& motion) const; virtual S visit(const InterpMotion& motion) const; diff --git a/include/fcl/narrowphase/continuous_collision-inl.h b/include/fcl/narrowphase/continuous_collision-inl.h index 3121e089e..785a7af83 100644 --- a/include/fcl/narrowphase/continuous_collision-inl.h +++ b/include/fcl/narrowphase/continuous_collision-inl.h @@ -40,10 +40,13 @@ #include "fcl/narrowphase/continuous_collision.h" +#include "fcl/common/unused.h" + #include "fcl/math/motion/translation_motion.h" #include "fcl/math/motion/interp_motion.h" #include "fcl/math/motion/screw_motion.h" #include "fcl/math/motion/spline_motion.h" + #include "fcl/narrowphase/collision.h" #include "fcl/narrowphase/collision_result.h" #include "fcl/narrowphase/detail/traversal/collision_node.h" @@ -178,6 +181,8 @@ typename BV::S continuousCollideBVHPolynomial( const ContinuousCollisionRequest& request, ContinuousCollisionResult& result) { + FCL_UNUSED(request); + using S = typename BV::S; const BVHModel* o1__ = static_cast*>(o1_); diff --git a/include/fcl/narrowphase/detail/collision_func_matrix-inl.h b/include/fcl/narrowphase/detail/collision_func_matrix-inl.h index 6363a19f6..b2f1dd9cc 100644 --- a/include/fcl/narrowphase/detail/collision_func_matrix-inl.h +++ b/include/fcl/narrowphase/detail/collision_func_matrix-inl.h @@ -42,6 +42,8 @@ #include "fcl/config.h" +#include "fcl/common/unused.h" + #include "fcl/narrowphase/collision_object.h" #include "fcl/geometry/shape/box.h" @@ -652,6 +654,8 @@ std::size_t BVHCollide( const CollisionRequest& request, CollisionResult& result) { + FCL_UNUSED(nsolver); + return BVHCollide(o1, tf1, o2, tf2, request, result); } diff --git a/include/fcl/narrowphase/detail/conservative_advancement_func_matrix-inl.h b/include/fcl/narrowphase/detail/conservative_advancement_func_matrix-inl.h index 70a2f7dc4..d6431d6e3 100644 --- a/include/fcl/narrowphase/detail/conservative_advancement_func_matrix-inl.h +++ b/include/fcl/narrowphase/detail/conservative_advancement_func_matrix-inl.h @@ -40,8 +40,12 @@ #include "fcl/narrowphase/detail/conservative_advancement_func_matrix.h" +#include "fcl/common/unused.h" + #include "fcl/narrowphase/collision_object.h" + #include "fcl/math/motion/motion_base.h" + #include "fcl/geometry/bvh/BVH_model.h" #include "fcl/geometry/shape/box.h" #include "fcl/geometry/shape/capsule.h" @@ -688,6 +692,9 @@ struct ConservativeAdvancementImpl>, NarrowPhaseSolver> template typename BV::S BVHConservativeAdvancement(const CollisionGeometry* o1, const MotionBase* motion1, const CollisionGeometry* o2, const MotionBase* motion2, const NarrowPhaseSolver* nsolver, const ContinuousCollisionRequest& request, ContinuousCollisionResult& result) { + FCL_UNUSED(nsolver); + FCL_UNUSED(request); + using S = typename BV::S; const BVHModel* obj1 = static_cast*>(o1); @@ -707,6 +714,8 @@ typename BV::S BVHConservativeAdvancement(const CollisionGeometry typename Shape1::S ShapeConservativeAdvancement(const CollisionGeometry* o1, const MotionBase* motion1, const CollisionGeometry* o2, const MotionBase* motion2, const NarrowPhaseSolver* nsolver, const ContinuousCollisionRequest& request, ContinuousCollisionResult& result) { + FCL_UNUSED(request); + using S = typename Shape1::S; const Shape1* obj1 = static_cast(o1); @@ -726,6 +735,8 @@ typename Shape1::S ShapeConservativeAdvancement(const CollisionGeometry typename BV::S ShapeBVHConservativeAdvancement(const CollisionGeometry* o1, const MotionBase* motion1, const CollisionGeometry* o2, const MotionBase* motion2, const NarrowPhaseSolver* nsolver, const ContinuousCollisionRequest& request, ContinuousCollisionResult& result) { + FCL_UNUSED(request); + using S = typename BV::S; const Shape* obj1 = static_cast(o1); @@ -746,6 +757,8 @@ typename BV::S ShapeBVHConservativeAdvancement(const CollisionGeometry typename BV::S BVHShapeConservativeAdvancement(const CollisionGeometry* o1, const MotionBase* motion1, const CollisionGeometry* o2, const MotionBase* motion2, const NarrowPhaseSolver* nsolver, const ContinuousCollisionRequest& request, ContinuousCollisionResult& result) { + FCL_UNUSED(request); + using S = typename BV::S; const BVHModel* obj1 = static_cast*>(o1); diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h index ccb0b6546..fa3dadcd8 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd-inl.h @@ -40,6 +40,7 @@ #include "fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h" +#include "fcl/common/unused.h" #include "fcl/common/warning.h" namespace fcl @@ -1105,6 +1106,8 @@ static int penEPAPosCmp(const void *a, const void *b) static int penEPAPosClosest(const ccd_pt_t *pt, const ccd_pt_el_t *nearest, ccd_vec3_t *p1, ccd_vec3_t* p2) { + FCL_UNUSED(nearest); + ccd_pt_vertex_t *v; ccd_pt_vertex_t **vs; size_t i, len; @@ -1265,6 +1268,8 @@ static inline ccd_real_t ccdGJKDist2(const void *obj1, const void *obj2, const c template static void shapeToGJK(const ShapeBase& s, const Transform3& tf, ccd_obj_t* o) { + FCL_UNUSED(s); + const Quaternion q(tf.linear()); const Vector3& T = tf.translation(); ccdVec3Set(&o->pos, T[0], T[1], T[2]); diff --git a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h index 73b47caa4..c6cbf20d8 100644 --- a/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h +++ b/include/fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h @@ -41,6 +41,9 @@ #include #include #include + +#include "fcl/common/unused.h" + #include "fcl/geometry/shape/box.h" #include "fcl/geometry/shape/capsule.h" #include "fcl/geometry/shape/cone.h" @@ -51,6 +54,7 @@ #include "fcl/geometry/shape/plane.h" #include "fcl/geometry/shape/sphere.h" #include "fcl/geometry/shape/triangle_p.h" + #include "fcl/narrowphase/detail/convexity_based_algorithm/simplex.h" #include "fcl/narrowphase/detail/convexity_based_algorithm/polytope.h" #include "fcl/narrowphase/detail/convexity_based_algorithm/alloc.h" @@ -85,7 +89,7 @@ class GJKInitializer static void* createGJKObject(const T& /* s */, const Transform3& /*tf*/) { return nullptr; } /// @brief Delete GJK object - static void deleteGJKObject(void* o) {} + static void deleteGJKObject(void* o) { FCL_UNUSED(o); } }; /// @brief initialize GJK Cylinder diff --git a/include/fcl/narrowphase/detail/distance_func_matrix-inl.h b/include/fcl/narrowphase/detail/distance_func_matrix-inl.h index 1c4b257a8..43f5f0984 100644 --- a/include/fcl/narrowphase/detail/distance_func_matrix-inl.h +++ b/include/fcl/narrowphase/detail/distance_func_matrix-inl.h @@ -43,6 +43,7 @@ #include "fcl/config.h" #include "fcl/common/types.h" +#include "fcl/common/unused.h" #include "fcl/narrowphase/collision_object.h" @@ -467,6 +468,8 @@ typename BV::S BVHDistance( const DistanceRequest& request, DistanceResult& result) { + FCL_UNUSED(nsolver); + return BVHDistance(o1, tf1, o2, tf2, request, result); } diff --git a/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h b/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h index 4e0b2ff8e..c9b520e13 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h +++ b/include/fcl/narrowphase/detail/gjk_solver_indep-inl.h @@ -42,7 +42,10 @@ #include +#include "fcl/common/unused.h" + #include "fcl/geometry/shape/triangle_p.h" + #include "fcl/narrowphase/detail/convexity_based_algorithm/gjk.h" #include "fcl/narrowphase/detail/convexity_based_algorithm/epa.h" #include "fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h" @@ -268,6 +271,8 @@ struct ShapeIntersectIndepImpl, Halfspace> const Transform3& tf2, std::vector>* contacts) { + FCL_UNUSED(contacts); + Halfspace s; Vector3 p, d; S depth; @@ -302,6 +307,8 @@ struct ShapeIntersectIndepImpl, Halfspace> const Transform3& tf2, std::vector>* contacts) { + FCL_UNUSED(contacts); + Plane pl; Vector3 p, d; S depth; @@ -321,6 +328,8 @@ struct ShapeIntersectIndepImpl, Plane> const Transform3& tf2, std::vector>* contacts) { + FCL_UNUSED(contacts); + Plane pl; Vector3 p, d; S depth; diff --git a/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h b/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h index 064b8c82f..3bf490eb3 100755 --- a/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h +++ b/include/fcl/narrowphase/detail/gjk_solver_libccd-inl.h @@ -42,6 +42,8 @@ #include +#include "fcl/common/unused.h" + #include "fcl/narrowphase/detail/convexity_based_algorithm/gjk_libccd.h" #include "fcl/narrowphase/detail/primitive_shape_algorithm/capsule_capsule.h" #include "fcl/narrowphase/detail/primitive_shape_algorithm/sphere_capsule.h" @@ -265,6 +267,8 @@ struct ShapeIntersectLibccdImpl, Halfspace> const Transform3& tf2, std::vector>* contacts) { + FCL_UNUSED(contacts); + Halfspace s; Vector3 p, d; S depth; @@ -299,6 +303,8 @@ struct ShapeIntersectLibccdImpl, Halfspace> const Transform3& tf2, std::vector>* contacts) { + FCL_UNUSED(contacts); + Plane pl; Vector3 p, d; S depth; @@ -318,6 +324,8 @@ struct ShapeIntersectLibccdImpl, Plane> const Transform3& tf2, std::vector>* contacts) { + FCL_UNUSED(contacts); + Plane pl; Vector3 p, d; S depth; @@ -902,6 +910,8 @@ GJKSolver_libccd::GJKSolver_libccd() template void GJKSolver_libccd::enableCachedGuess(bool if_enable) const { + FCL_UNUSED(if_enable); + // TODO: need change libccd to exploit spatial coherence } @@ -910,6 +920,8 @@ template void GJKSolver_libccd::setCachedGuess( const Vector3& guess) const { + FCL_UNUSED(guess); + // TODO: need change libccd to exploit spatial coherence } diff --git a/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node-inl.h index 73a11ad3e..5faef8c71 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/collision/bvh_shape_collision_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -84,6 +86,8 @@ int BVHShapeCollisionTraversalNode::getFirstRightChild(int b) const template bool BVHShapeCollisionTraversalNode::BVTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) num_bv_tests++; return !model1->getBV(b1).bv.overlap(model2_bv); } diff --git a/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h b/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h index 80b1f4de8..f1243c841 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/collision/collision_traversal_node_base.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -69,6 +71,9 @@ CollisionTraversalNodeBase::~CollisionTraversalNodeBase() template bool CollisionTraversalNodeBase::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + FCL_UNUSED(b2); + return true; } @@ -76,6 +81,9 @@ bool CollisionTraversalNodeBase::BVTesting(int b1, int b2) const template void CollisionTraversalNodeBase::leafTesting(int b1, int b2) const { + FCL_UNUSED(b1); + FCL_UNUSED(b2); + // Do nothing } diff --git a/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h index 0319a8a1e..66255b631 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/collision/mesh_collision_traversal_node.h" +#include "fcl/common/unused.h" + #include "fcl/narrowphase/collision_result.h" namespace fcl @@ -348,6 +350,9 @@ template void MeshCollisionTraversalNodeOBB::leafTesting( int b1, int b2, const Matrix3& Rc, const Vector3& Tc) const { + FCL_UNUSED(Rc); + FCL_UNUSED(Tc); + detail::meshCollisionOrientedNodeLeafTesting( b1, b2, diff --git a/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node-inl.h index 651a802ed..d24b4676c 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/collision/mesh_shape_collision_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -61,6 +63,8 @@ MeshShapeCollisionTraversalNode::MeshShapeCollisio template void MeshShapeCollisionTraversalNode::leafTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_leaf_tests++; const BVNode& node = this->model1->getBV(b1); @@ -198,6 +202,8 @@ void meshShapeCollisionOrientedNodeLeafTesting( const CollisionRequest& request, CollisionResult& result) { + FCL_UNUSED(b2); + using S = typename BV::S; if(enable_statistics) num_leaf_tests++; @@ -272,6 +278,8 @@ MeshShapeCollisionTraversalNodeOBB() template bool MeshShapeCollisionTraversalNodeOBB::BVTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv); @@ -296,6 +304,8 @@ MeshShapeCollisionTraversalNodeRSS::MeshShapeCollision template bool MeshShapeCollisionTraversalNodeRSS::BVTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv); @@ -321,6 +331,8 @@ MeshShapeCollisionTraversalNodekIOS() template bool MeshShapeCollisionTraversalNodekIOS::BVTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv); @@ -346,6 +358,8 @@ MeshShapeCollisionTraversalNodeOBBRSS() template bool MeshShapeCollisionTraversalNodeOBBRSS::BVTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv); } diff --git a/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node-inl.h index 962cae9c4..7426ad063 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/collision/shape_bvh_collision_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -91,6 +93,8 @@ int ShapeBVHCollisionTraversalNode::getSecondRightChild(int b) const template bool ShapeBVHCollisionTraversalNode::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) num_bv_tests++; return !model2->getBV(b2).bv.overlap(model1_bv); } diff --git a/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h index 2fff0ec1c..ed405f592 100644 --- a/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/collision/shape_mesh_collision_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -61,6 +63,8 @@ ShapeMeshCollisionTraversalNode::ShapeMeshCollisio template void ShapeMeshCollisionTraversalNode::leafTesting(int b1, int b2) const { + FCL_UNUSED(b1); + using S = typename BV::S; if(this->enable_statistics) this->num_leaf_tests++; @@ -195,6 +199,8 @@ ShapeMeshCollisionTraversalNodeOBB::ShapeMeshCollision template bool ShapeMeshCollisionTraversalNodeOBB::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv); } @@ -219,6 +225,8 @@ ShapeMeshCollisionTraversalNodeRSS::ShapeMeshCollision template bool ShapeMeshCollisionTraversalNodeRSS::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv); } @@ -243,6 +251,8 @@ ShapeMeshCollisionTraversalNodekIOS::ShapeMeshCollisio template bool ShapeMeshCollisionTraversalNodekIOS::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv); } @@ -267,6 +277,8 @@ ShapeMeshCollisionTraversalNodeOBBRSS::ShapeMeshCollis template bool ShapeMeshCollisionTraversalNodeOBBRSS::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_bv_tests++; return !overlap(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv); } diff --git a/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node-inl.h index 5c8363c12..094d84367 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/distance/bvh_shape_distance_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -85,6 +87,8 @@ template typename BV::S BVHShapeDistanceTraversalNode::BVTesting( int b1, int b2) const { + FCL_UNUSED(b2); + return model1->getBV(b1).bv.distance(model2_bv); } diff --git a/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h b/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h index 07f11b940..763179b69 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/distance/distance_traversal_node_base.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -69,6 +71,9 @@ DistanceTraversalNodeBase::~DistanceTraversalNodeBase() template S DistanceTraversalNodeBase::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + FCL_UNUSED(b2); + return std::numeric_limits::max(); } @@ -76,6 +81,9 @@ S DistanceTraversalNodeBase::BVTesting(int b1, int b2) const template void DistanceTraversalNodeBase::leafTesting(int b1, int b2) const { + FCL_UNUSED(b1); + FCL_UNUSED(b2); + // Do nothing } @@ -83,6 +91,8 @@ void DistanceTraversalNodeBase::leafTesting(int b1, int b2) const template bool DistanceTraversalNodeBase::canStop(S c) const { + FCL_UNUSED(c); + return false; } diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node-inl.h index 9424f599f..20ee58d40 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/distance/mesh_shape_conservative_advancement_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -82,6 +84,8 @@ template void MeshShapeConservativeAdvancementTraversalNode:: leafTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_leaf_tests++; const BVNode& node = this->model1->getBV(b1); @@ -292,6 +296,8 @@ bool meshShapeConservativeAdvancementOrientedNodeCanStop( std::vector>& stack, typename BV::S& delta_t) { + FCL_UNUSED(model2); + using S = typename BV::S; if((c >= w * (min_distance - abs_err)) && (c * (1 + rel_err) >= w * min_distance)) diff --git a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node-inl.h index ae34d1d63..4540f600b 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/distance/mesh_shape_distance_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -66,6 +68,8 @@ template void MeshShapeDistanceTraversalNode:: leafTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_leaf_tests++; const BVNode& node = this->model1->getBV(b1); @@ -269,6 +273,8 @@ typename Shape::S MeshShapeDistanceTraversalNodeRSS::BVTesting( int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_bv_tests++; return distance(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv); @@ -319,6 +325,8 @@ void MeshShapeDistanceTraversalNodekIOS::postprocess() template typename Shape::S MeshShapeDistanceTraversalNodekIOS::BVTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_bv_tests++; return distance(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv); @@ -359,6 +367,8 @@ typename Shape::S MeshShapeDistanceTraversalNodeOBBRSS:: BVTesting(int b1, int b2) const { + FCL_UNUSED(b2); + if(this->enable_statistics) this->num_bv_tests++; return distance(this->tf1.linear(), this->tf1.translation(), this->model2_bv, this->model1->getBV(b1).bv); diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node-inl.h index 558ae5ee4..1478e92fc 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/distance/shape_bvh_distance_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -85,6 +87,8 @@ template typename BV::S ShapeBVHDistanceTraversalNode::BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + return model1_bv.distance(model2->getBV(b2).bv); } diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node-inl.h index 4b7704ba7..45ae86fe3 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/distance/shape_mesh_conservative_advancement_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -81,6 +83,8 @@ BVTesting(int b1, int b2) const template void ShapeMeshConservativeAdvancementTraversalNode::leafTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_leaf_tests++; const BVNode& node = this->model2->getBV(b2); diff --git a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h index 75d96a62d..c059ed10e 100644 --- a/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h +++ b/include/fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/distance/shape_mesh_distance_traversal_node.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -65,6 +67,8 @@ ShapeMeshDistanceTraversalNode() template void ShapeMeshDistanceTraversalNode::leafTesting(int b1, int b2) const { + FCL_UNUSED(b1); + using S = typename BV::S; if(this->enable_statistics) this->num_leaf_tests++; @@ -183,6 +187,8 @@ typename Shape::S ShapeMeshDistanceTraversalNodeRSS:: BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_bv_tests++; return distance(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv); } @@ -232,6 +238,8 @@ typename Shape::S ShapeMeshDistanceTraversalNodekIOS:: BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_bv_tests++; return distance(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv); } @@ -281,6 +289,8 @@ typename Shape::S ShapeMeshDistanceTraversalNodeOBBRSS:: BVTesting(int b1, int b2) const { + FCL_UNUSED(b1); + if(this->enable_statistics) this->num_bv_tests++; return distance(this->tf2.linear(), this->tf2.translation(), this->model1_bv, this->model2->getBV(b2).bv); } diff --git a/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h b/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h index acfc6c8f0..9ff776e0e 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_node_base-inl.h @@ -40,6 +40,8 @@ #include "fcl/narrowphase/detail/traversal/traversal_node_base.h" +#include "fcl/common/unused.h" + namespace fcl { @@ -75,6 +77,8 @@ void TraversalNodeBase::postprocess() template bool TraversalNodeBase::isFirstNodeLeaf(int b) const { + FCL_UNUSED(b); + return true; } @@ -82,6 +86,8 @@ bool TraversalNodeBase::isFirstNodeLeaf(int b) const template bool TraversalNodeBase::isSecondNodeLeaf(int b) const { + FCL_UNUSED(b); + return true; } @@ -89,6 +95,9 @@ bool TraversalNodeBase::isSecondNodeLeaf(int b) const template bool TraversalNodeBase::firstOverSecond(int b1, int b2) const { + FCL_UNUSED(b1); + FCL_UNUSED(b2); + return true; } diff --git a/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h b/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h index 8a8d6ed28..5d9704b34 100644 --- a/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h +++ b/include/fcl/narrowphase/detail/traversal/traversal_recurse-inl.h @@ -42,6 +42,8 @@ #include +#include "fcl/common/unused.h" + namespace fcl { @@ -214,6 +216,13 @@ void collisionRecurse(MeshCollisionTraversalNodeOBB* node, int b1, int b2, co template void collisionRecurse(MeshCollisionTraversalNodeRSS* node, int b1, int b2, const Matrix3& R, const Vector3& T, BVHFrontList* front_list) { + FCL_UNUSED(node); + FCL_UNUSED(b1); + FCL_UNUSED(b2); + FCL_UNUSED(R); + FCL_UNUSED(T); + FCL_UNUSED(front_list); + // Do nothing } diff --git a/test/test_fcl_geometric_shapes.cpp b/test/test_fcl_geometric_shapes.cpp index 84551f2eb..a8663b7af 100755 --- a/test/test_fcl_geometric_shapes.cpp +++ b/test/test_fcl_geometric_shapes.cpp @@ -41,15 +41,20 @@ #include +#include "fcl/common/unused.h" + #include "fcl/math/motion/translation_motion.h" + #include "fcl/geometry/shape/cone.h" #include "fcl/geometry/shape/capsule.h" #include "fcl/geometry/shape/ellipsoid.h" #include "fcl/geometry/shape/halfspace.h" #include "fcl/geometry/shape/plane.h" + #include "fcl/narrowphase/detail/gjk_solver_indep.h" #include "fcl/narrowphase/detail/gjk_solver_libccd.h" #include "fcl/narrowphase/collision.h" + #include "test_fcl_utility.h" using namespace fcl; @@ -234,6 +239,12 @@ bool checkContactPointds(const Shape1& s1, const Transform3& bool check_opposite_normal = false, typename Shape1::S tol = 1e-9) { + FCL_UNUSED(s1); + FCL_UNUSED(tf1); + FCL_UNUSED(s2); + FCL_UNUSED(tf2); + FCL_UNUSED(solver_type); + if (check_position) { bool contact_equal = actual.pos.isApprox(expected.pos, tol); diff --git a/test/test_fcl_utility.h b/test/test_fcl_utility.h index efadbe430..50b0d7caf 100644 --- a/test/test_fcl_utility.h +++ b/test/test_fcl_utility.h @@ -41,13 +41,18 @@ #include #include #include + +#include "fcl/common/unused.h" + #include "fcl/math/constants.h" #include "fcl/math/triangle.h" + #include "fcl/geometry/shape/box.h" #include "fcl/geometry/shape/sphere.h" #include "fcl/geometry/shape/cylinder.h" #include "fcl/geometry/bvh/BVH_model.h" #include "fcl/geometry/octree/octree.h" + #include "fcl/narrowphase/collision.h" #include "fcl/narrowphase/distance.h" #include "fcl/narrowphase/collision_object.h" @@ -123,7 +128,7 @@ S rand_interval(S rmin, S rmax); template void eulerToMatrix(S a, S b, S c, Matrix3& R); -/// @brief Generate one random transform whose translation is constrained by extents and rotation without constraints. +/// @brief Generate one random transform whose translation is constrained by extents and rotation without constraints. /// The translation is (x, y, z), and extents[0] <= x <= extents[3], extents[1] <= y <= extents[4], extents[2] <= z <= extents[5] template void generateRandomTransform(S extents[6], Transform3& transform); @@ -159,7 +164,7 @@ struct DistanceRes Vector3 p2; }; -/// @brief Collision data stores the collision request and the result given by collision algorithm. +/// @brief Collision data stores the collision request and the result given by collision algorithm. template struct CollisionData { @@ -179,7 +184,7 @@ struct CollisionData }; -/// @brief Distance data stores the distance request and the result given by distance algorithm. +/// @brief Distance data stores the distance request and the result given by distance algorithm. template struct DistanceData { @@ -490,6 +495,11 @@ void generateRandomTransforms_ccd(S extents[6], Eigen::aligned_vector>& vertices1, const std::vector& triangles1, const std::vector>& vertices2, const std::vector& triangles2) { + FCL_UNUSED(vertices1); + FCL_UNUSED(triangles1); + FCL_UNUSED(vertices2); + FCL_UNUSED(triangles2); + transforms.resize(n); transforms2.resize(n); @@ -654,6 +664,11 @@ bool defaultContinuousCollisionFunction(ContinuousCollisionObject* o1, Contin template bool defaultContinuousDistanceFunction(ContinuousCollisionObject* o1, ContinuousCollisionObject* o2, void* cdata_, S& dist) { + FCL_UNUSED(o1); + FCL_UNUSED(o2); + FCL_UNUSED(cdata_); + FCL_UNUSED(dist); + return true; }