6 if os.environ[
"ROS_DISTRO"] == 
"groovy":
 
    7   roslib.load_manifest(
"jsk_footstep_planner")
 
    9 from jsk_recognition_msgs.msg 
import PolygonArray
 
   10 from geometry_msgs.msg 
import PolygonStamped, Point32
 
   13   global_frame_id = rospy.myargv()[1]
 
   15   ret.header.stamp = rospy.Time.now()
 
   16   ret.header.frame_id = global_frame_id
 
   18   for i 
in range(-1, 5):
 
   24     points_array = [[[x2, 2, 0],   [x1, 2, 0],   [x1, -2, 0],   [x2, -2, 0]],
 
   25                     [[x3, 2, 0.3], [x2, 2, 0.2], [x2, -2, 0.2], [x3, -2, 0.3]],
 
   26                     [[x4, 2, 0.1], [x3, 2, 0.1], [x3, -2, 0.1], [x4, -2, 0.1]]]
 
   27     for points 
in points_array:
 
   28       polygon = PolygonStamped()
 
   29       polygon.header.frame_id = global_frame_id
 
   30       polygon.header.stamp = rospy.Time.now()
 
   32         polygon.polygon.points.append(Point32(*p))
 
   33       ret.polygons.append(polygon)
 
   38   rospy.init_node(
"plane_publisher")
 
   40   pub = rospy.Publisher(
"planes", PolygonArray)
 
   41   while not rospy.is_shutdown():
 
   46 if __name__ == 
"__main__":