$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 00034 # Author: Bhaskara Marthi 00035 # 00036 # Given a database of stored objects, revisit the object locations 00037 # and rescan. 00038 00039 import roslib; roslib.load_manifest('semanticmodel') 00040 import rospy 00041 import optparse as op 00042 import threading 00043 import logging 00044 import mongo_ros as mr 00045 import actionlib as al 00046 from actionlib_msgs.msg import * 00047 from pr2_controllers_msgs.msg import * 00048 import move_base_msgs.msg as mbm 00049 import sensor_msgs.msg as sm 00050 import semanticmodel.srv as srv 00051 import nav_msgs.msg as nm 00052 from semanticmodel.msg import * 00053 import geometry_msgs.msg as gm 00054 from std_msgs.msg import Header 00055 from math import sin, cos 00056 import semanticmodel.db as sdb 00057 00058 log = logging.getLogger('world_model.diffs') 00059 00060 00061 class Node: 00062 "Holds the node state and ros interaction logic" 00063 00064 def __init__(self, run): 00065 "Initialize variables, set up ros comms" 00066 self.lock = threading.Lock() 00067 rospy.init_node('look_for_diffs') 00068 self.run1 = run 00069 self.db = rospy.get_param('semantic_db_name') 00070 self.path_pub = rospy.Publisher('plan', nm.Path) 00071 self.nav_client = al.SimpleActionClient('move_base', 00072 mbm.MoveBaseAction) 00073 log.info("Waiting for move_base action server") 00074 self.nav_client.wait_for_server() 00075 log.info("Got move_base action server.") 00076 00077 self.headclient = al.SimpleActionClient( 00078 '/head_traj_controller/point_head_action', PointHeadAction) 00079 log.info("Waiting for point_head action server.") 00080 self.headclient.wait_for_server() 00081 log.info("Got point_head server.") 00082 00083 def run(self): 00084 "Top level" 00085 # This used to switch to a second db and generate diffs, but no more 00086 self.navigate_viewpoints() 00087 00088 def find_blob(self, blobs, image): 00089 """ 00090 Our image messages don't contain the (x, y, z) coordinate of the blob, 00091 but we use them to figure out where to rescan from. Given a 00092 MessageCollection of blobs, and a particular image dictionary, return 00093 the (x, y, z) coordinate of the corresponding blob (where 00094 "corresponding" means "same id"), or None if it's all gone wrong. 00095 """ 00096 for blob in blobs.query({}, True): 00097 if blob['id'] == image['cluster_id']: 00098 return (blob['x'], blob['y'], blob['z']) 00099 return None 00100 00101 def navigate_viewpoints(self): 00102 images = mr.MessageCollection(self.db, 00103 sdb.collection_name(self.run1, 00104 'images'), 00105 sm.Image) 00106 blobs = mr.MessageCollection(self.db, 00107 sdb.collection_name(self.run1, 'blobs'), 00108 BlobMessage) 00109 seen_clusters = set() 00110 log.info("The locations are {0}". 00111 format([(m['x'], 00112 m['y'], 00113 m['cluster_id']) for m in images.query({}, True)])) 00114 clusters = list(images.query({}, True)) 00115 mb_goals = map(mb_goal, clusters) 00116 for i, cluster in enumerate(clusters): 00117 cluster_id = cluster['cluster_id'] 00118 if cluster_id in seen_clusters: 00119 log.info("Cluster {0} already seen. Skipping.".format(cluster_id)) 00120 continue 00121 seen_clusters.add(cluster_id) 00122 if rospy.is_shutdown(): 00123 break 00124 00125 # Visualize remaining path 00126 path = nm.Path() 00127 path.header.frame_id="/map" 00128 path.header.stamp = rospy.Time.now() 00129 path.poses = mb_goals[i:] 00130 self.path_pub.publish(path) 00131 log.info("Sending goal ({0[x]}, {0[y]}, {0[theta]} " 00132 "for cluster {0[cluster_id]}".format(cluster)) 00133 00134 # Send goal 00135 res = self.nav_client.send_goal_and_wait(\ 00136 mbm.MoveBaseGoal(mb_goals[i]), rospy.Duration(300.0)) 00137 log.info("Nav result was {0}".format(res)) 00138 XYZ = self.find_blob(blobs, cluster) 00139 if not XYZ: 00140 log.fatal("Couldn't find matching id! What the heck?") 00141 continue 00142 00143 00144 00145 log.info("Pointing the head at {0}.".format(XYZ)) 00146 g = PointHeadGoal() 00147 g.target.header.frame_id = "/map" 00148 g.target.header.stamp = rospy.Time.now() 00149 g.target.point.x = XYZ[0] 00150 g.target.point.y = XYZ[1] 00151 g.target.point.z = XYZ[2] 00152 g.min_duration = rospy.Duration(1.0) 00153 self.headclient.send_goal(g) 00154 # wait_for_result seems to be hanging. 00155 #self.headclient.wait_for_result() 00156 rospy.sleep(2.0) 00157 if self.headclient.get_state() != GoalStatus.SUCCEEDED: 00158 log.fatal("Head pointing failed! What? {0}".\ 00159 format(self.headclient.get_state())) 00160 log.info("Scanning...") 00161 rospy.sleep(3.0) 00162 g2 = PointHeadGoal() 00163 g.target.header.stamp = rospy.Time.now() 00164 g2.target.header.frame_id = '/base_link' 00165 g2.target.point.x = 3.0 00166 g2.min_duration = rospy.Duration(1.0) 00167 log.info("Pointing head forward") 00168 self.headclient.send_goal(g2) 00169 self.headclient.wait_for_result() 00170 self.nav_client.send_goal_and_wait(mbm.MoveBaseGoal(mb_goals[0]), 00171 rospy.Duration(300.0)) 00172 00173 00174 ############################################################ 00175 # Helper functions 00176 ############################################################ 00177 00178 def mb_goal(m): 00179 theta = m['theta'] 00180 q = gm.Quaternion(z=sin(theta/2), w=cos(theta/2)) 00181 p = gm.Point(m['x'], m['y'], 0) 00182 return gm.PoseStamped(pose=gm.Pose(position=p, orientation=q), 00183 header=Header(frame_id='/map', 00184 stamp=rospy.Time.now())) 00185 00186 00187 ############################################################ 00188 # Arg parsing, startup 00189 ############################################################ 00190 00191 if __name__ == "__main__": 00192 # Parse arguments 00193 parser = op.OptionParser() 00194 parser.add_option('--run', dest='run', 00195 help="The original run id") 00196 (options, _) = parser.parse_args(rospy.myargv()) 00197 00198 # Start node 00199 node = Node(options.run) 00200 node.run()