face_detector_groovy_bridge.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # simple script to convert from people_msgs/PositionMeasurementArray to people_msgs/PositionMeasurement
00004 
00005 import os
00006 import rospy
00007 
00008 try:
00009     from people_msgs.msg import *
00010 except:
00011     import roslib; roslib.load_manifest("people_msgs")
00012     from people_msgs.msg import *
00013 
00014 def arrayCallback(msg):
00015     global repub
00016     if len(msg.people) > 0:
00017         repub.publish(msg.people[0])
00018 
00019 
00020 def main():
00021     global repub
00022     repub = rospy.Publisher("/face_detector/people_tracker_measurements",
00023                             PositionMeasurement)
00024     s = rospy.Subscriber("/face_detector/people_tracker_measurements_array",
00025                          PositionMeasurementArray,
00026                          arrayCallback)
00027     rospy.spin()
00028 
00029 
00030 if __name__ == "__main__":
00031     rospy.init_node("face_detector_groovy_bridge")
00032     if os.environ["ROS_DISTRO"] == "groovy":
00033         rospy.logfatal("face_detector_groovy_bridge cannot run on groovy")
00034         exit(1)
00035     else:
00036         main()
00037 
00038 


jsk_pr2_startup
Author(s):
autogenerated on Sat Jul 1 2017 02:43:24