20 #include <gtest/gtest.h> 21 #include <opencv2/highgui.hpp> 25 #include <object_msgs/DetectObject.h> 27 TEST(UnitTestDetection, testImage)
31 object_msgs::DetectObject srv;
33 std::vector<std::string> image_format = {
".jpg",
".jpeg",
".png",
".bmp"};
34 for (std::string suffix : image_format)
36 srv.request.image_paths.push_back(
ros::package::getPath(
"movidius_ncs_lib") +
"/../data/images/bicycle"+suffix);
39 EXPECT_TRUE(client.
call(srv));
40 EXPECT_TRUE(srv.response.objects[0].objects_vector.size());
41 EXPECT_EQ(srv.response.objects[0].objects_vector[0].object.object_name,
"bicycle");
42 EXPECT_TRUE(srv.response.objects[0].objects_vector[0].roi.x_offset > 130 &&
43 srv.response.objects[0].objects_vector[0].roi.x_offset < 150 &&
44 srv.response.objects[0].objects_vector[0].roi.y_offset > 90 &&
45 srv.response.objects[0].objects_vector[0].roi.y_offset < 110 &&
46 srv.response.objects[0].objects_vector[0].roi.width > 410 &&
47 srv.response.objects[0].objects_vector[0].roi.width < 470 &&
48 srv.response.objects[0].objects_vector[0].roi.height > 340 &&
49 srv.response.objects[0].objects_vector[0].roi.height < 360);
53 int main(
int argc,
char** argv)
55 testing::InitGoogleTest(&argc, argv);
56 ros::init(argc, argv,
"movidius_ncs_image_tests");
57 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
int main(int argc, char **argv)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ROSLIB_DECL std::string getPath(const std::string &package_name)
TEST(UnitTestDetection, testImage)