init.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 json
24 import os
25 import time as t
26 import __builtin__
27 import move
28 import subprocess, os, signal
29 import shutil
30 import sys
31 
32 from select import select
33 from asr_world_model.srv import EmptyViewportList, EmptyCompletePatterns, GetAllObjectsList
34 from geometry_msgs.msg import (Pose, PoseWithCovariance,
35  PoseWithCovarianceStamped, Point, Quaternion, Twist)
36 from asr_msgs.msg import AsrViewport
37 from common.evaluation_decorators import *
38 from nav_msgs.msg import Odometry
39 from std_srvs.srv import Empty
40 from asr_recognizer_prediction_ism.srv import SetLogDir
41 from os.path import expanduser
42 from direct_search.direct_search_states import execute_direct_search_action
43 
44 """
45 Contains all initialization states and useful methods for initialization.
46 """
47 def reset_ism():
48  """ Reset ism node counter"""
49  rospy.loginfo("Resetting rp_ism_node.")
50  try:
51  rospy.loginfo("wait_for_service /rp_ism_node/reset")
52  rospy.wait_for_service('/rp_ism_node/reset')
53  reset = rospy.ServiceProxy('/rp_ism_node/reset', Empty)
54  reset()
55  except (rospy.ServiceException, rospy.exceptions.ROSException), e:
56  rospy.logwarn(str(e))
57  rospy.logwarn("Could not reset rp_ism_node")
58 
59 
61  rospy.loginfo("Creating log folder.")
62  """
63  Creates folder for log files and copies scene_file to this folder if on
64  odete. Returns folder path
65  """
66  local_time = t.strftime("%Y-%m-%dT%H-%M-%S", t.localtime())
67  home = expanduser("~")
68  path = home + "/log/" + local_time
69  os.makedirs(path)
70  open(path + '/log.csv', 'a').close()
71 
72  # copy scene file to log dir
73  if True:
74  scene_path = None
75  try:
76  rospy.loginfo("wait_for_service /env/asr_world_model/get_all_objects_list")
77  rospy.wait_for_service('/env/asr_world_model/get_all_objects_list')
78  get_all_objects_list = rospy.ServiceProxy(
79  '/env/asr_world_model/get_all_objects_list', GetAllObjectsList)
80  scene_path = get_all_objects_list().scenePath
81 
82  rospy.loginfo("wait_for_service /rp_ism_node/set_log_dir")
83  rospy.wait_for_service('/rp_ism_node/set_log_dir')
84  set_log_dir = rospy.ServiceProxy(
85  'rp_ism_node/set_log_dir', SetLogDir)
86  set_log_dir(path)
87  except (rospy.ServiceException, rospy.exceptions.ROSException), e:
88  rospy.logwarn(str(e))
89 
90  if scene_path:
91  shutil.copy(scene_path,path)
92 
93  return path
94 
95 
97  rospy.loginfo("Clearing world_model.")
98  """
99  Delete all viewports and objects from world model
100  """
101  try:
102  rospy.loginfo("wait_for_service /env/asr_world_model/empty_found_object_list")
103  rospy.wait_for_service('/env/asr_world_model/empty_found_object_list')
104  rospy.loginfo("wait_for_service /env/asr_world_model/empty_viewport_list")
105  rospy.wait_for_service('/env/asr_world_model/empty_viewport_list')
106  rospy.loginfo("wait_for_service /env/asr_world_model/empty_complete_patterns")
107  rospy.wait_for_service('/env/asr_world_model/empty_complete_patterns')
108  clear_object_list = rospy.ServiceProxy('/env/asr_world_model/empty_found_object_list',
109  Empty)
110  clear_viewport_list = rospy.ServiceProxy('/env/asr_world_model/empty_viewport_list',
111  EmptyViewportList)
112  empty_complete_patterns = rospy.ServiceProxy('/env/asr_world_model/empty_complete_patterns',
113  EmptyCompletePatterns)
114  clear_object_list()
115  clear_viewport_list('all')
116  empty_complete_patterns()
117  except (rospy.ServiceException, rospy.exceptions.ROSException) as e:
118  rospy.logwarn(e)
119  rospy.logwarn("Could not clear world model")
120 
121 
123  rospy.loginfo("Clearing costmap.")
124  """
125  Clears costmap from move base
126  """
127  try:
128  rospy.loginfo("wait_for_service /move_base/clear_costmaps")
129  rospy.wait_for_service('/move_base/clear_costmaps')
130  clear_costmaps = rospy.ServiceProxy('/move_base/clear_costmaps',
131  Empty)
132  clear_costmaps()
133  except (rospy.ServiceException, rospy.exceptions.ROSException) as e:
134  rospy.loginfo("Could not clear costmaps")
135 
137  initial_objects = []
138  rospy.loginfo("Object types to look for in the first step")
139  rospy.loginfo("Enter nothing if you want to look for all objects in the scene")
140  rospy.loginfo("They will only be used in indirect_search")
141  timeout = 0.1
142  while not rospy.is_shutdown():
143  # Wait for input while check if node is_shutdown
144  obj, _, _ = select([sys.stdin], [], [], timeout)
145  if obj:
146  currentLine = str(sys.stdin.readline().strip())
147  if currentLine is not "":
148  initial_objects.append(currentLine)
149  else:
150  break
151 
152  return initial_objects
153 
154 
155 def start_rosbag(path):
156  rospy.loginfo("Starting rosbag.")
157  """
158  Starts rosbag in the specified folder with the topics.
159  """
160 
161  #TODO move topics to settings file
162  rospy.loginfo("wait_for_service /rp_ism_node/set_log_dir")
163  rospy.wait_for_service('/rp_ism_node/set_log_dir')
164  posePredictionMarkersPublisherName = rospy.get_param("/rp_ism_node/posePredictionMarkersPublisherName")
165  sceneMarkersPublisherName = rospy.get_param("/rp_ism_node/sceneMarkersPosePredictionPublisherName")
166  visualization_topic = rospy.get_param("/rp_ism_node/sceneMarkersSceneRecognitionPublisherName")
167 
168  waypoints = rospy.get_param("/scene_exploration_sm/waypoints")
169 
170  stereo_visualization_marker = '/stereo/visualization_marker'
171  stereo_objects = '/stereo/objects'
172 
173  tf = rospy.get_param("/scene_exploration_sm/tf")
174  tf_static = rospy.get_param("/scene_exploration_sm/tf_static")
175  map = rospy.get_param("/scene_exploration_sm/map")
176  move_base_footprint_stamped = rospy.get_param("/scene_exploration_sm/move_base_footprint_stamped")
177  odom = rospy.get_param("/scene_exploration_sm/odom")
178  move_base_plan = rospy.get_param("/scene_exploration_sm/move_base_plan")
179  move_base_local_plan = rospy.get_param("/scene_exploration_sm/move_base_local_plan")
180  move_base_goal = rospy.get_param("/scene_exploration_sm/move_base_goal")
181  move_base_global_costmap = rospy.get_param("/scene_exploration_sm/move_base_global_costmap")
182  move_base_local_costmap = rospy.get_param("/scene_exploration_sm/move_base_local_costmap")
183  particlecloud = rospy.get_param("/scene_exploration_sm/particlecloud")
184 
185  rospy.loginfo("wait_for_service /nbv/trigger_old_frustum_visualization")
186  rospy.wait_for_service('/nbv/trigger_old_frustum_visualization')
187 
188  nbv_frustum_array = rospy.get_param("/nbv/frustumVisualization")
189  nbv_frustum_object = rospy.get_param("/nbv/frustumObjectsVisualization")
190  nbv_object_meshes = rospy.get_param("/nbv/objectsVisualization")
191  nbv_iteration_viz = rospy.get_param("/nbv/iterationVisualization")
192  nbv_object_normals = rospy.get_param("/nbv/objectNormalsVisualization")
193  nbv_cropbox = rospy.get_param("/nbv/cropBoxVisualization")
194  nbv_IK = rospy.get_param("/nbv/IKVisualization")
195 
196  rospy.loginfo("wait_for_service /env/asr_world_model/empty_found_object_list")
197  rospy.wait_for_service('/env/asr_world_model/empty_found_object_list')
198  world_model_found = '/env/asr_world_model/found_object_visualization'
199  constellation_fake = '/asr_fake_object_recognition/constellation_visualization'
200 
201  container_status = rospy.get_param("/scene_exploration_sm/container_status")
202  container_init = rospy.get_param("/scene_exploration_sm/container_init")
203  container_structure = rospy.get_param("/scene_exploration_sm/container_structure")
204 
205  threeD_models_topic = rospy.get_param("/scene_exploration_sm/threeD_models_topic")
206 
207 
208  topics=[posePredictionMarkersPublisherName, sceneMarkersPublisherName, visualization_topic, waypoints,
209  stereo_visualization_marker, stereo_objects, tf, tf_static, map,move_base_footprint_stamped, odom,
210  move_base_plan, move_base_local_plan, move_base_goal, move_base_global_costmap, move_base_local_costmap, particlecloud,
211  nbv_frustum_array, nbv_frustum_object, nbv_object_meshes, nbv_iteration_viz, nbv_object_normals, nbv_cropbox, nbv_IK,
212  world_model_found, constellation_fake, container_status, container_init, container_structure, threeD_models_topic]
213 
214  command = "rosbag record -b 1000 -O OBJ${1}"
215  for topic in topics:
216  command += " " + topic
217  print command
218  rosbag_proc = subprocess.Popen(command, stdin=subprocess.PIPE, shell=True, cwd=path)
219  return rosbag_proc
220 
221 
222 class ObjectSearchInit(smach.State):
223 
224  def __init__(self):
225  smach.State.__init__(self,
226  outcomes=['succeeded', 'aborted'])
227 
228  @log
229  @timed
230  def execute(self, userdata):
231  rospy.loginfo('Executing OBJECT_SEARCH_INIT')
232 
233  clear_costmap()
235  reset_ism()
236  result = execute_direct_search_action("Reset")
237  if (result == 'aborted'):
238  return 'aborted'
239 
240  return 'succeeded'
241 
242 
243 class SearchInit(smach.State):
244  """
245  Initial state for object search.
246  """
247 
248  def __init__(self, searched_object_types=None):
249  smach.State.__init__(self,
250  outcomes=['succeeded', 'aborted'],
251  output_keys=['searched_object_types'])
252  self.searched_object_types = searched_object_types
253 
254  @log
255  @timed
256  def execute(self, userdata):
257  rospy.loginfo('Executing SEARCH_INIT')
258 
259  clear_costmap()
261  reset_ism()
262  first_object_types_to_search = []
263  if not self.searched_object_types:
264  try:
265  rospy.loginfo("wait_for_service /env/asr_world_model/get_all_objects_list")
266  rospy.wait_for_service('/env/asr_world_model/get_all_objects_list')
267  get_all_objects_list = rospy.ServiceProxy(
268  '/env/asr_world_model/get_all_objects_list', GetAllObjectsList)
269  for object_type_and_id in get_all_objects_list().allObjects:
270  first_object_types_to_search.append(object_type_and_id.type)
271  except (rospy.ServiceException, rospy.exceptions.ROSException), e:
272  rospy.logwarn(str(e))
273  return 'aborted'
274  else:
275  first_object_types_to_search = self.searched_object_types
276 
277  userdata.searched_object_types = first_object_types_to_search
278 
279  return 'succeeded'
280 
def __init__(self, searched_object_types=None)
Definition: init.py:248
def start_rosbag(path)
Definition: init.py:155
def reset_ism()
Definition: init.py:47
def create_log_folder()
Definition: init.py:60
def clear_costmap()
Definition: init.py:122
def execute_direct_search_action(action_command, searched_object_types_and_ids=None)
def get_initial_objects()
Definition: init.py:136
def execute(self, userdata)
Definition: init.py:230
def clear_world_model()
Definition: init.py:96
def execute(self, userdata)
Definition: init.py:256


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