4 from jsk_recognition_msgs.msg 
import ClusterPointIndices
 
    5 from jsk_topic_tools 
import ConnectionBasedTransport
 
   12         super(AddClusterIndices, self).
__init__()
 
   13         self.
_pub = self.advertise(
'~output', ClusterPointIndices,
 
   17         topics = rospy.get_param(
'~topics')
 
   22         use_async = rospy.get_param(
'~approximate_sync', 
False)
 
   23         queue_size = rospy.get_param(
'~queue_size', 100)
 
   25             slop = rospy.get_param(
'~slop', 0.1)
 
   26             sync = message_filters.ApproximateTimeSynchronizer(
 
   27                 self.
subs, queue_size, slop)
 
   37         out_msg = ClusterPointIndices()
 
   38         out_msg.header = cpi_msgs[0].header
 
   39         for cpi_msg 
in cpi_msgs:
 
   40             out_msg.cluster_indices.extend(cpi_msg.cluster_indices)
 
   41         self.
_pub.publish(out_msg)
 
   44 if __name__ == 
'__main__':
 
   45     rospy.init_node(
'add_cluster_indices')