record_states.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 Copyright (c) 2016, Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Marek Felix, Meissner Pascal, Trautmann Jeremias, Wittenbeck Valerij
5 
6 All rights reserved.
7 
8 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
9 
10 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
11 
12 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.
13 
14 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.
15 
16 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.
17 '''
18 
19 import roslib
20 import rospy
21 import smach
22 import smach_ros
23 import __builtin__
24 import tf
25 import math
26 import os.path
27 
28 from lxml import etree
29 
30 from geometry_msgs.msg import Pose, Point, Quaternion
31 import common.state_acquisition as state_acquisition
32 from common.evaluation_decorators import *
33 
34 class CropboxStateRecording(smach.State):
35  """
36  Please enter some comments here!
37  """
38 
39  def __init__(self):
40  smach.State.__init__(
41  self,
42  outcomes=['succeeded', 'aborted'],
43  input_keys=['goal_camera_pose',
44  'goal_robot_pose',
45  'goal_ptu_position',
46  'deactivated_object_normals_count'])
47  self.isInitDone = 0
48 
49 
50  def initNode(self):
51  rospy.loginfo('Init STATE_RECORDING')
52  self.isInitDone = 1
53 
54  self.cropBoxRecordingPath = rospy.get_param('/scene_exploration_sm/CropBoxRecordingPath')
55  rospy.loginfo("CropBoxRecordingPath: " + str(self.cropBoxRecordingPath))
57 
58 
59  self.xmlTemplate = """<state>
60  <goal_camera_pose>
61  <position x="%(goal_camera_pose.position.x)s" y="%(goal_camera_pose.position.y)s" z="%(goal_camera_pose.position.z)s"/>
62  <orientation x="%(goal_camera_pose.orientation.x)s" y="%(goal_camera_pose.orientation.y)s" z="%(goal_camera_pose.orientation.z)s" w="%(goal_camera_pose.orientation.w)s" />
63  </goal_camera_pose>
64  <goal_robot_pose>
65  <position x="%(goal_robot_pose.position.x)s" y="%(goal_robot_pose.position.y)s" z="%(goal_robot_pose.position.z)s"/>
66  <orientation x="%(goal_robot_pose.orientation.x)s" y="%(goal_robot_pose.orientation.y)s" z="%(goal_robot_pose.orientation.z)s" w="%(goal_robot_pose.orientation.w)s" />
67  </goal_robot_pose>
68  <goal_ptu_position pan="%(goal_ptu_position.pan)s" tilt="%(goal_ptu_position.tilt)s" />
69  <deactivated_object_normals_count count="%(deactivated_object_normals_count)s" />
70  </state>"""
71 
72 
73  @log
74  @key_press
75  @timed
76  def execute(self, userdata):
77  rospy.loginfo('Executing STATE_RECORDING')
78  if (self.isInitDone == 0):
79  if self.initNode() == 'aborted':
80  return 'aborted'
81 
82  data = {'goal_camera_pose.position.x':str(userdata.goal_camera_pose.position.x),
83  'goal_camera_pose.position.y':str(userdata.goal_camera_pose.position.y),
84  'goal_camera_pose.position.z':str(userdata.goal_camera_pose.position.z),
85  'goal_camera_pose.orientation.x':str(userdata.goal_camera_pose.orientation.x),
86  'goal_camera_pose.orientation.y':str(userdata.goal_camera_pose.orientation.y),
87  'goal_camera_pose.orientation.z':str(userdata.goal_camera_pose.orientation.z),
88  'goal_camera_pose.orientation.w':str(userdata.goal_camera_pose.orientation.w),
89  'goal_robot_pose.position.x':str(userdata.goal_robot_pose.position.x),
90  'goal_robot_pose.position.y':str(userdata.goal_robot_pose.position.y),
91  'goal_robot_pose.position.z':str(userdata.goal_robot_pose.position.z),
92  'goal_robot_pose.orientation.x':str(userdata.goal_robot_pose.orientation.x),
93  'goal_robot_pose.orientation.y':str(userdata.goal_robot_pose.orientation.y),
94  'goal_robot_pose.orientation.z':str(userdata.goal_robot_pose.orientation.z),
95  'goal_robot_pose.orientation.w':str(userdata.goal_robot_pose.orientation.w),
96  'goal_ptu_position.pan':str(userdata.goal_ptu_position[0]),
97  'goal_ptu_position.tilt':str(userdata.goal_ptu_position[1]),
98  'deactivated_object_normals_count':str(userdata.deactivated_object_normals_count)}
99 
100  addXml(self.cropBoxRecordingPath, self.xmlTemplate%data)
101 
102  return 'succeeded'
103 
104 
105 class GridInitStateRecording(smach.State):
106  """
107  Please enter some comments here!
108  """
109 
110  def __init__(self):
111  smach.State.__init__(
112  self,
113  outcomes=['succeeded', 'aborted'],
114  input_keys=['goal_robot_pose',
115  'goal_ptu_position',])
116  self.isInitDone = 0
117 
118 
119  def initNode(self):
120  rospy.loginfo('Init STATE_RECORDING')
121  self.isInitDone = 1
122 
123  self.initializedGridFilePath = rospy.get_param('/scene_exploration_sm/initializedGridFilePath')
124  rospy.loginfo("initializedGridFilePath: " + str(self.initializedGridFilePath))
126 
127 
128  self.xmlTemplate = """<state>
129  <goal_camera_pose>
130  <position x="%(goal_camera_pose.position.x)s" y="%(goal_camera_pose.position.y)s" z="%(goal_camera_pose.position.z)s"/>
131  <orientation x="%(goal_camera_pose.orientation.x)s" y="%(goal_camera_pose.orientation.y)s" z="%(goal_camera_pose.orientation.z)s" w="%(goal_camera_pose.orientation.w)s" />
132  </goal_camera_pose>
133  <goal_robot_pose>
134  <position x="%(goal_robot_pose.position.x)s" y="%(goal_robot_pose.position.y)s" z="%(goal_robot_pose.position.z)s"/>
135  <orientation x="%(goal_robot_pose.orientation.x)s" y="%(goal_robot_pose.orientation.y)s" z="%(goal_robot_pose.orientation.z)s" w="%(goal_robot_pose.orientation.w)s" />
136  </goal_robot_pose>
137  <goal_ptu_position pan="%(goal_ptu_position.pan)s" tilt="%(goal_ptu_position.tilt)s" />
138  </state>"""
139 
140 
141  @log
142  @key_press
143  @timed
144  def execute(self, userdata):
145  rospy.loginfo('Executing STATE_RECORDING')
146  if (self.isInitDone == 0):
147  if self.initNode() == 'aborted':
148  return 'aborted'
149 
150  current_camera_pose = state_acquisition.get_camera_pose_cpp()
151 
152  data = {'goal_camera_pose.position.x':str(current_camera_pose.position.x),
153  'goal_camera_pose.position.y':str(current_camera_pose.position.y),
154  'goal_camera_pose.position.z':str(current_camera_pose.position.z),
155  'goal_camera_pose.orientation.x':str(current_camera_pose.orientation.x),
156  'goal_camera_pose.orientation.y':str(current_camera_pose.orientation.y),
157  'goal_camera_pose.orientation.z':str(current_camera_pose.orientation.z),
158  'goal_camera_pose.orientation.w':str(current_camera_pose.orientation.w),
159  'goal_robot_pose.position.x':str(userdata.goal_robot_pose.position.x),
160  'goal_robot_pose.position.y':str(userdata.goal_robot_pose.position.y),
161  'goal_robot_pose.position.z':str(userdata.goal_robot_pose.position.z),
162  'goal_robot_pose.orientation.x':str(userdata.goal_robot_pose.orientation.x),
163  'goal_robot_pose.orientation.y':str(userdata.goal_robot_pose.orientation.y),
164  'goal_robot_pose.orientation.z':str(userdata.goal_robot_pose.orientation.z),
165  'goal_robot_pose.orientation.w':str(userdata.goal_robot_pose.orientation.w),
166  'goal_ptu_position.pan':str(userdata.goal_ptu_position[0]),
167  'goal_ptu_position.tilt':str(userdata.goal_ptu_position[1])}
168 
169 
171  return 'succeeded'
172 
173 
174 def initFile(path):
175  if os.path.isfile(path):
176  rospy.loginfo("File " + path + " does exists and will be erased.")
177  open(path, 'w').close()
178 
179  with open(path, "w+") as xmlFile:
180  xmlFile.write("""<root></root>""")
181 
182 def addXml(path, xmlToAdd):
183  parser = etree.XMLParser(remove_blank_text=True)
184  tree = etree.parse(path, parser)
185 
186  root = tree.getroot()
187  new_state = etree.XML(xmlToAdd, parser)
188  root.append(new_state)
189  # Make pretty XML
190  tree._setroot(etree.fromstring(etree.tostring(root, encoding='UTF-8', pretty_print=True)))
191 
192  tree.write(path)


asr_state_machine
Author(s): Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Marek Felix, Meißner Pascal, Trautmann Jeremias, Wittenbeck Valerij
autogenerated on Mon Feb 28 2022 21:53:50