psm_node_test.py
Go to the documentation of this file.
1 '''
2 Copyright (c) 2016, Braun Kai, Meissner Pascal
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
6 
7 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
8 
9 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
10 
11 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
12 
13 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
14 '''
15 
16 from asr_msgs.msg import AsrObject
18 import roslib
19 import rospy
20 import os
21 from visualization_msgs.msg import Marker
22 from visualization_msgs.msg import MarkerArray
23 import signal
24 import sys
25 import rospkg
26 
27 from geometry_msgs.msg import PoseWithCovariance
28 
29 def main():
30  objects = []
31 
32  # detect some objects
33  obj = AsrObject()
34  obj.type = 'Cup'
35  obj.identifier = '/map'
36  obj.header.frame_id = '/map'
37  poseWithCovariance = PoseWithCovariance()
38  poseWithCovariance.pose.position.x = 0.10103984720538714
39  poseWithCovariance.pose.position.y = -0.0140818815746599
40  poseWithCovariance.pose.position.z = 0.16235541952861962
41  poseWithCovariance.pose.orientation.w = 0.99553314478114419
42  poseWithCovariance.pose.orientation.x = -0.0074066082083501595
43  poseWithCovariance.pose.orientation.y = -0.030613037027407385
44  poseWithCovariance.pose.orientation.z = 0.037845601112626276
45  obj.sampledPoses.append(poseWithCovariance)
46  objects.append(obj)
47 
48  obj2 = AsrObject()
49  obj2.type = 'PlateDeep'
50  obj2.identifier = '/map'
51  obj2.header.frame_id = '/map'
52  poseWithCovariance.pose.position.x = 0
53  poseWithCovariance.pose.position.y = 0
54  poseWithCovariance.pose.position.z = 0
55  poseWithCovariance.pose.orientation.w = 1
56  poseWithCovariance.pose.orientation.x = 0.0
57  poseWithCovariance.pose.orientation.y = 0.0
58  poseWithCovariance.pose.orientation.z = 0.0
59  obj2.sampledPoses.append(poseWithCovariance)
60  objects.append(obj2)
61 
62  obj2 = AsrObject()
63  obj2.type = 'Smacks'
64  obj2.identifier = '/map'
65  obj2.header.frame_id = '/map'
66  poseWithCovariance.pose.position.x = 0.076435975386262803
67  poseWithCovariance.pose.position.y = -0.11043452060606049
68  poseWithCovariance.pose.position.z = 0.30012156632996601
69  poseWithCovariance.pose.orientation.w = 0.99788836565656736
70  poseWithCovariance.pose.orientation.x = -0.020827786229582479
71  poseWithCovariance.pose.orientation.y = -0.011928087026733992
72  poseWithCovariance.pose.orientation.z = 0.01032709707676762
73  obj2.sampledPoses.append(poseWithCovariance)
74  #objects.append(obj2)
75 
76 
77 
78  try:
79  rospy.wait_for_service('/psm_node', timeout=5)
80 
81  except rospy.exceptions.ROSException, e:
82  rospy.loginfo('Could not reach service')
83 
84  try:
85  service_proxy = rospy.ServiceProxy('/psm_node', psm_node)
86 
87  # call the service
88  # the parameters are: a list of already observed objects,
89  response = service_proxy(objects)
90 
91  # print the results
92  print("Number of generated hypothesis: " + str(len(response.pose_hypothesis.elements)))
93  print("All scene objects found: " + str(response.all_scene_objects_found));
94  #print(response)
95 
96  return response.pose_hypothesis.elements
97 
98 
99 
100  except rospy.ServiceException, e:
101  rospy.loginfo('Could not generate hyps')
102 
103  return []
104 
105 # This method catches the abort signal crtl + c
106 def signal_handler(signal, frame):
107  sys.exit(0)
108 
109 
110 
111 if __name__ == '__main__':
112  # catch ctrl + c
113  signal.signal(signal.SIGINT, signal_handler)
114 
115 
116  hypothesis_cloud = []
117 
118 
119  try:
120  hypothesis_cloud = main()
121  except rospy.ROSInterruptException: pass
122 
123 
124 
125 
126 
127 
128 
129 
130 
def signal_handler(signal, frame)


asr_recognizer_prediction_psm
Author(s): Braun Kai, Meißner Pascal
autogenerated on Wed Feb 19 2020 03:31:30