Skip to content

Commit fe61e23

Browse files
author
Acorn
committed
add unit tests for computeShapeBoundingSphere()
1 parent f69f624 commit fe61e23

File tree

1 file changed

+280
-0
lines changed

1 file changed

+280
-0
lines changed

test/test_bounding_sphere.cpp

+280
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,280 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2013, Willow Garage, Inc.
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of the Willow Garage nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
35+
/** \Author Acorn Pooley */
36+
37+
#include <geometric_shapes/bodies.h>
38+
#include <geometric_shapes/shape_operations.h>
39+
#include <geometric_shapes/body_operations.h>
40+
#include <boost/filesystem.hpp>
41+
#include <gtest/gtest.h>
42+
43+
44+
TEST(SphereBoundingSphere, Sphere1)
45+
{
46+
shapes::Sphere shape(1.0);
47+
Eigen::Vector3d center;
48+
double radius;
49+
computeShapeBoundingSphere(&shape, center, radius);
50+
51+
EXPECT_EQ(1.0, radius);
52+
EXPECT_EQ(0.0, center.x());
53+
EXPECT_EQ(0.0, center.y());
54+
EXPECT_EQ(0.0, center.z());
55+
}
56+
57+
TEST(SphereBoundingSphere, Sphere2)
58+
{
59+
shapes::Shape *shape = new shapes::Sphere(2.0);
60+
Eigen::Vector3d center;
61+
double radius;
62+
computeShapeBoundingSphere(shape, center, radius);
63+
64+
EXPECT_EQ(2.0, radius);
65+
EXPECT_EQ(0.0, center.x());
66+
EXPECT_EQ(0.0, center.y());
67+
EXPECT_EQ(0.0, center.z());
68+
delete shape;
69+
}
70+
71+
TEST(BoxBoundingSphere, Box1)
72+
{
73+
shapes::Shape *shape = new shapes::Box(2.0, 4.0, 6.0);
74+
Eigen::Vector3d center;
75+
double radius;
76+
computeShapeBoundingSphere(shape, center, radius);
77+
78+
EXPECT_EQ(sqrt(14.0), radius);
79+
EXPECT_EQ(0.0, center.x());
80+
EXPECT_EQ(0.0, center.y());
81+
EXPECT_EQ(0.0, center.z());
82+
}
83+
84+
TEST(BoxBoundingSphere, Box2)
85+
{
86+
shapes::Shape *shape = new shapes::Box(2.0, 2.0, 2.0);
87+
Eigen::Vector3d center;
88+
double radius;
89+
computeShapeBoundingSphere(shape, center, radius);
90+
91+
EXPECT_EQ(sqrt(3.0), radius);
92+
EXPECT_EQ(0.0, center.x());
93+
EXPECT_EQ(0.0, center.y());
94+
EXPECT_EQ(0.0, center.z());
95+
}
96+
97+
TEST(CylBoundingSphere, Cyl1)
98+
{
99+
shapes::Shape *shape = new shapes::Cylinder(1.0, 4.0);
100+
Eigen::Vector3d center;
101+
double radius;
102+
computeShapeBoundingSphere(shape, center, radius);
103+
104+
EXPECT_EQ(sqrt(1+4), radius);
105+
EXPECT_EQ(0.0, center.x());
106+
EXPECT_EQ(0.0, center.y());
107+
EXPECT_EQ(0.0, center.z());
108+
}
109+
110+
TEST(CylBoundingSphere, Cyl2)
111+
{
112+
shapes::Shape *shape = new shapes::Cylinder(2.0, 20.0);
113+
Eigen::Vector3d center;
114+
double radius;
115+
computeShapeBoundingSphere(shape, center, radius);
116+
117+
EXPECT_EQ(sqrt(4+100), radius);
118+
EXPECT_EQ(0.0, center.x());
119+
EXPECT_EQ(0.0, center.y());
120+
EXPECT_EQ(0.0, center.z());
121+
}
122+
123+
TEST(ConeBoundingSphere, Cone1)
124+
{
125+
shapes::Shape *shape = new shapes::Cone(20.0, 2.0);
126+
Eigen::Vector3d center;
127+
double radius;
128+
computeShapeBoundingSphere(shape, center, radius);
129+
130+
EXPECT_EQ(20.0, radius);
131+
EXPECT_EQ(0.0, center.x());
132+
EXPECT_EQ(0.0, center.y());
133+
EXPECT_EQ(-1.0, center.z());
134+
}
135+
136+
TEST(ConeBoundingSphere, Cone2)
137+
{
138+
shapes::Shape *shape = new shapes::Cone(5.0, 5.0);
139+
Eigen::Vector3d center;
140+
double radius;
141+
computeShapeBoundingSphere(shape, center, radius);
142+
143+
EXPECT_EQ(5.0, radius);
144+
EXPECT_EQ(0.0, center.x());
145+
EXPECT_EQ(0.0, center.y());
146+
EXPECT_EQ(-2.5, center.z());
147+
}
148+
149+
TEST(ConeBoundingSphere, Cone3)
150+
{
151+
double height = 1.0 + 1.0/sqrt(2);
152+
shapes::Shape *shape = new shapes::Cone(1/sqrt(2), height);
153+
Eigen::Vector3d center;
154+
double radius;
155+
computeShapeBoundingSphere(shape, center, radius);
156+
157+
EXPECT_EQ(1.0, radius);
158+
EXPECT_EQ(0.0, center.x());
159+
EXPECT_EQ(0.0, center.y());
160+
EXPECT_EQ(height/2 - 1, center.z());
161+
}
162+
163+
TEST(ConeBoundingSphere, Cone4)
164+
{
165+
shapes::Shape *shape = new shapes::Cone(3, 10);
166+
Eigen::Vector3d center;
167+
double radius;
168+
computeShapeBoundingSphere(shape, center, radius);
169+
170+
EXPECT_EQ(109.0/20, radius);
171+
EXPECT_EQ(0.0, center.x());
172+
EXPECT_EQ(0.0, center.y());
173+
EXPECT_EQ(5 - (109.0/20), center.z());
174+
}
175+
176+
TEST(MeshBoundingSphere, Mesh1)
177+
{
178+
shapes::Shape *shape = new shapes::Mesh(8, 12);
179+
shapes::Mesh *m = dynamic_cast<shapes::Mesh*>(shape);
180+
EXPECT_TRUE(m);
181+
182+
// box mesh
183+
184+
m->vertices[3*0 + 0] = 0;
185+
m->vertices[3*0 + 1] = 0;
186+
m->vertices[3*0 + 2] = 0;
187+
188+
m->vertices[3*1 + 0] = 1;
189+
m->vertices[3*1 + 1] = 0;
190+
m->vertices[3*1 + 2] = 0;
191+
192+
m->vertices[3*2 + 0] = 0;
193+
m->vertices[3*2 + 1] = 1;
194+
m->vertices[3*2 + 2] = 0;
195+
196+
m->vertices[3*3 + 0] = 1;
197+
m->vertices[3*3 + 1] = 1;
198+
m->vertices[3*3 + 2] = 0;
199+
200+
m->vertices[3*4 + 0] = 0;
201+
m->vertices[3*4 + 1] = 0;
202+
m->vertices[3*4 + 2] = 1;
203+
204+
m->vertices[3*5 + 0] = 1;
205+
m->vertices[3*5 + 1] = 0;
206+
m->vertices[3*5 + 2] = 1;
207+
208+
m->vertices[3*6 + 0] = 0;
209+
m->vertices[3*6 + 1] = 1;
210+
m->vertices[3*6 + 2] = 1;
211+
212+
m->vertices[3*7 + 0] = 1;
213+
m->vertices[3*7 + 1] = 1;
214+
m->vertices[3*7 + 2] = 1;
215+
216+
217+
m->triangles[3*0 + 0] = 0;
218+
m->triangles[3*0 + 1] = 1;
219+
m->triangles[3*0 + 2] = 2;
220+
221+
m->triangles[3*1 + 0] = 1;
222+
m->triangles[3*1 + 1] = 3;
223+
m->triangles[3*1 + 2] = 2;
224+
225+
m->triangles[3*2 + 0] = 5;
226+
m->triangles[3*2 + 1] = 4;
227+
m->triangles[3*2 + 2] = 6;
228+
229+
m->triangles[3*3 + 0] = 5;
230+
m->triangles[3*3 + 1] = 6;
231+
m->triangles[3*3 + 2] = 7;
232+
233+
m->triangles[3*4 + 0] = 1;
234+
m->triangles[3*4 + 1] = 5;
235+
m->triangles[3*4 + 2] = 3;
236+
237+
m->triangles[3*5 + 0] = 5;
238+
m->triangles[3*5 + 1] = 7;
239+
m->triangles[3*5 + 2] = 3;
240+
241+
m->triangles[3*6 + 0] = 4;
242+
m->triangles[3*6 + 1] = 0;
243+
m->triangles[3*6 + 2] = 2;
244+
245+
m->triangles[3*7 + 0] = 4;
246+
m->triangles[3*7 + 1] = 2;
247+
m->triangles[3*7 + 2] = 6;
248+
249+
m->triangles[3*8 + 0] = 2;
250+
m->triangles[3*8 + 1] = 3;
251+
m->triangles[3*8 + 2] = 6;
252+
253+
m->triangles[3*9 + 0] = 3;
254+
m->triangles[3*9 + 1] = 7;
255+
m->triangles[3*9 + 2] = 6;
256+
257+
m->triangles[3*10 + 0] = 1;
258+
m->triangles[3*10 + 1] = 0;
259+
m->triangles[3*10 + 2] = 4;
260+
261+
m->triangles[3*11 + 0] = 1;
262+
m->triangles[3*11 + 1] = 4;
263+
m->triangles[3*11 + 2] = 5;
264+
265+
266+
Eigen::Vector3d center;
267+
double radius;
268+
computeShapeBoundingSphere(shape, center, radius);
269+
270+
EXPECT_EQ(sqrt(0.75), radius);
271+
EXPECT_EQ(0.5, center.x());
272+
EXPECT_EQ(0.5, center.y());
273+
EXPECT_EQ(0.5, center.z());
274+
}
275+
276+
int main(int argc, char **argv)
277+
{
278+
testing::InitGoogleTest(&argc, argv);
279+
return RUN_ALL_TESTS();
280+
}

0 commit comments

Comments
 (0)