fake_people_detection.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 import roslib
00003 roslib.load_manifest('srs_human_sensing')
00004 
00005 
00006 import rospy
00007 
00008 
00009 from sensor_msgs.msg import *
00010 from std_msgs.msg import *
00011 from geometry_msgs.msg import *
00012 
00013 from cob_people_detection.srv import  *
00014 from cob_people_detection_msgs.msg import *
00015 
00016 
00017 
00018 def peopledetect(req):
00019         p=PeopleDetection()
00020         p2=PeopleDetection()
00021 
00022         pa=PeopleDetectionArray()
00023         p_srv=DetectPeopleResponse()
00024         pose=PoseStamped()
00025         pose.pose.position.x=1
00026         pose.pose.position.y=2
00027         pose.pose.position.z=3
00028         
00029         pose2=PoseStamped()
00030         pose2.pose.position.x=4
00031         pose2.pose.position.y=5
00032         pose2.pose.position.z=6
00033         
00034     
00035         p.pose=pose 
00036         p.label='alex'
00037         p2.pose=pose2
00038         
00039         rospy.loginfo("kam was an")
00040 
00041       #  pa.detections.append(p)
00042       #  pa.header='leer'
00043         p_srv.people_list.detections.append(p)
00044         p_srv.people_list.detections.append(p2)
00045 
00046         
00047         return p_srv  
00048 
00049 
00050 def people_detection_fake_server():
00051     rospy.init_node('detect_people_fake')
00052    
00053     s = rospy.Service('/cob_people_detection/detect_people', DetectPeople, peopledetect)
00054     rospy.loginfo("people_detection_fake_server ready.")
00055     rospy.spin()
00056 
00057 if __name__ == "__main__":
00058 
00059     people_detection_fake_server()


srs_human_sensing
Author(s): Alex
autogenerated on Sun Jan 5 2014 12:21:20