20 #include <gtest/gtest.h>    25 #include <object_msgs/Object.h>    26 #include <object_msgs/Objects.h>    30 void syncCb(
const sensor_msgs::ImageConstPtr& img,
    31             const object_msgs::Objects::ConstPtr& objs)
    38 TEST(UnitTestStreamClassification, testClassification)
    41   std::string camera, camera_topic;
    45     camera_topic = 
"/usb_cam/image_raw";
    47   else if (camera == 
"realsense")
    49     camera_topic = 
"/camera/color/image_raw";
    55                                                            "/movidius_ncs_nodelet/classified_objects",
    63 int main(
int argc, 
char** argv)
    65   testing::InitGoogleTest(&argc, argv);
    66   ros::init(argc, argv, 
"movidius_ncs_stream_tests");
    67   return RUN_ALL_TESTS();
 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
 
void syncCb(const sensor_msgs::ImageConstPtr &img, const object_msgs::Objects::ConstPtr &objs)
 
ROSCPP_DECL void spin(Spinner &spinner)
 
Connection registerCallback(C &callback)
 
TEST(UnitTestStreamClassification, testClassification)
 
bool getParam(const std::string &key, std::string &s) const 
 
ROSCPP_DECL void shutdown()
 
int main(int argc, char **argv)