unittest_image_detection.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Intel Corporation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <string>
18 #include <vector>
19 
20 #include <gtest/gtest.h>
21 #include <opencv2/highgui.hpp>
22 #include <cv_bridge/cv_bridge.h>
23 #include <ros/package.h>
24 #include <ros/ros.h>
25 #include <object_msgs/DetectObject.h>
26 
27 TEST(UnitTestDetection, testImage)
28 {
30  ros::ServiceClient client = n.serviceClient<object_msgs::DetectObject>("/movidius_ncs_image_multiple/detect_object");
31  object_msgs::DetectObject srv;
32 
33  std::vector<std::string> image_format = {".jpg", ".jpeg", ".png", ".bmp"};
34  for (std::string suffix : image_format)
35  {
36  srv.request.image_paths.push_back(ros::package::getPath("movidius_ncs_lib") + "/../data/images/bicycle"+suffix);
37 
38  client.waitForExistence(ros::Duration(60));
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);
50  }
51 }
52 
53 int main(int argc, char** argv)
54 {
55  testing::InitGoogleTest(&argc, argv);
56  ros::init(argc, argv, "movidius_ncs_image_tests");
57  return RUN_ALL_TESTS();
58 }
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)


movidius_ncs_image
Author(s): Xiaojun Huang
autogenerated on Mon Jun 10 2019 14:11:26