Skip to content

Commit

Permalink
Update TYPED_TEST_CASE to TYPED_TEST_SUITE with fallback for older GT…
Browse files Browse the repository at this point in the history
…est versions (#3677)

Co-authored-by:
Aaryaman Vasishta @jammm <jem456.vasishta@gmail.com>
Shrijit Singh @shrijitsingh99 <shrijitsingh99@gmail.com>
  • Loading branch information
shrijitsingh99 authored Feb 26, 2020
1 parent b1d9c7e commit 4316e11
Show file tree
Hide file tree
Showing 20 changed files with 106 additions and 23 deletions.
2 changes: 2 additions & 0 deletions test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ endif()

set_target_properties(tests PROPERTIES FOLDER "Tests")

include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")

add_subdirectory(2d)
add_subdirectory(common)
add_subdirectory(features)
Expand Down
7 changes: 4 additions & 3 deletions test/common/test_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include <pcl/point_cloud.h>

#include <pcl/common/centroid.h>
#include <pcl/test/gtest.h>

using namespace pcl;

Expand Down Expand Up @@ -308,7 +309,7 @@ TEST (PCL, PointTypes)

template <typename T> class XYZPointTypesTest : public ::testing::Test { };
using XYZPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM(PCL_XYZ_POINT_TYPES)>;
TYPED_TEST_CASE(XYZPointTypesTest, XYZPointTypes);
TYPED_TEST_SUITE(XYZPointTypesTest, XYZPointTypes);
TYPED_TEST(XYZPointTypesTest, GetVectorXfMap)
{
TypeParam pt;
Expand All @@ -329,7 +330,7 @@ TYPED_TEST(XYZPointTypesTest, GetArrayXfMap)

template <typename T> class NormalPointTypesTest : public ::testing::Test { };
using NormalPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM(PCL_NORMAL_POINT_TYPES)>;
TYPED_TEST_CASE(NormalPointTypesTest, NormalPointTypes);
TYPED_TEST_SUITE(NormalPointTypesTest, NormalPointTypes);
TYPED_TEST(NormalPointTypesTest, GetNormalVectorXfMap)
{
TypeParam pt;
Expand All @@ -341,7 +342,7 @@ TYPED_TEST(NormalPointTypesTest, GetNormalVectorXfMap)

template <typename T> class RGBPointTypesTest : public ::testing::Test { };
using RGBPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM(PCL_RGB_POINT_TYPES)>;
TYPED_TEST_CASE(RGBPointTypesTest, RGBPointTypes);
TYPED_TEST_SUITE(RGBPointTypesTest, RGBPointTypes);
TYPED_TEST(RGBPointTypesTest, GetRGBVectorXi)
{
TypeParam pt; pt.r = 1; pt.g = 2; pt.b = 3; pt.a = 4;
Expand Down
3 changes: 2 additions & 1 deletion test/common/test_geometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,14 @@
#include <gtest/gtest.h>
#include <pcl/common/geometry.h>
#include <pcl/point_types.h>
#include <pcl/test/gtest.h>

using namespace pcl;

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T> class XYZPointTypesTest : public ::testing::Test { };
using XYZPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM(PCL_XYZ_POINT_TYPES)>;
TYPED_TEST_CASE(XYZPointTypesTest, XYZPointTypes);
TYPED_TEST_SUITE(XYZPointTypesTest, XYZPointTypes);

TYPED_TEST(XYZPointTypesTest, Distance)
{
Expand Down
3 changes: 2 additions & 1 deletion test/common/test_transforms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
#include <pcl/common/io.h>

#include <pcl/pcl_tests.h>
#include <pcl/test/gtest.h>

using namespace pcl;

Expand Down Expand Up @@ -107,7 +108,7 @@ class Transforms : public ::testing::Test
PCL_MAKE_ALIGNED_OPERATOR_NEW;
};

TYPED_TEST_CASE (Transforms, TransformTypes);
TYPED_TEST_SUITE (Transforms, TransformTypes);

TYPED_TEST (Transforms, PointCloudXYZDense)
{
Expand Down
1 change: 0 additions & 1 deletion test/common/test_type_traits.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
*/


#include <pcl/pcl_macros.h>

This comment has been minimized.

Copy link
@aPonza

aPonza Feb 27, 2020

Contributor

This change is actually masking the inclusion for the definition for PCL_MAKE_ALIGNED_OPERATOR_NEW, it's now included transitively via point_traits.h. This change should be implicitly fixed by #3654 due to the memory.h addition.

#include <pcl/point_traits.h>
#include <pcl/point_types.h>

Expand Down
3 changes: 2 additions & 1 deletion test/features/test_pfh_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
#include <pcl/features/vfh.h>
#include <pcl/features/gfpfh.h>
#include <pcl/io/pcd_io.h>
#include <pcl/test/gtest.h>

using PointT = pcl::PointNormal;
using KdTreePtr = pcl::search::KdTree<PointT>::Ptr;
Expand Down Expand Up @@ -294,7 +295,7 @@ struct FPFHTest<FPFHEstimationOMP<PointT, PointT, FPFHSignature33> >
using FPFHEstimatorTypes = ::testing::Types
<FPFHEstimation<PointT, PointT, FPFHSignature33>,
FPFHEstimationOMP<PointT, PointT, FPFHSignature33> >;
TYPED_TEST_CASE (FPFHTest, FPFHEstimatorTypes);
TYPED_TEST_SUITE (FPFHTest, FPFHEstimatorTypes);

// This is a copy of the old FPFHEstimation test which will now
// be applied to both FPFHEstimation and FPFHEstimationOMP
Expand Down
5 changes: 3 additions & 2 deletions test/features/test_shot_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
#include "pcl/features/shot_lrf.h"
#include <pcl/features/3dsc.h>
#include <pcl/features/usc.h>
#include <pcl/test/gtest.h>

using namespace pcl;
using namespace pcl::io;
Expand Down Expand Up @@ -371,7 +372,7 @@ struct SHOTShapeTest<SHOTEstimationOMP<PointXYZ, Normal, SHOT352> >
using SHOTEstimatorTypes = ::testing::Types
<SHOTEstimation<PointXYZ, Normal, SHOT352>,
SHOTEstimationOMP<PointXYZ, Normal, SHOT352> >;
TYPED_TEST_CASE (SHOTShapeTest, SHOTEstimatorTypes);
TYPED_TEST_SUITE (SHOTShapeTest, SHOTEstimatorTypes);

// This is a copy of the old SHOTShapeEstimation test which will now
// be applied to both SHOTEstimation and SHOTEstimationOMP
Expand Down Expand Up @@ -560,7 +561,7 @@ struct SHOTShapeAndColorTest<SHOTColorEstimationOMP<PointXYZRGBA, Normal, SHOT13
using SHOTColorEstimatorTypes= ::testing::Types
<SHOTColorEstimation<PointXYZRGBA, Normal, SHOT1344>,
SHOTColorEstimationOMP<PointXYZRGBA, Normal, SHOT1344> >;
TYPED_TEST_CASE (SHOTShapeAndColorTest, SHOTColorEstimatorTypes);
TYPED_TEST_SUITE (SHOTShapeAndColorTest, SHOTColorEstimatorTypes);

// This is a copy of the old SHOTShapeAndColorEstimation test which will now
// be applied to both SHOTColorEstimation and SHOTColorEstimationOMP
Expand Down
3 changes: 2 additions & 1 deletion test/geometry/test_mesh_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
#include <pcl/pcl_macros.h>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/test/gtest.h>

#include "test_mesh_common_functions.h"

Expand Down Expand Up @@ -152,7 +153,7 @@ using NonManifoldMeshTraits = MeshTraits<false>;

using MeshTraitsTypes = testing::Types <ManifoldMeshTraits, NonManifoldMeshTraits>;

TYPED_TEST_CASE (TestMeshConversion, MeshTraitsTypes);
TYPED_TEST_SUITE (TestMeshConversion, MeshTraitsTypes);

////////////////////////////////////////////////////////////////////////////////

Expand Down
3 changes: 2 additions & 1 deletion test/geometry/test_mesh_get_boundary.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@

#include <pcl/geometry/polygon_mesh.h>
#include <pcl/geometry/get_boundary.h>
#include <pcl/test/gtest.h>
#include "test_mesh_common_functions.h"

////////////////////////////////////////////////////////////////////////////////
Expand All @@ -68,7 +69,7 @@ class TestGetBoundary : public testing::Test
using Mesh = MeshT;
};

TYPED_TEST_CASE (TestGetBoundary, MeshTypes);
TYPED_TEST_SUITE (TestGetBoundary, MeshTypes);

////////////////////////////////////////////////////////////////////////////////

Expand Down
3 changes: 2 additions & 1 deletion test/geometry/test_mesh_indices.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <gtest/gtest.h>

#include <pcl/geometry/mesh_indices.h>
#include <pcl/test/gtest.h>

////////////////////////////////////////////////////////////////////////////////

Expand All @@ -63,7 +64,7 @@ class TestMeshIndicesTyped : public testing::Test

using MeshIndexTypes = testing::Types <VertexIndex, HalfEdgeIndex, EdgeIndex, FaceIndex>;

TYPED_TEST_CASE (TestMeshIndicesTyped, MeshIndexTypes);
TYPED_TEST_SUITE (TestMeshIndicesTyped, MeshIndexTypes);

////////////////////////////////////////////////////////////////////////////////

Expand Down
3 changes: 2 additions & 1 deletion test/geometry/test_polygon_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <gtest/gtest.h>

#include <pcl/geometry/polygon_mesh.h>
#include <pcl/test/gtest.h>

#include "test_mesh_common_functions.h"

Expand Down Expand Up @@ -82,7 +83,7 @@ class TestPolygonMesh : public testing::Test
using Mesh = MeshT;
};

TYPED_TEST_CASE (TestPolygonMesh, PolygonMeshTypes);
TYPED_TEST_SUITE (TestPolygonMesh, PolygonMeshTypes);

////////////////////////////////////////////////////////////////////////////////

Expand Down
3 changes: 2 additions & 1 deletion test/geometry/test_quad_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <gtest/gtest.h>

#include <pcl/geometry/quad_mesh.h>
#include <pcl/test/gtest.h>

#include "test_mesh_common_functions.h"

Expand Down Expand Up @@ -80,7 +81,7 @@ class TestQuadMesh : public testing::Test
using Mesh = MeshT;
};

TYPED_TEST_CASE (TestQuadMesh, QuadMeshTypes);
TYPED_TEST_SUITE (TestQuadMesh, QuadMeshTypes);

////////////////////////////////////////////////////////////////////////////////

Expand Down
3 changes: 2 additions & 1 deletion test/geometry/test_triangle_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <gtest/gtest.h>

#include <pcl/geometry/triangle_mesh.h>
#include <pcl/test/gtest.h>

#include "test_mesh_common_functions.h"

Expand Down Expand Up @@ -80,7 +81,7 @@ class TestTriangleMesh : public testing::Test
using Mesh = MeshT;
};

TYPED_TEST_CASE (TestTriangleMesh, TriangleMeshTypes);
TYPED_TEST_SUITE (TestTriangleMesh, TriangleMeshTypes);

////////////////////////////////////////////////////////////////////////////////

Expand Down
65 changes: 65 additions & 0 deletions test/include/pcl/test/gtest.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
/*
* Software License Agreement (BSD License)
*
* Point Cloud Library (PCL) - www.pointclouds.org
* Copyright (c) 2019-, Open Perception, Inc.
*
* 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 the copyright holder(s) 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.
*/

#pragma once

#include <gtest/gtest.h>

/**
* \file pcl/test/gtest.h
*
* \brief Defines all the PCL test macros used
* \ingroup test
*/

/**
* \brief Macro choose between TYPED_TEST_CASE and TYPED_TEST_SUITE depending on the GTest version
*
* \ingroup test
*/
#if !defined(TYPED_TEST_SUITE)
#define TYPED_TEST_SUITE TYPED_TEST_CASE
#endif

/**
* \brief Macro choose between INSTANTIATE_TEST_CASE_P and INSTANTIATE_TEST_SUITE_P depending on the GTest version
*
* \ingroup test
*/
#if !defined(INSTANTIATE_TEST_SUITE_P)
#define INSTANTIATE_TEST_SUITE_P INSTANTIATE_TEST_CASE_P
#endif

3 changes: 2 additions & 1 deletion test/io/test_buffers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <cstdint>

#include <pcl/io/buffers.h>
#include <pcl/test/gtest.h>

using namespace pcl::io;

Expand Down Expand Up @@ -84,7 +85,7 @@ class BuffersTest : public ::testing::Test
};

using DataTypes = ::testing::Types<std::int8_t, std::int32_t, float>;
TYPED_TEST_CASE (BuffersTest, DataTypes);
TYPED_TEST_SUITE (BuffersTest, DataTypes);

TYPED_TEST (BuffersTest, SingleBuffer)
{
Expand Down
3 changes: 2 additions & 1 deletion test/io/test_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include <pcl/io/ply_io.h>
#include <pcl/io/ascii_io.h>
#include <pcl/io/obj_io.h>
#include <pcl/test/gtest.h>
#include <fstream>
#include <locale>
#include <stdexcept>
Expand Down Expand Up @@ -1319,7 +1320,7 @@ TEST (PCL, Locale)
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T> class AutoIOTest : public testing::Test { };
using PCLXyzNormalPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM (PCL_XYZ_POINT_TYPES PCL_NORMAL_POINT_TYPES)>;
TYPED_TEST_CASE (AutoIOTest, PCLXyzNormalPointTypes);
TYPED_TEST_SUITE (AutoIOTest, PCLXyzNormalPointTypes);
TYPED_TEST (AutoIOTest, AutoLoadCloudFiles)
{
PointCloud<TypeParam> cloud;
Expand Down
7 changes: 4 additions & 3 deletions test/io/test_ply_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <gtest/gtest.h>
#include <pcl/test/gtest.h>

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
TEST (PCL, PLYReaderWriter)
Expand Down Expand Up @@ -288,7 +289,7 @@ TEST_F (PLYColorTest, LoadPLYFileColoredASCIIIntoPolygonMesh)
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T> class PLYPointCloudTest : public PLYColorTest { };
using RGBPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM (PCL_RGB_POINT_TYPES)>;
TYPED_TEST_CASE (PLYPointCloudTest, RGBPointTypes);
TYPED_TEST_SUITE (PLYPointCloudTest, RGBPointTypes);
TYPED_TEST (PLYPointCloudTest, LoadPLYFileColoredASCIIIntoPointCloud)
{
int res;
Expand Down Expand Up @@ -316,7 +317,7 @@ template<typename T>
struct PLYCoordinatesIsDenseTest : public PLYTest {};

using XYZPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM (PCL_XYZ_POINT_TYPES)>;
TYPED_TEST_CASE (PLYCoordinatesIsDenseTest, XYZPointTypes);
TYPED_TEST_SUITE (PLYCoordinatesIsDenseTest, XYZPointTypes);

TYPED_TEST (PLYCoordinatesIsDenseTest, NaNInCoordinates)
{
Expand Down Expand Up @@ -410,7 +411,7 @@ template<typename T>
struct PLYNormalsIsDenseTest : public PLYTest {};

using NormalPointTypes = ::testing::Types<BOOST_PP_SEQ_ENUM (PCL_NORMAL_POINT_TYPES)>;
TYPED_TEST_CASE (PLYNormalsIsDenseTest, NormalPointTypes);
TYPED_TEST_SUITE (PLYNormalsIsDenseTest, NormalPointTypes);

TYPED_TEST (PLYNormalsIsDenseTest, NaNInNormals)
{
Expand Down
3 changes: 2 additions & 1 deletion test/octree/test_octree_iterator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <pcl/common/projection_matrix.h>
#include <pcl/point_types.h>
#include <gtest/gtest.h>
#include <pcl/test/gtest.h>

using pcl::octree::OctreeBase;
using pcl::octree::OctreeIteratorBase;
Expand Down Expand Up @@ -154,7 +155,7 @@ using OctreeIteratorTypes = testing::Types
OctreeLeafNodeDepthFirstIterator<OctreeBase<int> >,
OctreeFixedDepthIterator<OctreeBase<int> >,
OctreeLeafNodeBreadthFirstIterator<OctreeBase<int> > >;
TYPED_TEST_CASE (OctreeIteratorTest, OctreeIteratorTypes);
TYPED_TEST_SUITE (OctreeIteratorTest, OctreeIteratorTypes);

TYPED_TEST (OctreeIteratorTest, CopyConstructor)
{
Expand Down
3 changes: 2 additions & 1 deletion test/sample_consensus/test_sample_consensus.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include <pcl/sample_consensus/ransac.h>
#include <pcl/sample_consensus/rransac.h>
#include <pcl/sample_consensus/sac_model_sphere.h>
#include <pcl/test/gtest.h>

#include <chrono>
#include <condition_variable>
Expand Down Expand Up @@ -92,7 +93,7 @@ using sacTypes = ::testing::Types<
RandomizedMEstimatorSampleConsensus<PointXYZ>,
MaximumLikelihoodSampleConsensus<PointXYZ>
>;
TYPED_TEST_CASE(SacTest, sacTypes);
TYPED_TEST_SUITE(SacTest, sacTypes);

TYPED_TEST(SacTest, InfiniteLoop)
{
Expand Down
Loading

0 comments on commit 4316e11

Please sign in to comment.