4 from sensor_msgs.msg 
import PointCloud2
 
    6 from std_msgs.msg 
import Header
 
    8                                       BoundingBox, BoundingBoxArray)
 
    9 from pcl_msgs.msg 
import ModelCoefficients
 
   11 from std_srvs.srv 
import Empty
 
   13 from math 
import pi, cos, sin
 
   19     for x 
in np.arange(-1, 1, dx):
 
   20         for y 
in np.arange(-1, 1, dx):
 
   21             plane_points.append([x, y, 0.0])
 
   22     for x 
in np.arange(-0.1, 0.1, dx):
 
   23         for y 
in np.arange(-0.1, 0.1, dx):
 
   24             object_points.append([x, y, 0.2])
 
   25     return plane_points + object_points
 
   31     for x 
in np.arange(-1, 1, dx):
 
   32         for y 
in np.arange(-1, 1, dx):
 
   33             plane_points.append([x, y, 0.0])
 
   34     for x 
in np.arange(-0.3, 0.2, dx):
 
   35         for y 
in np.arange(-0.1, 0.1, dx):
 
   36             object_points.append([x, y, 0.2])
 
   37     return plane_points + object_points
 
   43     for x 
in np.arange(-1, 1, dx):
 
   44         for y 
in np.arange(-1, 1, dx):
 
   45             plane_points.append([x, y, 0.0])
 
   46     for x 
in np.arange(-0.1, 0.1, dx):
 
   47         for y 
in np.arange(-0.1, 0.1, dx):
 
   48             object_points.append([x, y, 0.2])
 
   49     for x 
in np.arange(-0.4, -0.2, dx):
 
   50         for y 
in np.arange(-0.1, 0.1, dx):
 
   51             object_points.append([x, y, 0.2])
 
   53     return plane_points + object_points
 
   59     for x 
in np.arange(-1, 1, dx):
 
   60         for y 
in np.arange(-1, 1, dx):
 
   61             plane_points.append([x, y, 0.0])
 
   62     for x 
in np.arange(-0.1, 0.1, dx):
 
   63         for y 
in np.arange(-0.1, 0.1, dx):
 
   64             object_points.append([x, y, 0.2])
 
   65     for z 
in np.arange(0.0, 0.2, dx):
 
   66         for y 
in np.arange(-0.1, 0.1, dx):
 
   67             object_points.append([0.1, y, z])
 
   68             object_points.append([-0.1, y, z])
 
   69     for z 
in np.arange(0.0, 0.2, dx):
 
   70         for x 
in np.arange(-0.1, 0.1, dx):
 
   71             object_points.append([x, 0.1, z])
 
   72             object_points.append([x, -0.1, z])
 
   74     return plane_points + object_points
 
   80     for y 
in np.arange(-0.5, 0.5, dx):
 
   81         for z 
in np.arange(0, 2, dx):
 
   82             plane_points.append([0.0, y, z])
 
   83     for y 
in np.arange(0.2, 0.4, dx):
 
   84         for z 
in np.arange(0.8, 0.9, dx):
 
   85             object_points.append([-0.1, y, z])
 
   86     return plane_points + object_points
 
   91     elif model_index == 1:
 
   93     elif model_index == 2:
 
   95     elif model_index == 3:
 
   97     elif model_index == 4:
 
  101     polygon = PolygonArray()
 
  102     polygon.header = header
 
  103     polygon.polygons = [PolygonStamped()]
 
  104     polygon.polygons[0].header = header;
 
  105     coef = ModelCoefficientsArray()
 
  106     coef.coefficients = [ModelCoefficients()]
 
  108     if model_index 
in [0, 1, 2, 3]:
 
  110         polygon.polygons[0].polygon.points = [Point32(x=1.0, y=1.0),
 
  111                                               Point32(x=-1.0, y=1.0),
 
  112                                               Point32(x=-1.0, y=-1.0),
 
  113                                               Point32(x=1.0, y=-1.0)]
 
  114         coef.coefficients[0].header = header
 
  115         coef.coefficients[0].values = [0, 0, 1, 0]
 
  116     elif model_index == 4:
 
  117         polygon.polygons[0].polygon.points = [Point32(x=0.0, y=-0.5, z=0.0),
 
  118                                               Point32(x=0.0, y=-0.5, z=2.0),
 
  119                                               Point32(x=0.0, y=0.5, z=2.0),
 
  120                                               Point32(x=0.0, y=0.5, z=0.0)]
 
  122         coef.coefficients[0].header = header
 
  123         coef.coefficients[0].values = [-1, 0, 0, 0]
 
  124     return (polygon, coef)
 
  128     box_array = BoundingBoxArray()
 
  129     box_array.header.stamp = header.stamp
 
  130     box_array.header.frame_id = 
"odom" 
  132     for y 
in np.arange(0.0, 0.6, dx):
 
  133         for z 
in np.arange(0.7, 1.0, dx):
 
  134             for x 
in np.arange(0.0, -0.5, -dx):
 
  136                 box.header = box_array.header
 
  137                 box.pose.orientation.w = 1.0
 
  138                 box.pose.position.x = x
 
  139                 box.pose.position.y = y
 
  140                 box.pose.position.z = z
 
  141                 box.dimensions.x = 0.1
 
  142                 box.dimensions.y = 0.1
 
  143                 box.dimensions.z = 0.1
 
  144                 box_array.boxes.append(box)
 
  147 if __name__ == 
"__main__":
 
  148     rospy.init_node(
"sample_simulate_tabletop_cloud")
 
  149     pub = rospy.Publisher(
"~output", PointCloud2, queue_size=1)
 
  150     pub_polygon = rospy.Publisher(
 
  151         "~output/polygon", PolygonArray, queue_size=1)
 
  152     pub_coef = rospy.Publisher(
 
  153         "~output/coef", ModelCoefficientsArray, queue_size=1)
 
  154     pub_boxes = rospy.Publisher(
 
  155         "~output/candidate_boxes", BoundingBoxArray, queue_size=1)
 
  160     while not rospy.is_shutdown():
 
  163         header.frame_id = 
"odom" 
  164         header.stamp = rospy.Time.now()
 
  165         msg = create_cloud_xyz32(header, points)
 
  168         pub_polygon.publish(polygon)
 
  169         pub_coef.publish(coef)
 
  170         counter = counter + 1
 
  172         if reset 
and counter > 1.0 / r.sleep_dur.to_sec() * 10:
 
  173             reset = rospy.ServiceProxy(
"/plane_supported_cuboid_estimator/reset", Empty)
 
  175             model_index = model_index + 1