20 #include <boost/filesystem/operations.hpp> 23 #include <object_msgs/Object.h> 24 #include <object_msgs/Objects.h> 25 #include <object_msgs/ObjectInBox.h> 26 #include <object_msgs/ObjectsInBoxes.h> 37 : ncs_manager_handle_(nullptr)
39 , max_device_number_(255)
40 , start_device_index_(0)
41 , log_level_(
Device::Errors)
43 , graph_file_path_(
"")
44 , category_file_path_(
"")
45 , network_dimension_(0)
60 ROS_WARN(
"param max_device_number not set, use default");
66 throw std::exception();
73 ROS_WARN(
"param start_device_index not set, use default");
79 throw std::exception();
86 ROS_WARN(
"param log_level not set, use default");
89 if (log_level_ < Device::Nothing || log_level_ > Device::Verbose)
92 throw std::exception();
99 ROS_WARN(
"param cnn_type not set, use default");
108 throw std::exception();
115 ROS_WARN(
"param graph_file_path not set, use default");
121 throw std::exception();
128 ROS_WARN(
"param category_file_path not set, use default");
134 throw std::exception();
141 ROS_WARN(
"param network_dimension not set, use default");
147 throw std::exception();
152 for (
int i = 0; i < 3; i++)
154 std::ostringstream oss;
155 oss <<
"channel" << (i + 1) <<
"_mean";
156 std::string mean_param_name = oss.str();
160 ROS_WARN_STREAM(
"param " << mean_param_name <<
"not set, use default");
163 mean_.push_back(mean_val);
168 ROS_WARN(
"param top_n not set, use default");
174 throw std::exception();
181 ROS_WARN(
"param scale not set, use default");
187 throw std::exception();
214 object_msgs::ClassifyObject::Response& response)
216 std::vector<ClassificationResultPtr> results =
ncs_manager_handle_->classifyImage(request.image_paths);
218 for (
unsigned int i = 0; i < results.size(); i++)
220 object_msgs::Objects objs;
221 for (
auto item : results[i]->items)
223 object_msgs::Object obj;
224 obj.object_name = item.category;
225 obj.probability = item.probability;
226 objs.objects_vector.push_back(obj);
229 objs.inference_time_ms = results[i]->time_taken;
230 response.objects.push_back(objs);
237 object_msgs::DetectObject::Response& response)
239 std::vector<DetectionResultPtr> results =
ncs_manager_handle_->detectImage(request.image_paths);
241 for (
unsigned int i = 0; i < results.size(); i++)
243 object_msgs::ObjectsInBoxes objs;
244 for (
auto item : results[i]->items_in_boxes)
246 object_msgs::ObjectInBox obj;
247 obj.object.object_name = item.item.category;
248 obj.object.probability = item.item.probability;
249 obj.roi.x_offset = item.bbox.x;
250 obj.roi.y_offset = item.bbox.y;
251 obj.roi.width = item.bbox.width;
252 obj.roi.height = item.bbox.height;
253 objs.objects_vector.push_back(obj);
256 objs.inference_time_ms = results[i]->time_taken;
257 response.objects.push_back(objs);
265 int main(
int argc,
char** argv)
267 ros::init(argc, argv,
"movidius_ncs_node");
277 ROS_ERROR(
"exception caught in movidius_ncs_node");
std::shared_ptr< DetectionResult > DetectionResultPtr
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string graph_file_path_
ros::ServiceServer service_
std::shared_ptr< movidius_ncs_lib::NCSManager > ncs_manager_handle_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool cbDetectObject(object_msgs::DetectObject::Request &request, object_msgs::DetectObject::Response &response)
ROSCPP_DECL void spin(Spinner &spinner)
NCSServer(ros::NodeHandle &nh)
std::string category_file_path_
#define ROS_WARN_STREAM(args)
std::vector< float > mean_
std::shared_ptr< ClassificationResult > ClassificationResultPtr
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
#define ROS_ERROR_STREAM(args)
bool cbClassifyObject(object_msgs::ClassifyObject::Request &request, object_msgs::ClassifyObject::Response &response)