unittest_image_classification.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 
19 #include <gtest/gtest.h>
20 #include <opencv2/highgui.hpp>
21 #include <cv_bridge/cv_bridge.h>
22 #include <ros/package.h>
23 #include <ros/ros.h>
24 #include <object_msgs/ClassifyObject.h>
25 
26 TEST(UnitTestClassification, testImage)
27 {
29  ros::ServiceClient client;
30  client = n.serviceClient<object_msgs::ClassifyObject>("/movidius_ncs_image_multiple/classify_object");
31  object_msgs::ClassifyObject srv;
32 
33  srv.request.image_paths.push_back(ros::package::getPath("movidius_ncs_lib") + "/../data/images/bicycle.jpg");
34 
35  client.waitForExistence(ros::Duration(80));
36  EXPECT_TRUE(client.call(srv));
37  EXPECT_TRUE(srv.response.objects[0].objects_vector.size());
38  EXPECT_TRUE(srv.response.objects[0].objects_vector[0].object_name.find("cycle") != std::string::npos);
39 }
40 
41 int main(int argc, char** argv)
42 {
43  testing::InitGoogleTest(&argc, argv);
44  ros::init(argc, argv, "movidius_ncs_image_tests");
45  return RUN_ALL_TESTS();
46 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
TEST(UnitTestClassification, testImage)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ROSLIB_DECL std::string getPath(const std::string &package_name)
int main(int argc, char **argv)


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