Skip to content

Commit

Permalink
Add uuid for each object type
Browse files Browse the repository at this point in the history
  • Loading branch information
Hannah DeFazio committed Jun 27, 2022
1 parent 25db973 commit cb2e501
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 15 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -80,3 +80,5 @@
# Temporary auto-generated Android Assets
/unity/ARUI/[Aa]ssets/[Ss]treamingAssets/aa.meta
/unity/ARUI/[Aa]ssets/[Ss]treamingAssets/aa/*

__pycache__
40 changes: 25 additions & 15 deletions ros/angel_system_nodes/angel_system_nodes/feedback_generator.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
import time

import uuid

import rclpy
from rclpy.node import Node
from vision_msgs.msg import BoundingBox3D
Expand All @@ -13,6 +15,7 @@
AruiObject3d
)


class FeedbackGenerator(Node):
def __init__(self):
super().__init__(self.__class__.__name__)
Expand Down Expand Up @@ -67,9 +70,12 @@ def __init__(self):
# message
self.arui_update_message = AruiUpdate()

# detection uuids
self.uuids = dict()

def publish_update(self):
self.arui_update_message.header.stamp = self.get_clock().now().to_msg()
self.log.info(f"Publishing AruiUpdate: {self.arui_update_message}")
self.log.info(f"Publishing AruiUpdate: {self.arui_update_message}\n")
self.arui_update_publisher.publish(self.arui_update_message)

def activity_callback(self, activity):
Expand All @@ -79,35 +85,39 @@ def activity_callback(self, activity):

def object_callback(self, object_msg):
self.arui_update_message.object3d_remove = self.arui_update_message.object3d_update
self.log.info(f"object message type: {type(object_msg)}")

# convert ObjectDetection3dSet to AruiObject3d
detections = []
for i in range(object_msg.num_objects):
detection = AruiObject3d()
#detection.uid =
detection.stamp = object_msg.source_stamp

detection.label = object_msg.object_labels[i]

# TODO: Update this to real tracking
# For now, assumes only one type of object will be in the scene at a time
if detection.label in self.uuids.keys():
detection.uid = self.uuids[detection.label]
else:
detection.uid = str(uuid.uuid4())
self.uuids[detection.label] = detection.uid

detection.stamp = object_msg.source_stamp

detection.bbox = BoundingBox3D()

# min = sorted[0], max = sorted[-1]
xs = sorted([object_msg.right[i].x, object_msg.left[i].x, object_msg.top[i].x, object_msg.bottom[i].x])
ys = sorted([object_msg.right[i].y, object_msg.left[i].y, object_msg.top[i].y, object_msg.bottom[i].y])
zs = sorted([object_msg.right[i].z, object_msg.left[i].z, object_msg.top[i].z, object_msg.bottom[i].z])

w = xs[-1] - xs[0]
h = ys[-1] - ys[0]
d = zs[-1] - zs[0]

detection.bbox.size.x = w
detection.bbox.size.y = h
detection.bbox.size.z = d
detection.bbox.size.x = xs[-1] - xs[0] # width
detection.bbox.size.y = ys[-1] - ys[0] # height
detection.bbox.size.z = zs[-1] - zs[0] # depth

detection.bbox.center.position.x = xs[0] + (0.5 * w)
detection.bbox.center.position.y = ys[0] + (0.5 * h)
detection.bbox.center.position.z = zs[0] + (0.5 * d)
detection.bbox.center.position.x = xs[0] + (0.5 * detection.bbox.size.x)
detection.bbox.center.position.y = ys[0] + (0.5 * detection.bbox.size.y)
detection.bbox.center.position.z = zs[0] + (0.5 * detection.bbox.size.z)

self.log.info(f"detection: {detection}")
detections.append(detection)

self.arui_update_message.object3d_update = detections
Expand Down

0 comments on commit cb2e501

Please sign in to comment.