34 #include <gtest/gtest.h> 41 pcl::PointCloud<pcl::PointXYZ> pc;
42 for (
float y = -1.0;
y < 1.0;
y += 0.1)
44 for (
float z = -1.0;
z < 1.0;
z += 0.1)
46 pc.push_back(pcl::PointXYZ(0.5,
y,
z));
52 for (
float y = -0.8;
y < 0.8;
y += 0.11)
54 for (
float z = -0.8;
z < 0.8;
z += 0.13)
56 bool collision =
false;
60 for (
auto point : ray)
69 ASSERT_TRUE(collision);
72 for (
float y = -1.0;
y < 1.0;
y += 0.11)
74 for (
float z = -1.0;
z < 1.0;
z += 0.13)
76 bool collision =
false;
80 for (
auto point : ray)
85 ASSERT_FALSE(collision);
89 bool collision =
false;
93 for (
auto point : ray)
98 ASSERT_FALSE(collision);
102 TEST(Raycast, CollisionTolerance)
104 pcl::PointCloud<pcl::PointXYZ> pc;
105 for (
float y = -1.0;
y < 1.0;
y += 0.05)
107 for (
float z = -1.0;
z < 1.0;
z += 0.1)
109 pc.push_back(pcl::PointXYZ(0.5,
y,
z));
116 bool collision =
false;
120 for (
auto point : ray)
122 if (point.collision_)
128 ASSERT_TRUE(collision);
131 bool collision =
false;
135 for (
auto point : ray)
137 if (point.collision_)
143 ASSERT_FALSE(collision);
146 bool collision =
false;
150 for (
auto point : ray)
152 if (point.collision_)
158 ASSERT_FALSE(collision);
163 pcl::PointCloud<pcl::PointXYZ> pc;
164 for (
float y = -1.0;
y < 1.0;
y += 0.1)
166 for (
float z = -1.0;
z < 1.0;
z += 0.1)
168 pc.push_back(pcl::PointXYZ(0.5,
y,
z));
175 bool collision =
false;
179 for (
auto point : ray)
181 if (point.collision_)
183 EXPECT_NEAR(point.sin_angle_, 1.0, 0.1);
188 ASSERT_TRUE(collision);
191 bool collision =
false;
195 for (
auto point : ray)
197 if (point.collision_)
199 EXPECT_NEAR(point.sin_angle_, sinf(0.5 / 5.0), 0.05);
204 ASSERT_TRUE(collision);
207 bool collision =
false;
211 for (
auto point : ray)
213 if (point.collision_)
215 EXPECT_NEAR(point.sin_angle_, sinf(0.5 / 3.0), 0.05);
220 ASSERT_TRUE(collision);
224 int main(
int argc,
char** argv)
226 testing::InitGoogleTest(&argc, argv);
228 return RUN_ALL_TESTS();
std::shared_ptr< ChunkedKdtree > Ptr
TFSIMD_FORCE_INLINE const tfScalar & y() const
int main(int argc, char **argv)
void setInputCloud(const typename pcl::PointCloud< POINT_TYPE >::ConstPtr cloud)
TFSIMD_FORCE_INLINE const tfScalar & z() const