|
| 1 | +#!/usr/bin/env python |
| 2 | +import rospy |
| 3 | +import cv2 |
| 4 | +import numpy as np |
| 5 | +from cv_bridge import CvBridge |
| 6 | +from typing import List |
| 7 | + |
| 8 | +from people_tracking.msg import ColourTarget, DetectedPerson |
| 9 | +from std_srvs.srv import Empty, EmptyResponse |
| 10 | + |
| 11 | +NODE_NAME = 'HoC' |
| 12 | +TOPIC_PREFIX = '/hero/' |
| 13 | + |
| 14 | + |
| 15 | +class HOC: |
| 16 | + """Class for the histogram of colour node.""" |
| 17 | + def __init__(self) -> None: |
| 18 | + # ROS Initialize |
| 19 | + rospy.init_node(NODE_NAME, anonymous=True) |
| 20 | + self.subscriber = rospy.Subscriber(TOPIC_PREFIX + 'person_detections', DetectedPerson, self.callback, |
| 21 | + queue_size=1) |
| 22 | + self.publisher = rospy.Publisher(TOPIC_PREFIX + 'HoC', ColourTarget, queue_size=2) |
| 23 | + self.reset_service = rospy.Service(TOPIC_PREFIX + NODE_NAME + '/reset', Empty, self.reset) |
| 24 | + |
| 25 | + # Variables |
| 26 | + self.HoC_detections = [] |
| 27 | + self.last_batch_processed = 0 |
| 28 | + |
| 29 | + def reset(self, request): |
| 30 | + """ Reset all stored variables in Class to their default values.""" |
| 31 | + self.HoC_detections = [] |
| 32 | + self.last_batch_processed = 0 |
| 33 | + return EmptyResponse() |
| 34 | + |
| 35 | + @staticmethod |
| 36 | + def get_vector(image, bins: int = 32) -> List[float]: |
| 37 | + """ Return HSV-colour histogram vector from image. |
| 38 | +
|
| 39 | + :param image: cv2 image to turn into vector. |
| 40 | + :param bins: amount of bins in histogram. |
| 41 | + :return: HSV-colour histogram vector from image. |
| 42 | + """ |
| 43 | + hsv_image = cv2.cvtColor(image, cv2.COLOR_RGB2HSV) # Convert image to HSV |
| 44 | + |
| 45 | + histograms = [cv2.calcHist([hsv_image], [i], None, [bins], [1, 256]) |
| 46 | + for i in range(3)] # Get color histograms |
| 47 | + |
| 48 | + histograms = [hist / hist.sum() for hist in histograms] # Normalize histograms |
| 49 | + |
| 50 | + vector = np.concatenate(histograms, axis=0).reshape(-1) # Create colour histogram vector |
| 51 | + return vector.tolist() |
| 52 | + |
| 53 | + def callback(self, data: DetectedPerson) -> None: |
| 54 | + """ Get the colour vectors for each detected person and publish this.""" |
| 55 | + time = data.time |
| 56 | + nr_batch = data.nr_batch |
| 57 | + nr_persons = data.nr_persons |
| 58 | + detected_persons = data.detected_persons |
| 59 | + x_positions = data.x_positions |
| 60 | + y_positions = data.y_positions |
| 61 | + z_positions = data.z_positions |
| 62 | + |
| 63 | + if nr_batch <= self.last_batch_processed: |
| 64 | + return |
| 65 | + if nr_persons < 1: |
| 66 | + return |
| 67 | + |
| 68 | + bridge = CvBridge() |
| 69 | + colour_vectors = [self.get_vector(bridge.imgmsg_to_cv2(person, desired_encoding='passthrough')) for person in |
| 70 | + detected_persons] |
| 71 | + |
| 72 | + msg = ColourTarget() |
| 73 | + msg.time = time |
| 74 | + msg.nr_batch = nr_batch |
| 75 | + msg.nr_persons = nr_persons |
| 76 | + msg.x_positions = x_positions |
| 77 | + msg.y_positions = y_positions |
| 78 | + msg.z_positions = z_positions |
| 79 | + msg.colour_vectors = [item for sublist in colour_vectors for item in sublist] |
| 80 | + |
| 81 | + self.publisher.publish(msg) |
| 82 | + self.last_batch_processed = nr_batch |
| 83 | + |
| 84 | + |
| 85 | +if __name__ == '__main__': |
| 86 | + try: |
| 87 | + node_hoc = HOC() |
| 88 | + rospy.spin() |
| 89 | + except rospy.exceptions.ROSInterruptException: |
| 90 | + rospy.loginfo("Failed to launch HoC Node") |
| 91 | + pass |
0 commit comments