8 rospy.init_node(
"bbox_sample")
9 pub = rospy.Publisher(
"bbox", BoundingBoxArray)
12 while not rospy.is_shutdown():
17 box_arr = BoundingBoxArray()
18 now = rospy.Time.now()
19 box_a.header.stamp = now
20 box_b.header.stamp = now
21 box_arr.header.stamp = now
22 box_a.header.frame_id =
"map"
23 box_b.header.frame_id =
"map"
24 box_arr.header.frame_id =
"map"
25 q = quaternion_about_axis((counter % 100) * math.pi * 2 / 100.0, [0, 0, 1])
26 box_a.pose.orientation.x = q[0]
27 box_a.pose.orientation.y = q[1]
28 box_a.pose.orientation.z = q[2]
29 box_a.pose.orientation.w = q[3]
30 box_b.pose.orientation.w = 1
31 box_b.pose.position.y = 2
32 box_b.dimensions.x = (counter % 10 + 1) * 0.1
33 box_b.dimensions.y = ((counter + 1) % 10 + 1) * 0.1
34 box_b.dimensions.z = ((counter + 2) % 10 + 1) * 0.1
35 box_a.dimensions.x = 1
36 box_a.dimensions.y = 1
37 box_a.dimensions.z = 1
38 box_a.value = (counter % 100) / 100.0
39 box_b.value = 1 - (counter % 100) / 100.0
40 box_arr.boxes.append(box_a)
41 box_arr.boxes.append(box_b)