4 Copyright (c) 2016, Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Marek Felix, Meissner Pascal, Trautmann Jeremias, Wittenbeck Valerij 8 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 10 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 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. 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. 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. 28 import subprocess, os, signal
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
45 Contains all initialization states and useful methods for initialization. 48 """ Reset ism node counter""" 49 rospy.loginfo(
"Resetting rp_ism_node.")
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)
55 except (rospy.ServiceException, rospy.exceptions.ROSException), e:
57 rospy.logwarn(
"Could not reset rp_ism_node")
61 rospy.loginfo(
"Creating log folder.")
63 Creates folder for log files and copies scene_file to this folder if on 64 odete. Returns folder path 66 local_time = t.strftime(
"%Y-%m-%dT%H-%M-%S", t.localtime())
67 home = expanduser(
"~")
68 path = home +
"/log/" + local_time
70 open(path +
'/log.csv',
'a').close()
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
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)
87 except (rospy.ServiceException, rospy.exceptions.ROSException), e:
91 shutil.copy(scene_path,path)
97 rospy.loginfo(
"Clearing world_model.")
99 Delete all viewports and objects from world model 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',
110 clear_viewport_list = rospy.ServiceProxy(
'/env/asr_world_model/empty_viewport_list',
112 empty_complete_patterns = rospy.ServiceProxy(
'/env/asr_world_model/empty_complete_patterns',
113 EmptyCompletePatterns)
115 clear_viewport_list(
'all')
116 empty_complete_patterns()
117 except (rospy.ServiceException, rospy.exceptions.ROSException)
as e:
119 rospy.logwarn(
"Could not clear world model")
123 rospy.loginfo(
"Clearing costmap.")
125 Clears costmap from move base 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',
133 except (rospy.ServiceException, rospy.exceptions.ROSException)
as e:
134 rospy.loginfo(
"Could not clear costmaps")
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")
142 while not rospy.is_shutdown():
144 obj, _, _ = select([sys.stdin], [], [], timeout)
146 currentLine = str(sys.stdin.readline().strip())
147 if currentLine
is not "":
148 initial_objects.append(currentLine)
152 return initial_objects
156 rospy.loginfo(
"Starting rosbag.")
158 Starts rosbag in the specified folder with the topics. 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")
168 waypoints = rospy.get_param(
"/scene_exploration_sm/waypoints")
170 stereo_visualization_marker =
'/stereo/visualization_marker' 171 stereo_objects =
'/stereo/objects' 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")
185 rospy.loginfo(
"wait_for_service /nbv/trigger_old_frustum_visualization")
186 rospy.wait_for_service(
'/nbv/trigger_old_frustum_visualization')
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")
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' 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")
205 threeD_models_topic = rospy.get_param(
"/scene_exploration_sm/threeD_models_topic")
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]
214 command =
"rosbag record -b 1000 -O OBJ${1}" 216 command +=
" " + topic
218 rosbag_proc = subprocess.Popen(command, stdin=subprocess.PIPE, shell=
True, cwd=path)
225 smach.State.__init__(self,
226 outcomes=[
'succeeded',
'aborted'])
231 rospy.loginfo(
'Executing OBJECT_SEARCH_INIT')
237 if (result ==
'aborted'):
245 Initial state for object search. 249 smach.State.__init__(self,
250 outcomes=[
'succeeded',
'aborted'],
251 output_keys=[
'searched_object_types'])
257 rospy.loginfo(
'Executing SEARCH_INIT')
262 first_object_types_to_search = []
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))
277 userdata.searched_object_types = first_object_types_to_search
def __init__(self, searched_object_types=None)
def execute_direct_search_action(action_command, searched_object_types_and_ids=None)
def get_initial_objects()
def execute(self, userdata)
def execute(self, userdata)