$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, 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 Willow Garage, Inc. 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 import roslib; roslib.load_manifest('pr2_calibration_executive') 00035 import sys 00036 import threading 00037 00038 import rospy 00039 from calibration_msgs.msg import * 00040 import sensor_msgs.msg 00041 00042 import message_filters 00043 00044 00045 class ChainManager: 00046 def __init__(self, chain_id, callback, *cb_args): 00047 self._chain_id = chain_id 00048 self._callback = callback 00049 self._cb_args = cb_args 00050 self._mode = "off" 00051 00052 self._lock = threading.Lock() 00053 00054 self._chain_sub = rospy.Subscriber(chain_id + "/chain_state", sensor_msgs.msg.JointState, self.callback) 00055 00056 def callback(self, msg): 00057 self._lock.acquire() 00058 if self._mode is "on": 00059 # Populate measurement message 00060 m_msg = ChainMeasurement() 00061 m_msg.header.stamp = msg.header.stamp 00062 m_msg.chain_id = self._chain_id 00063 m_msg.chain_state = msg 00064 self._callback(self._chain_id, m_msg, *self._cb_args) 00065 self._lock.release() 00066 00067 def enable(self): 00068 self._lock.acquire() 00069 self._mode = "on" 00070 self._lock.release() 00071 00072 def disable(self): 00073 self._lock.acquire() 00074 self._mode = "off" 00075 self._lock.release() 00076 00077 class CamManager: 00078 def __init__(self, cam_id, callback, *cb_args): 00079 self._cam_id = cam_id 00080 self._callback = callback 00081 self._cb_args = cb_args 00082 self._mode = "off" 00083 00084 self._lock = threading.Lock() 00085 00086 # How do I specify a queue size of 1? 00087 self._cam_info_sub = message_filters.Subscriber(cam_id + "/camera_info", sensor_msgs.msg.CameraInfo) 00088 self._features_sub = message_filters.Subscriber(cam_id + "/features", calibration_msgs.msg.CalibrationPattern) 00089 self._image_sub = message_filters.Subscriber(cam_id + "/image", sensor_msgs.msg.Image) 00090 self._image_rect_sub=message_filters.Subscriber(cam_id + "/image_rect", sensor_msgs.msg.Image) 00091 00092 self._verbose_sync = message_filters.TimeSynchronizer([self._cam_info_sub, self._features_sub, self._image_sub, self._image_rect_sub], 10) 00093 self._minimal_sync = message_filters.TimeSynchronizer([self._cam_info_sub, self._features_sub], 10) 00094 00095 self._verbose_sync.registerCallback(self.verbose_callback) 00096 self._minimal_sync.registerCallback(self.minimal_callback) 00097 00098 def verbose_callback(self, cam_info, features, image, image_rect): 00099 self._lock.acquire() 00100 if self._mode is "verbose": 00101 # Populate measurement message 00102 msg = CameraMeasurement() 00103 msg.header.stamp = cam_info.header.stamp 00104 msg.camera_id = self._cam_id 00105 msg.image_points = features.image_points 00106 msg.cam_info = cam_info 00107 msg.verbose = True 00108 msg.image = image 00109 msg.image_rect = image_rect 00110 msg.features = features 00111 self._callback(self._cam_id, msg, *self._cb_args) 00112 self._lock.release() 00113 00114 def minimal_callback(self, cam_info, features): 00115 self._lock.acquire() 00116 if self._mode is "minimal": 00117 # Populate measurement message 00118 msg = CameraMeasurement() 00119 msg.header.stamp = cam_info.header.stamp 00120 msg.camera_id = self._cam_id 00121 msg.image_points = features.image_points 00122 msg.cam_info = cam_info 00123 msg.verbose = False 00124 self._callback(self._cam_id, msg, *self._cb_args) 00125 self._lock.release() 00126 00127 def enable(self, verbose=False): 00128 self._lock.acquire() 00129 if verbose: 00130 self._mode = "verbose" 00131 else: 00132 self._mode = "minimal" 00133 self._lock.release() 00134 00135 def disable(self): 00136 self._lock.acquire() 00137 self._mode = "off" 00138 self._lock.release() 00139 00140 00141 class LaserManager: 00142 def __init__(self, laser_id, callback, *cb_args): 00143 self._laser_id = laser_id 00144 self._callback = callback 00145 self._cb_args = cb_args 00146 self._mode = "off" 00147 00148 self._lock = threading.Lock() 00149 00150 # How do I specify a queue size of 1? 00151 self._snapshot_sub = message_filters.Subscriber(laser_id + "/snapshot", calibration_msgs.msg.DenseLaserSnapshot) 00152 self._laser_image_sub = message_filters.Subscriber(laser_id + "/laser_image", sensor_msgs.msg.Image) 00153 self._image_features_sub = message_filters.Subscriber(laser_id + "/image_features", calibration_msgs.msg.CalibrationPattern) 00154 self._joint_features_sub = message_filters.Subscriber(laser_id + "/joint_features", calibration_msgs.msg.JointStateCalibrationPattern) 00155 self._duration_sub = message_filters.Subscriber(laser_id + "/laser_interval", calibration_msgs.msg.IntervalStamped) 00156 00157 self._verbose_sync = message_filters.TimeSynchronizer([self._snapshot_sub, 00158 self._laser_image_sub, 00159 self._image_features_sub, 00160 self._joint_features_sub, 00161 self._duration_sub], 10) 00162 self._minimal_sync = message_filters.TimeSynchronizer([self._joint_features_sub, 00163 self._duration_sub], 10) 00164 00165 self._verbose_sync.registerCallback(self.verbose_callback) 00166 self._minimal_sync.registerCallback(self.minimal_callback) 00167 00168 def verbose_callback(self, snapshot, laser_image, image_features, joint_features, laser_duration): 00169 self._lock.acquire() 00170 #print "In verbose sensor_manager callback. Mode = %s" % self._mode 00171 if self._mode is "verbose": 00172 # Populate measurement message 00173 msg = LaserMeasurement() 00174 msg.laser_id = self._laser_id 00175 msg.joint_points = joint_features.joint_points 00176 msg.verbose = True 00177 msg.snapshot = snapshot 00178 msg.laser_image = laser_image 00179 msg.image_features = image_features 00180 msg.joint_features = joint_features 00181 self._callback(self._laser_id, msg, laser_duration.interval.start, laser_duration.interval.end, *self._cb_args) 00182 self._lock.release() 00183 00184 def minimal_callback(self, joint_features, laser_duration): 00185 self._lock.acquire() 00186 #print "In minimal sensor_manager callback. Mode = %s" % self._mode 00187 if self._mode is "minimal": 00188 # Populate measurement message 00189 msg = LaserMeasurement() 00190 msg.laser_id = self._laser_id 00191 msg.joint_points = joint_features.joint_points 00192 msg.verbose = True 00193 self._callback(self._laser_id, msg, laser_duration.interval.start, laser_duration.interval.end, *self._cb_args) 00194 self._lock.release() 00195 00196 def enable(self, verbose=False): 00197 self._lock.acquire() 00198 if verbose: 00199 self._mode = "verbose" 00200 else: 00201 self._mode = "minimal" 00202 self._lock.release() 00203 00204 def disable(self): 00205 self._lock.acquire() 00206 self._mode = "off" 00207 self._lock.release() 00208