22 #include <boost/date_time/posix_time/posix_time.hpp> 24 #include <object_msgs/ClassifyObject.h> 25 #include <opencv2/highgui/highgui.hpp> 26 #include <opencv2/imgproc/imgproc.hpp> 29 #define LINESPACING 30 30 #define MOVEWINDOW 1000 31 #define DEFAULT_PARALLEL_SIZE 1 32 #define DEFAULT_IMAGE_BASE_PATH "/opt/movidius/ncappzoo/data/images/" 33 #define DEFAULT_DEMO_MODE 0 34 #define DEFAULT_PARALLEL_FLAG 1 38 if (image_dir.back() !=
'/')
43 std::vector<std::string> files;
48 if ((dir = opendir(image_dir.c_str())) == NULL)
50 std::cerr <<
"Open Dir error..." << std::endl;
54 while ((ptr = readdir(dir)) != NULL)
56 if (strcmp(ptr->d_name,
".") == 0 || strcmp(ptr->d_name,
"..") == 0)
58 else if (ptr->d_type == DT_REG)
59 files.push_back(image_dir + ptr->d_name);
66 int main(
int argc,
char** argv)
68 ros::init(argc, argv,
"movidius_ncs_example_classification");
73 if (!n.
getParam(
"image_base_path", image_base_path))
75 ROS_WARN(
"param image_base_path not set, use default");
78 std::vector<std::string> image_paths =
getImagePath(image_base_path);
81 if (!n.
getParam(
"parallel_size", parallel_size))
83 ROS_WARN(
"param parallel_size not set, use default");
88 if (!n.
getParam(
"demo_mode", demo_mode))
90 ROS_WARN(
"param demo_mode not set, use default");
95 if (!n.
getParam(
"parallel_flag", parallel_flag))
97 ROS_WARN(
"param parallel_flag not set, use default");
101 if (parallel_flag == 0)
103 client = n.
serviceClient<object_msgs::ClassifyObject>(
"/movidius_ncs_image_single/classify_object");
107 client = n.
serviceClient<object_msgs::ClassifyObject>(
"/movidius_ncs_image_multiple/classify_object");
112 object_msgs::ClassifyObject srv;
113 srv.request.image_paths = image_paths;
114 boost::posix_time::ptime
start = boost::posix_time::microsec_clock::local_time();
115 if (!client.
call(srv))
117 ROS_ERROR(
"failed to call service ClassifyObject");
120 boost::posix_time::ptime end = boost::posix_time::microsec_clock::local_time();
121 boost::posix_time::time_duration msdiff = end - start;
123 for (
unsigned int i = 0; i < srv.response.objects.size(); i++)
126 cv_image.
image = cv::imread(image_paths[i]);
130 ROS_INFO(
"Classification result for image No.%u:", i + 1);
131 for (
unsigned int j = 0; j < srv.response.objects[i].objects_vector.size(); j++)
133 std::stringstream ss;
134 ss << srv.response.objects[i].objects_vector[j].object_name <<
": " 135 << srv.response.objects[i].objects_vector[j].probability * 100 <<
"%";
137 ROS_INFO(
"%d: object: %s\nprobability: %lf%%", j, srv.response.objects[i].objects_vector[j].object_name.c_str(),
138 srv.response.objects[i].objects_vector[j].probability * 100);
141 0.5, cv::Scalar(0, 255, 0), 1);
144 cv::imshow(
"image_classification", cv_image.
image);
147 ROS_INFO(
"inference %lu images during %ld ms", srv.response.objects.size(), msdiff.total_milliseconds());
153 object_msgs::ClassifyObject srv;
154 std::vector<int> random_index_list;
155 for (
int i = 0; i < parallel_size; i++)
157 std::random_device rd;
158 std::default_random_engine engine(rd());
159 std::uniform_int_distribution<> dis(0, image_paths.size() - 1);
160 auto dice = std::bind(dis, engine);
161 int random_index = dice();
162 random_index_list.push_back(random_index);
163 srv.request.image_paths.push_back(image_paths[random_index]);
166 if (!client.
call(srv))
168 ROS_ERROR(
"failed to call service ClassifyObject");
172 for (
unsigned int i = 0; i < srv.response.objects.size(); i++)
175 cv_image.
image = cv::imread(image_paths[random_index_list[i]]);
179 for (
unsigned int j = 0; j < srv.response.objects[i].objects_vector.size(); j++)
181 std::stringstream ss;
182 ss << srv.response.objects[i].objects_vector[j].object_name <<
": " 183 << srv.response.objects[i].objects_vector[j].probability * 100 <<
"%";
186 0.5, cv::Scalar(0, 255, 0), 1);
189 if (parallel_flag == 0)
191 cv::imshow(
"image classification with single device", cv_image.
image);
196 cv::namedWindow(
"image classification with multiple devices");
197 cv::moveWindow(
"image classification with multiple devices",
MOVEWINDOW, 0);
198 cv::imshow(
"image classification with multiple devices", cv_image.
image);
#define DEFAULT_PARALLEL_FLAG
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
#define DEFAULT_IMAGE_BASE_PATH
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
#define DEFAULT_DEMO_MODE
std::vector< std::string > getImagePath(std::string image_dir)
#define ROS_INFO_STREAM(args)
#define DEFAULT_PARALLEL_SIZE
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)