renew_tracking.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 
4 PKG='jsk_pcl_ros'
5 
6 import imp
7 try:
8  imp.find_module(PKG)
9 except:
10  import roslib;roslib.load_manifest(PKG)
11 
12 from sensor_msgs.msg import PointCloud2
13 from jsk_recognition_msgs.srv import SetPointCloud2
14 
15 def cloud_cb(cloud):
16 
17  try:
18  setCloud = rospy.ServiceProxy('particle_filter_tracker/renew_model', SetPointCloud2)
19  setCloud(cloud, track_target_name)
20  rospy.loginfo("Success renew_tracking service");
21  except rospy.ServiceException as e:
22  rospy.loginfo("Failed to call renew_tracking service")
23 
24 if __name__ == "__main__":
25  rospy.init_node('send_renew_model', anonymous=True)
26  rospy.wait_for_service('particle_filter_tracker/renew_model')
27  track_target_name = rospy.get_param('~track_target_name', 'track_result')
28  rospy.Subscriber("selected_pointcloud", PointCloud2, cloud_cb)
29  rospy.spin()
def cloud_cb(cloud)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47