19 #include <gtest/gtest.h> 20 #include <opencv2/highgui.hpp> 24 #include <object_msgs/ClassifyObject.h> 26 TEST(UnitTestClassification, testImage)
30 client = n.
serviceClient<object_msgs::ClassifyObject>(
"/movidius_ncs_image_multiple/classify_object");
31 object_msgs::ClassifyObject srv;
33 srv.request.image_paths.push_back(
ros::package::getPath(
"movidius_ncs_lib") +
"/../data/images/bicycle.jpg");
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);
41 int main(
int argc,
char** argv)
43 testing::InitGoogleTest(&argc, argv);
44 ros::init(argc, argv,
"movidius_ncs_image_tests");
45 return RUN_ALL_TESTS();
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)