32 #include <gtest/gtest.h> 35 TEST(test_shape_extraction, simple_cube)
38 pcl::PointCloud<pcl::PointXYZRGB> cloud;
57 pcl::PointCloud<pcl::PointXYZRGB> output;
60 pcl::ModelCoefficients::Ptr plane(
new pcl::ModelCoefficients);
61 plane->values.resize(4);
62 plane->values[0] = 0.0;
63 plane->values[1] = 0.0;
64 plane->values[2] = 1.0;
65 plane->values[3] = -0.05;
67 shape_msgs::SolidPrimitive shape;
68 geometry_msgs::Pose
pose;
73 EXPECT_EQ(shape.BOX, shape.type);
74 ASSERT_EQ(3, shape.dimensions.size());
75 EXPECT_FLOAT_EQ(0.05, shape.dimensions[0]);
76 EXPECT_FLOAT_EQ(0.05, shape.dimensions[1]);
77 EXPECT_FLOAT_EQ(0.05, shape.dimensions[2]);
79 EXPECT_FLOAT_EQ(0.225, pose.position.x);
80 EXPECT_FLOAT_EQ(0.125, pose.position.y);
81 EXPECT_FLOAT_EQ(0.075, pose.position.z);
83 EXPECT_FLOAT_EQ(0.0, pose.orientation.x);
84 EXPECT_FLOAT_EQ(0.0, pose.orientation.y);
85 EXPECT_FLOAT_EQ(0.0, pose.orientation.z);
86 EXPECT_FLOAT_EQ(1.0, pose.orientation.w);
90 int main(
int argc,
char **argv)
92 testing::InitGoogleTest(&argc, argv);
93 return RUN_ALL_TESTS();
bool extractShape(const pcl::PointCloud< pcl::PointXYZRGB > &input, pcl::PointCloud< pcl::PointXYZRGB > &output, shape_msgs::SolidPrimitive &shape, geometry_msgs::Pose &pose)
Find the smallest shape primitive we can fit around this object.