Skip to content

Instantly share code, notes, and snippets.

@k-okada
Created March 10, 2023 10:19
Show Gist options
  • Save k-okada/7845471a8f6c3140e69cfe77ac6095b5 to your computer and use it in GitHub Desktop.
Save k-okada/7845471a8f6c3140e69cfe77ac6095b5 to your computer and use it in GitHub Desktop.
#!/usr/bin/env python
import rospy
import message_filters
from std_msgs.msg import ColorRGBA
from geometry_msgs.msg import Vector3
from jsk_recognition_msgs.msg import ClassificationResult, BoundingBoxArray
from visualization_msgs.msg import MarkerArray, Marker
import numpy as np
def callback(class_msg, bbox_msg):
rospy.loginfo("found {}".format(zip(class_msg.label_names, class_msg.label_proba)))
if len(class_msg.label_names) == 0:
return
target_names = class_msg.target_names
msg = MarkerArray()
for label, name, prob, bbox in zip(class_msg.labels, class_msg.label_names, class_msg.label_proba, bbox_msg.boxes):
msg.markers.append(Marker(header=class_msg.header,
type=Marker.TEXT_VIEW_FACING,
action=Marker.ADD,
id=np.random.randint(10000),
scale=Vector3(0.1, 0.1, 0.1),
lifetime=rospy.Duration(10),
text="{} ({:.2f})".format(name, prob),
color=ColorRGBA(1.0,1,1.0,1.0),
pose=bbox.pose))
marker_pub.publish(msg)
# The callback processing the pairs of numbers that arrived at approximately the same time
rospy.init_node('publish_bbox_label')
class_sub = message_filters.Subscriber('/spot/ncb_provider/class', ClassificationResult)
bbox_sub = message_filters.Subscriber('/spot/ncb_provider/bbox_array', BoundingBoxArray)
marker_pub = rospy.Publisher('/spot/ncb_provider/class_marker', MarkerArray, queue_size=1)
ts = message_filters.ApproximateTimeSynchronizer([class_sub, bbox_sub], 1, 0.1, allow_headerless=True)
ts.registerCallback(callback)
rospy.spin()
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment