jsk-ros-pkg / jsk_visualization

jsk visualization ros packages
https://github.com/jsk-ros-pkg/jsk_visualization
324 stars 173 forks source link

[jsk_rviz_plugins] allocate only valid bboxes #861

Closed knorth55 closed 1 year ago

knorth55 commented 1 year ago

this PR change to show only valid bboxes. current master allocate the bboxes first, and skip if the box is invalid, which cause to show the 1m cube at the originl point. this PR change to first check if bboxes are valid or not, and allocate it.

I also change to check if bboxes.box[i].header.frame_id is empty or not.

This PR

https://user-images.githubusercontent.com/9300063/200168499-83ef048c-0cfd-4b29-8955-26bea110c073.mp4

Current master branch

https://user-images.githubusercontent.com/9300063/200168503-7d3e9624-5c41-4aec-bb12-0418bc251cf0.mp4

Sample code

import numpy as np
import rospy

from jsk_recognition_msgs.msg import BoundingBox
from jsk_recognition_msgs.msg import BoundingBoxArray

class Spam(object):
    def __init__(self):
        self.pub = rospy.Publisher('~hoge', BoundingBoxArray, queue_size=1)
        self.timer = rospy.Timer(rospy.Duration(0.1), self._timer_cb)
        self.cnt = 0

    def _timer_cb(self, event):
        msg = BoundingBoxArray()
        msg.header.frame_id = 'base_link'
        # 1st: normal box
        box = BoundingBox()
        box.header.frame_id = 'base_link'
        box.pose.orientation.w = 1.0
        box.pose.position.x = 1.0
        box.pose.position.y = 1.0
        box.pose.position.z = np.sin(self.cnt)
        box.dimensions.x = 0.5
        box.dimensions.y = 0.5
        box.dimensions.z = 0.5
        msg.boxes.append(box)
        # 2nd: only initialized box
        msg.boxes.append(BoundingBox())
        # 3rd: normal box but without frame_id
        box = BoundingBox()
        # box.header.frame_id = 'base_link'
        box.pose.orientation.w = 1.0
        box.pose.position.x = 1.0
        box.pose.position.y = 1.0
        box.pose.position.z = 1.0
        box.dimensions.x = 0.5
        box.dimensions.y = 0.5
        box.dimensions.z = 0.5
        msg.boxes.append(box)
        self.pub.publish(msg)
        self.cnt = (self.cnt + 0.1) % (2 * np.pi)

if __name__ == '__main__':
    rospy.init_node('spam')
    app = Spam()
    rospy.spin()

cc. @Affonso-Gui