Skip to content

Commit

Permalink
(tracking) cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
MatthijsBurgh committed Dec 12, 2023
1 parent 785b903 commit 8e9b1b3
Show file tree
Hide file tree
Showing 12 changed files with 42 additions and 74 deletions.
33 changes: 13 additions & 20 deletions people_tracking/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,26 +2,23 @@ cmake_minimum_required(VERSION 3.0.2)
project(people_tracking)

find_package(catkin REQUIRED COMPONENTS
rgbd
rgbd_image_buffer
roscpp
sensor_msgs
people_recognition_msgs

rospy
std_msgs
message_generation
message_generation
people_recognition_msgs
rgbd
rgbd_image_buffer
roscpp
sensor_msgs
visualization_msgs
)

# TODO still needed?
catkin_python_setup()

add_message_files(
FILES
detect_person.msg
DetectedPerson.msg
ColourCheckedTarget.msg
ColourTarget.msg
FILES
ColourCheckedTarget.msg
ColourTarget.msg
DetectPerson.msg
DetectedPerson.msg
)

add_service_files(
Expand All @@ -31,15 +28,11 @@ add_service_files(

generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
)



catkin_package(
CATKIN_DEPENDS
message_runtime
CATKIN_DEPENDS message_runtime sensor_msgs
)

include_directories(
Expand Down
File renamed without changes.
25 changes: 18 additions & 7 deletions people_tracking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,17 +20,28 @@

<buildtool_depend>python3-setuptools</buildtool_depend>

<depend>cv_bridge</depend>
<depend>image_recognition_msgs</depend>
<depend>image_recognition_util</depend>
<depend>people_recognition_msgs</depend>
<depend>rgbd</depend>
<depend>rgbd_image_buffer</depend>
<depend>rospy</depend>
<depend>sensor_msgs</depend>

<build_depend>people_recognition_msgs</build_depend>
<build_depend>rgbd</build_depend>
<build_depend>rgbd_image_buffer</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>visualization_msgs</build_depend>

<build_depend>message_generation</build_depend>

<exec_depend>cv_bridge</exec_depend>
<exec_depend>image_recognition_util</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>people_recognition_msgs</exec_depend>
<exec_depend>rgbd</exec_depend>
<exec_depend>rgbd_image_buffer</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>visualization_msgs</exec_depend>

<test_depend>catkin_lint_cmake</test_depend>

<doc_depend>python3-sphinx</doc_depend>
<doc_depend>python-sphinx-autoapi-pip</doc_depend>
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
from ultralytics import YOLO
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
from people_tracking.msg import detect_person
from people_tracking.msg import DetectPerson

laptop = True
name_subscriber_RGB = '/hero/head_rgbd_sensor/rgb/image_raw' if not laptop else 'video_frames'
Expand All @@ -23,7 +23,7 @@ def __init__(self) -> None:
rospy.init_node('listener', anonymous=True)
self.publisher = rospy.Publisher('/hero/segmented_image', Image, queue_size=10)
# self.subscriber = rospy.Subscriber(name_subscriber_RGB, Image, self.callback, queue_size=1)
self.publisher2 = rospy.Publisher('/hero/test_msg', detect_person, queue_size= 10)
self.publisher2 = rospy.Publisher('/hero/test_msg', DetectPerson, queue_size= 10)


self.latest_image = None # To store the most recent image
Expand All @@ -33,7 +33,7 @@ def __init__(self) -> None:
self.subscriber = rospy.Subscriber(name_subscriber_RGB, Image, self.image_callback, queue_size=1)

def msg_callback(self):
msg = detect_person()
msg = DetectPerson()
msg.name = "hi"
msg.age = 5
self.publisher2.publish(msg)
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,38 +1,4 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2008, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
# Revision $Id$


import rospy
import cv2
Expand All @@ -42,12 +8,8 @@
from sensor_msgs.msg import Image


laptop = True
name_subscriber_RGB = '/hero/head_rgbd_sensor/rgb/image_raw' if not laptop else 'video_frames'


class PeopleTracker:
def __init__(self) -> None:
def __init__(self, name_subscriber_RGB: str) -> None:

# Initialize YOLO
model_path = "~/MEGA/developers/Donal/yolov8n-seg.pt"
Expand All @@ -59,11 +21,12 @@ def __init__(self) -> None:
rospy.init_node('listener', anonymous=True)
self.publisher = rospy.Publisher('/hero/segmented_image', Image)
self.subscriber = rospy.Subscriber(name_subscriber_RGB, Image, self.callback, queue_size = 1)
self.cv_bridge = CvBridge()

@staticmethod
def detect(model, frame):
"""
Return segemented image per class type.
Return segemented image per class type.
"""
results = model(frame)
result = results[0]
Expand All @@ -74,8 +37,7 @@ def detect(model, frame):
def callback(self, data):
rospy.loginfo("got message")
seconds = rospy.get_time()
bridge = CvBridge()
cv_image = bridge.imgmsg_to_cv2(data, desired_encoding='passthrough')
cv_image = self.cv_bridge.imgmsg_to_cv2(data, desired_encoding='passthrough')
cv_image = cv2.GaussianBlur(cv_image, (5, 5), 0)
# cv_image = cv2.cvtColor(cv_image, cv2.COLOR_RGB2BGR)
rospy.loginfo("converted message")
Expand All @@ -99,9 +61,11 @@ def callback(self, data):
self.publisher.publish(image_message) # Send image with boundaries human


if __name__ == '__main__':
if __name__ == "__main__":
laptop = True
name_subscriber_RGB = "/hero/head_rgbd_sensor/rgb/image_raw" if not laptop else "video_frames"
try:
node_pt = PeopleTracker()
node_pt = PeopleTracker(name_subscriber_RGB)
rospy.spin()
except rospy.exceptions.ROSInterruptException:
pass

0 comments on commit 8e9b1b3

Please sign in to comment.