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

Add FPS calculations and added License and description to setup.cfg #63

Open
wants to merge 1 commit 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
2 changes: 1 addition & 1 deletion object_detection/config/params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,6 @@ object_detection:
model_params:
detector_type: YOLOv5
model_dir_path: /root/percep_ws/models/yolov5
weight_file_name: yolov5.onnx
weight_file_name: yolov5s.pt
confidence_threshold : 0.5
show_fps : 1
25 changes: 25 additions & 0 deletions object_detection/object_detection/ObjectDetection.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

import importlib
import os
import time

import cv2

Expand Down Expand Up @@ -77,6 +78,12 @@ def __init__(self):

self.bridge = CvBridge()

if self.show_fps:
self.start_time = time.time()
self.frame_count = 0
self.total_elapsed_time = 0
self.average_fps = 0

def discover_detectors(self):
curr_dir = os.path.dirname(__file__)
dir_contents = os.listdir(curr_dir + "/Detectors")
Expand All @@ -101,6 +108,8 @@ def load_detector(self):
def detection_cb(self, img_msg):
cv_image = self.bridge.imgmsg_to_cv2(img_msg, "bgr8")

start_time = time.time()

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

if predictions is None:
Expand All @@ -120,6 +129,22 @@ 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)

if self.show_fps:
elapsed_time = time.time() - start_time
self.frame_count += 1
self.total_elapsed_time += elapsed_time

# Write FPS on the frame
cv_image = cv2.putText(cv_image, f"FPS: {self.average_fps:.2f}", (10, 30),
cv2.FONT_HERSHEY_SIMPLEX, 0.8, (0, 255, 0), 2)

if time.time() - self.start_time >= 1.0:
self.average_fps = self.frame_count / self.total_elapsed_time

self.frame_count = 0
self.total_elapsed_time = 0
self.start_time = time.time()

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

Expand Down
2 changes: 1 addition & 1 deletion object_detection/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<package format="3">
<name>object_detection</name>
<version>0.0.0</version>
<description>This is a ROS 2 package aimed at providing an interfacing between Deep Learning models and the ROS architecture using a plug-and-play modular arhitecture</description>
<description>This is a ROS 2 package aimed at providing an interfacing between Deep Learning models and the ROS architecture using a plug-and-play modular architecture</description>
<maintainer email="[email protected]">singh</maintainer>
<license>Apache 2.0</license>

Expand Down
4 changes: 2 additions & 2 deletions object_detection/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@
zip_safe=True,
maintainer='singh',
maintainer_email='[email protected]',
description='TODO: Package description',
license='TODO: License declaration',
description='Plug-and-Play ROS 2 package for Perception in Robotics',
license='Apache 2.0',
tests_require=['pytest'],
entry_points={
'console_scripts': [
Expand Down
Loading