Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added support for vision_msgs #69

Open
wants to merge 2 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
4 changes: 2 additions & 2 deletions object_detection/config/params.yaml
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

model_dir_path needs to be changed.

Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ object_detection:
publish_output_img: 1
model_params:
detector_type: YOLOv5
model_dir_path: /root/percep_ws/models/yolov5
weight_file_name: yolov5.onnx
model_dir_path: /home/mediapipe/Desktop/ros_workspaces/percep_ws/models/yolov5
weight_file_name: yolov5s.pt
confidence_threshold : 0.5
show_fps : 1
30 changes: 29 additions & 1 deletion object_detection/object_detection/ObjectDetection.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
from rclpy.node import Node

from sensor_msgs.msg import Image
from vision_msgs.msg import Detection2D, Detection2DArray, ObjectHypothesis, ObjectHypothesisWithPose, Point2D, Pose2D


class ObjectDetection(Node):
Expand Down Expand Up @@ -72,7 +73,7 @@ def __init__(self):
self.load_detector()

self.img_pub = self.create_publisher(Image, self.output_img_topic, 10)
self.bb_pub = None
self.bb_pub = self.create_publisher(Detection2DArray, self.output_bb_topic, 10)
self.img_sub = self.create_subscription(Image, self.input_img_topic, self.detection_cb, 10)

self.bridge = CvBridge()
Expand Down Expand Up @@ -103,6 +104,9 @@ def detection_cb(self, img_msg):

predictions = self.detector.get_predictions(cv_image=cv_image)

# Forming Detection2DArray message
detection_array_msg = Detection2DArray()

if predictions is None:
print("Image input from topic: {} is empty".format(self.input_img_topic))
else:
Expand All @@ -120,6 +124,30 @@ def detection_cb(self, img_msg):
cv_image = cv2.putText(cv_image, label, (x1, y1 - 5),
cv2.FONT_HERSHEY_SIMPLEX, 0.5, (0, 255, 0), 1)

detection_msg = Detection2D()
detection_msg.bbox.size_x = float(x2-x1)
detection_msg.bbox.size_y = float(y1-y2)

position_msg = Point2D()
position_msg.x = float((x2-x1)/2 + x1)
position_msg.y = float((y1-y2)/2 + y2)

center_msg = Pose2D()
center_msg.position = position_msg
detection_msg.bbox.center = center_msg

results_msg = ObjectHypothesisWithPose()
hypothesis_msg = ObjectHypothesis()
hypothesis_msg.class_id = str(class_id)
hypothesis_msg.score = prediction['confidence']

results_msg.hypothesis = hypothesis_msg
detection_msg.results.append(results_msg)

detection_array_msg.detections.append(detection_msg)

self.bb_pub.publish(detection_array_msg)

output = self.bridge.cv2_to_imgmsg(cv_image, "bgr8")
self.img_pub.publish(output)

Expand Down
Loading