Skip to content
This repository has been archived by the owner on Jan 7, 2023. It is now read-only.

Multiple ncs refactoring #66

Merged
merged 21 commits into from
Mar 22, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file added data/images/bicycle.bmp
Binary file not shown.
Binary file added data/images/bicycle.jpeg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added data/images/bicycle.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
34 changes: 28 additions & 6 deletions movidius_ncs_example/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
# Copyright (c) 2017 Intel Corporation
#
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#
# http://www.apache.org/licenses/LICENSE-2.0
#
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
Expand Down Expand Up @@ -42,13 +42,15 @@ add_executable(${PROJECT_NAME}_image_classification src/image_classification.cpp
add_executable(${PROJECT_NAME}_image_detection src/image_detection.cpp)
add_executable(${PROJECT_NAME}_stream_classification src/stream_classification.cpp)
add_executable(${PROJECT_NAME}_stream_detection src/stream_detection.cpp)
add_executable(${PROJECT_NAME}_single_device_classification src/single_device_classification.cpp)
add_executable(${PROJECT_NAME}_multiple_devices_classification src/multiple_devices_classification.cpp)

add_dependencies(${PROJECT_NAME}_image_classification
${${PROJECT_NAME}_EXPORTED_TARGETS}
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS})

add_dependencies(${PROJECT_NAME}_image_detection
${${PROJECT_NAME}_EXPORTED_TARGETS}
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS})

add_dependencies(${PROJECT_NAME}_stream_classification
Expand All @@ -59,6 +61,14 @@ add_dependencies(${PROJECT_NAME}_stream_detection
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS})

add_dependencies(${PROJECT_NAME}_single_device_classification
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS})

add_dependencies(${PROJECT_NAME}_multiple_devices_classification
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS})

target_link_libraries(${PROJECT_NAME}_image_classification
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
Expand All @@ -78,6 +88,17 @@ target_link_libraries(${PROJECT_NAME}_stream_detection
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
)

target_link_libraries(${PROJECT_NAME}_single_device_classification
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
)

target_link_libraries(${PROJECT_NAME}_multiple_devices_classification
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
)

# Flags
if(UNIX OR APPLE)
# Linker flags.
Expand Down Expand Up @@ -119,7 +140,8 @@ if(UNIX OR APPLE)
endif()

install(TARGETS ${PROJECT_NAME}_image_classification ${PROJECT_NAME}_image_detection
${PROJECT_NAME}_stream_classification ${PROJECT_NAME}_stream_detection
${PROJECT_NAME}_stream_classification ${PROJECT_NAME}_stream_detection ${PROJECT_NAME}_single_device_classification
${PROJECT_NAME}_multiple_devices_classification
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
Expand Down
82 changes: 71 additions & 11 deletions movidius_ncs_example/src/image_classification.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,48 @@

#include <opencv2/highgui.hpp>
#include <cv_bridge/cv_bridge.h>

#include <ros/ros.h>
#include <object_msgs/ClassifyObject.h>

#include <vector>
#include <dirent.h>

#include <boost/date_time/posix_time/posix_time.hpp>
#include <chrono>

#define LINESPACING 30

std::vector<std::string> getImagePath(std::string image_dir)
{
if (image_dir.back() != '/')
{
image_dir += "/";
}

std::vector<std::string> files;

DIR* dir;
struct dirent* ptr;

if ((dir = opendir(image_dir.c_str())) == NULL)
{
perror("Open Dir error...");
exit(1);
}

while ((ptr = readdir(dir)) != NULL)
{
if (strcmp(ptr->d_name, ".") == 0 || strcmp(ptr->d_name, "..") == 0)
continue;
else if (ptr->d_type == 8)
files.push_back(image_dir + ptr->d_name);
}
closedir(dir);

return files;
}

int main(int argc, char** argv)
{
ros::init(argc, argv, "movidius_ncs_example");
Expand All @@ -29,31 +68,52 @@ int main(int argc, char** argv)
return -1;
}

std::vector<std::string> images_path = getImagePath(*(argv + 1));

ros::NodeHandle n;
ros::ServiceClient client;
client = n.serviceClient<object_msgs::ClassifyObject>("/movidius_ncs_image/classify_object");
object_msgs::ClassifyObject srv;

cv_bridge::CvImage cv_image;
sensor_msgs::Image ros_image;
cv_image.image = cv::imread(argv[1]);
cv_image.encoding = "bgr8";
cv_image.toImageMsg(ros_image);
srv.request.image = ros_image;
srv.request.images_path = images_path;

boost::posix_time::ptime start = boost::posix_time::microsec_clock::local_time();

if (!client.call(srv))
{
ROS_ERROR("failed to call service ClassifyObject");
return 1;
}

for (unsigned int i = 0; i < srv.response.objects.objects_vector.size(); i++)
boost::posix_time::ptime end = boost::posix_time::microsec_clock::local_time();
boost::posix_time::time_duration msdiff = end - start;

for (unsigned int i = 0; i < srv.response.objects.size(); i++)
{
ROS_INFO("%d: object: %s\nprobability: %lf%%", i,
srv.response.objects.objects_vector[i].object_name.c_str(),
srv.response.objects.objects_vector[i].probability * 100);
cv_bridge::CvImage cv_image;
cv_image.image = cv::imread(images_path[i]);
cv_image.encoding = "bgr8";
int cnt = 0;

ROS_INFO("Classification result for image No.%u:", i + 1);
for (unsigned int j = 0; j < srv.response.objects[i].objects_vector.size(); j++)
{
std::stringstream ss;
ss << srv.response.objects[i].objects_vector[j].object_name << ": "
<< srv.response.objects[i].objects_vector[j].probability * 100 << "%";

ROS_INFO("%d: object: %s\nprobability: %lf%%", j, srv.response.objects[i].objects_vector[j].object_name.c_str(),
srv.response.objects[i].objects_vector[j].probability * 100);

cv::putText(cv_image.image, ss.str(), cvPoint(LINESPACING, LINESPACING * (++cnt)), cv::FONT_HERSHEY_SIMPLEX, 0.5,
cv::Scalar(0, 255, 0), 1);
}

cv::imshow("image_classification", cv_image.image);
cv::waitKey(0);
}

ROS_INFO("inference time: %fms", srv.response.objects.inference_time_ms);
ROS_INFO("inference %lu images during %ld ms", srv.response.objects.size(), msdiff.total_milliseconds());

return 0;
}
125 changes: 87 additions & 38 deletions movidius_ncs_example/src/image_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*/

#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>

Expand All @@ -21,6 +22,42 @@

#include <object_msgs/DetectObject.h>

#include <vector>
#include <dirent.h>

#include <boost/date_time/posix_time/posix_time.hpp>
#include <chrono>

std::vector<std::string> getImagePath(std::string image_dir)
{
if (image_dir.back() != '/')
{
image_dir += "/";
}

std::vector<std::string> files;

DIR* dir;
struct dirent* ptr;

if ((dir = opendir(image_dir.c_str())) == NULL)
{
perror("Open Dir error...");
exit(1);
}

while ((ptr = readdir(dir)) != NULL)
{
if (strcmp(ptr->d_name, ".") == 0 || strcmp(ptr->d_name, "..") == 0)
continue;
else if (ptr->d_type == 8)
files.push_back(image_dir + ptr->d_name);
}
closedir(dir);

return files;
}

int main(int argc, char** argv)
{
ros::init(argc, argv, "movidius_ncs_example");
Expand All @@ -31,58 +68,70 @@ int main(int argc, char** argv)
return -1;
}

std::vector<std::string> images_path = getImagePath(*(argv + 1));

ros::NodeHandle n;
ros::ServiceClient client;
client = n.serviceClient<object_msgs::DetectObject>("/movidius_ncs_image/detect_object");
object_msgs::DetectObject srv;

cv_bridge::CvImage cv_image;
sensor_msgs::Image ros_image;
cv_image.image = cv::imread(argv[1]);
cv_image.encoding = "bgr8";
cv_image.toImageMsg(ros_image);
int width = cv_image.image.cols;
int height = cv_image.image.rows;
srv.request.images_path = images_path;

srv.request.image = ros_image;
boost::posix_time::ptime start = boost::posix_time::microsec_clock::local_time();

if (!client.call(srv))
{
ROS_ERROR("failed to call service DetectObject");
return 1;
}

for (unsigned int i = 0; i < srv.response.objects.objects_vector.size(); i++)
boost::posix_time::ptime end = boost::posix_time::microsec_clock::local_time();
boost::posix_time::time_duration msdiff = end - start;

for (unsigned int i = 0; i < srv.response.objects.size(); i++)
{
std::stringstream ss;
ss << srv.response.objects.objects_vector[i].object.object_name << ": "
<< srv.response.objects.objects_vector[i].object.probability * 100 << "%";

ROS_INFO("%d: object: %s", i, srv.response.objects.objects_vector[i].object.object_name.c_str());
ROS_INFO("prob: %f", srv.response.objects.objects_vector[i].object.probability);
ROS_INFO("location: (%d, %d, %d, %d)",
srv.response.objects.objects_vector[i].roi.x_offset,
srv.response.objects.objects_vector[i].roi.y_offset,
srv.response.objects.objects_vector[i].roi.width,
srv.response.objects.objects_vector[i].roi.height);

int xmin = srv.response.objects.objects_vector[i].roi.x_offset;
int ymin = srv.response.objects.objects_vector[i].roi.y_offset;
int w = srv.response.objects.objects_vector[i].roi.width;
int h = srv.response.objects.objects_vector[i].roi.height;

int xmax = ((xmin + w) < width)? (xmin + w) : width;
int ymax = ((ymin + h) < height)? (ymin + h) : height;

cv::Point left_top = cv::Point(xmin, ymin);
cv::Point right_bottom = cv::Point(xmax, ymax);
cv::rectangle(cv_image.image, left_top, right_bottom, cv::Scalar(0, 255, 0), 1, cv::LINE_8, 0);
cv::rectangle(cv_image.image, cvPoint(xmin, ymin), cvPoint(xmax, ymin + 20), cv::Scalar(0, 255, 0), -1);
cv::putText(cv_image.image, ss.str(), cvPoint(xmin + 5, ymin + 20), cv::FONT_HERSHEY_PLAIN,
1, cv::Scalar(0, 0, 255), 1);
}
ROS_INFO("inference time: %fms", srv.response.objects.inference_time_ms);
cv_bridge::CvImage cv_image;
cv_image.image = cv::imread(images_path[i]);
cv_image.encoding = "bgr8";
int width = cv_image.image.cols;
int height = cv_image.image.rows;

ROS_INFO("Detection result for image No.%u:", i + 1);

for (unsigned int j = 0; j < srv.response.objects[i].objects_vector.size(); j++)
{
std::stringstream ss;
ss << srv.response.objects[i].objects_vector[j].object.object_name << ": "
<< srv.response.objects[i].objects_vector[j].object.probability * 100 << "%";

ROS_INFO("%d: object: %s", j, srv.response.objects[i].objects_vector[j].object.object_name.c_str());
ROS_INFO("prob: %f", srv.response.objects[i].objects_vector[j].object.probability);
ROS_INFO("location: (%d, %d, %d, %d)", srv.response.objects[i].objects_vector[j].roi.x_offset,
srv.response.objects[i].objects_vector[j].roi.y_offset,
srv.response.objects[i].objects_vector[j].roi.width,
srv.response.objects[i].objects_vector[j].roi.height);

int xmin = srv.response.objects[i].objects_vector[j].roi.x_offset;
int ymin = srv.response.objects[i].objects_vector[j].roi.y_offset;
int w = srv.response.objects[i].objects_vector[j].roi.width;
int h = srv.response.objects[i].objects_vector[j].roi.height;

int xmax = ((xmin + w) < width) ? (xmin + w) : width;
int ymax = ((ymin + h) < height) ? (ymin + h) : height;

cv::Point left_top = cv::Point(xmin, ymin);
cv::Point right_bottom = cv::Point(xmax, ymax);
cv::rectangle(cv_image.image, left_top, right_bottom, cv::Scalar(0, 255, 0), 1, cv::LINE_8, 0);
cv::rectangle(cv_image.image, cvPoint(xmin, ymin), cvPoint(xmax, ymin + 20), cv::Scalar(0, 255, 0), -1);
cv::putText(cv_image.image, ss.str(), cvPoint(xmin + 5, ymin + 20), cv::FONT_HERSHEY_PLAIN, 1,
cv::Scalar(0, 0, 255), 1);
}

cv::imshow("image_detection", cv_image.image);
cv::waitKey(0);
return 0;
}

ROS_INFO("inference %lu images during %ld ms", srv.response.objects.size(), msdiff.total_milliseconds());

return 0;
}
Loading