7 from jsk_recognition_msgs.msg
import ClusterPointIndices
8 from pcl_msgs.msg
import PointIndices
9 import dynamic_reconfigure.client
19 self.
dynparam = dynamic_reconfigure.client.Client(
20 'cluster_point_indices_to_point_indices')
21 self.
pub = rospy.Publisher(
'~output', ClusterPointIndices,
23 self.
sub = rospy.Subscriber(
'~input', PointIndices, self.
cb)
29 self.dynparam.update_configuration({
'index': 1})
31 cluster_indices_msg = ClusterPointIndices()
32 while self.
msg is None:
33 cluster_indices_msg.header.stamp = rospy.Time.now()
35 cluster_indices_msg.cluster_indices.append(
37 header=cluster_indices_msg.header,
41 self.pub.publish(cluster_indices_msg)
47 if __name__ ==
'__main__':
48 PKG =
'jsk_pcl_ros_utils' 49 ID =
'test_cluster_point_indices_to_point_indices' 51 rostest.rosrun(PKG, ID, TestClusterPointIndicesToPointIndices)
def test_conversion(self)