Skip to content

Commit

Permalink
Fix threshold value not passing to openvino.
Browse files Browse the repository at this point in the history
  • Loading branch information
ajtudela committed May 26, 2022
1 parent b8d3060 commit 0b12a96
Show file tree
Hide file tree
Showing 8 changed files with 557 additions and 101 deletions.
7 changes: 6 additions & 1 deletion CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,14 @@
Changelog for package object_detection_openvino
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.2.2 (26-05-2022)
------------------
* Improve documentation.
* Fix threshold value not passing to openvino.

3.2.1 (08-03-2022)
------------------
* Optimizations, change pose to bottom of bbox
* Optimizations, change pose to bottom of bbox.

3.2.0 (23-02-2022)
------------------
Expand Down
92 changes: 91 additions & 1 deletion include/object_detection_openvino/detectionObject.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,47 @@

#include <string>

/**
* @brief Implementation of a detection object in an image
*
* An object is defined by the 2D coordinates in pixels of the bounding box surrounding it,
* its class (name and numeric id) and its confidence.
*/
struct DetectionObject{
int xmin, ymin, xmax, ymax, classId;
/// Minimum coordinate in the X axis.
int xmin;

/// Minimum coordinate in the Y axis.
int ymin;

/// Maximum coordinate in the X axis.
int xmax;

/// Maximum coordinate in the Y axis.
int ymax;

/// Numeric id of the object class.
int classId;

/// Confidence of the detected object in a range between 0 and 1.
float confidence;

/// Name of object class.
std::string className;

/**
* @brief Constructor of a new detection object.
*
* @param x Coordinate of the center pixel in the X axis.
* @param y Coordinate of the center pixel in the Y axis.
* @param h Height in pixels of the bounding box surrounding the detected object.
* @param w Width in pixels of the bounding box surrounding the detected object.
* @param classId Numeric id of the object class.
* @param className Name of object class.
* @param confidence Confidence of the detected object in a range between 0 and 1.
* @param h_scale Scale of the bounding box height.
* @param w_scale Scale of the bounding box width.
*/
DetectionObject(double x, double y, double h, double w, int classId, std::string className, float confidence, float h_scale, float w_scale){
xmin = static_cast<int>((x - w / 2) * w_scale);
ymin = static_cast<int>((y - h / 2) * h_scale);
Expand All @@ -29,6 +65,18 @@ struct DetectionObject{
this->className = className;
}

/**
* @brief Overloaded constructor, provided for convenience.
* It differs from the above function only in what argument(s) it accepts.
*
* @param x Coordinate of the center pixel in the X axis.
* @param y Coordinate of the center pixel in the Y axis.
* @param h Height in pixels of the bounding box surrounding the detected object.
* @param w Width in pixels of the bounding box surrounding the detected object.
* @param classId Numeric id of the object class.
* @param className Name of object class.
* @param confidence Confidence of the detected object in a range between 0 and 1.
*/
DetectionObject(double x, double y, double h, double w, int classId, std::string className, float confidence){
xmin = static_cast<int>(x);
ymin = static_cast<int>(y);
Expand All @@ -39,10 +87,52 @@ struct DetectionObject{
this->className = className;
}

/**
* @brief Copy constructor.
*
* @param object The detected object.
*/
DetectionObject(DetectionObject& object){
xmin = object.xmin;
ymin = object.ymin;
xmax = object.xmax;
ymax = object.ymax;
confidence = object.confidence;
classId = object.classId;
className = object.className;
}

/**
* @brief Copy constructor.
*
* @param object The detected object.
*/
DetectionObject(const DetectionObject& object){
xmin = object.xmin;
ymin = object.ymin;
xmax = object.xmax;
ymax = object.ymax;
confidence = object.confidence;
classId = object.classId;
className = object.className;
}

/**
* @brief Relational operator of the confidence of the detected object.
*
* @param s2 Object to compare to.
* @return True if the left object has lower confidence than the right one. False, otherwise.
*/
bool operator<(const DetectionObject &s2) const {
return this->confidence < s2.confidence;
}

/**
* @brief Relational operator of the confidence of the detected object.
*
* @param s2 Object to compare to.
* @return True if the left object has greater confidence than the right one. False, otherwise.
*/
bool operator>(const DetectionObject &s2) const {
return this->confidence > s2.confidence;
}
Expand Down
204 changes: 194 additions & 10 deletions include/object_detection_openvino/objectDetectionVPU.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,48 +44,232 @@
// OpenCV
#include <cv_bridge/cv_bridge.h>


/// The number of the labels in the COCO database.
#define COCO_CLASSES 80

// Typedef for easier readability
/// Typedef for easier readability.
typedef std::chrono::duration<double, std::ratio<1, 1000>> ms;

/// Typedef for easier readability.
typedef pcl::PointCloud<pcl::PointXYZRGB> pcloud;

/**
* @brief Implmentation of the interface between different neural networks frameworks and ROS.
*
*/
class ObjectDetectionVPU{
public:

/// Constructor which initialize the subscribers, the publishers and the inference engine .
ObjectDetectionVPU(ros::NodeHandle& node, ros::NodeHandle& node_private);

/// Delete all parameteres of the node.
~ObjectDetectionVPU();

private:
ros::NodeHandle node_, nodePrivate_;

/// Public ROS node handler.
ros::NodeHandle node_;

/// Private ROS node handler.
ros::NodeHandle nodePrivate_;

/// The received image.
image_transport::ImageTransport imageTransport_;

/// Subscriber to a color image.
image_transport::SubscriberFilter colorSub_;

/// Publisher of the image with the bounding boxes of the detected objects.
image_transport::Publisher detectionColorPub_;

/// Subscriber to a pointcloud.
message_filters::Subscriber<sensor_msgs::PointCloud2> pointsSub_;
ros::Publisher detectionInfoPub_, detections2DPub_, detections3DPub_, markersPub_;

/// Publisher of the meta-information about the vision pipeline.
ros::Publisher detectionInfoPub_;

/// Publisher of the aray with the detected objects in 2 dimensions.
ros::Publisher detections2DPub_;

/// Publisher of the aray with the detected objects in 3 dimensions.
ros::Publisher detections3DPub_;

/// Publisher of markers with the bounding boxes and labels of the detected objects.
ros::Publisher markersPub_;

/// Listener of the transformations tree.
tf::TransformListener tfListener_;

/// Typedef for a ApproximateTime policy between an image message and a pointcloud message.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2> SyncPolicyImagePCL;

/// Synchronizer of the image message and the pointcloud message.
message_filters::Synchronizer<SyncPolicyImagePCL> syncImagePCL_;

/// Intel OpenVino framework.
Openvino openvino_;
float thresh_, iouThresh_;
bool showFPS_, useDepth_;
std::string deviceTarget_, networkType_;
std::string modelFileName_, binFileName_, labelFileName_;
std::string colorFrameId_, cameraFrameId_;
std::string colorTopic_, pointCloudTopic_, detectionImageTopic_, detectionInfoTopic_, detections2DTopic_, detections3DTopic_;
cv::Mat nextFrame_, currFrame_;

/// Value below which objects will be discarded.
float thresh_;

/// Value of the intersection over union threshold in a range between 0 and 1.
float iouThresh_;

/// Flag to enable / disable the number of FPS in the iamge.
bool showFPS_;

/// Flag to enable / disable the use of te pointcloud to perform depth analysis.
bool useDepth_;

/// Type of the neural network.
std::string networkType_;

/// Name of the device to load the neural network into.
std::string deviceTarget_;

/// The filename of the model in XML format.
std::string modelFileName_;

/// The filename of the model in BIN format.
std::string binFileName_;

/// The filename of the labels used in the model.
std::string labelFileName_;

/// Frame identifier of the color image.
std::string colorFrameId_;

/// Frame identifier of the camera.
std::string cameraFrameId_;

/// Topic of the color image.
std::string colorTopic_;

/// Topic of the pointcloud.
std::string pointCloudTopic_;

/// Topic of the image with the bounding boxes of the detected objects.
std::string detectionImageTopic_;

/// Topic of the information about the vision pipeline.
std::string detectionInfoTopic_;

/// Topic of the detected objects in 2 dimensions.
std::string detections2DTopic_;

/// Topic of the detected objects in 3 dimensions.
std::string detections3DTopic_;

/// Next image to be processed.
cv::Mat nextFrame_;

/// Curent image to be processed.
cv::Mat currFrame_;

/// Class labels of the neural network.
std::vector<std::string> labels_;

/**
* @brief Update the parameters of the node.
*
*/
void getParams();

/**
* @brief Get color of the class.
*
* @param c Integer with the channel of the color.
* @param x Offset value.
* @param max Maximum number of classes.
* @return The color of the class.
*/
int getColor(int c, int x, int max);

/**
* @brief Publish the meta-information about the vision pipeline when a subscriber connect to it.
*
* @param pub The publisher of the information.
*/
void connectInfoCallback(const ros::SingleSubscriberPublisher& pub);

/**
* @brief Receive an image, perform 2d object detection on it and publish the detected objects.
*
* @param colorImageMsg A message with an image to be processed.
*/
void colorImageCallback(const sensor_msgs::Image::ConstPtr& colorImageMsg);

/**
* @brief Receive an image and a pointcloud, perform 2d object detection on it and publish the detected objects.
*
*
* @param colorImageMsg A message with an image to be processed.
* @param pointsMsg A message with a pointcloud to be processed.
*/
void colorPointCallback(const sensor_msgs::Image::ConstPtr& colorImageMsg, const sensor_msgs::PointCloud2::ConstPtr& pointsMsg);

/**
* @brief Show the histogram of the image.
*
* @param image The image from the sensor.
* @param mean The mean value of the pixels.
*/
void showHistogram(cv::Mat image, cv::Scalar mean);

/**
* @brief Create a Detection2D message with the detected object.
*
* @param[in] object The detected object.
* @param[in] header The header of the detected object.
* @param[out] detection2D The detection2D message with the detected object.
* @return True if the message was created correctly, false otherwise.
*/
bool createDetection2DMsg(DetectionObject object, std_msgs::Header header, vision_msgs::Detection2D& detection2D);

/**
* @brief Create a detection3D message with the detected object.
*
* @param[in] object The detected object.
* @param[in] header The header of the detected object.
* @param[in] cloudPC2 The pointcloud of the detected object in sensor_msgs::PointCloud2 format.
* @param[in] cloudPCL The pointcloud of the detected object in pcloud format.
* @param[out] detection3D The detection3D message with the detected object.
* @return True if the message was created correctly, false otherwise.
*/
bool createDetection3DMsg(DetectionObject object, std_msgs::Header header, const sensor_msgs::PointCloud2& cloudPC2, pcloud::ConstPtr cloudPCL, vision_msgs::Detection3D& detection3D);

/**
* @brief Create a 3D marker with the bounding box of the object to be shown in Rviz.
*
* @param[in] id The numeric identifier of the marker.
* @param[in] header The header of the marker.
* @param[in] colorRGB The color of the marker.
* @param[in] bbox The dimensions of the bounding box surrounding the object.
* @param[out] marker The 3d marker with the bounding of the detected object.
* @return True if the marker was created correctly, false otherwise.
*/
bool createBBox3DMarker(int id, std_msgs::Header header, float colorRGB[3], vision_msgs::BoundingBox3D bbox, visualization_msgs::Marker& marker);

/**
* @brief Create a 3d marker with the label of the object to be shown in Rviz.
*
* @param[in] id The numeric identifier of the marker.
* @param[in] header The header of the marker.
* @param[in] colorRGB The color of the marker.
* @param[in] bbox The dimensions of the bounding box surrounding the object.
* @param[in] label The label class of the detected object.
* @param[out] marker The 3d marker with the label of the detected object.
* @return True if the marker was created correctly, false otherwise.
*/
bool createLabel3DMarker(int id, std_msgs::Header header, float colorRGB[3], vision_msgs::BoundingBox3D bbox, std::string label, visualization_msgs::Marker& marker);

/**
* @brief Publish the image with the bounding boxes of the detected objects.
*
* @param image The image with the bounding boxes of the detected objects.
*/
void publishImage(cv::Mat image);
};
#endif
Loading

0 comments on commit 0b12a96

Please sign in to comment.