$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_launch') 00035 import rospy 00036 import yaml 00037 import sys 00038 import actionlib 00039 import joint_states_settler.msg 00040 import monocam_settler.msg 00041 import image_cb_detector.msg 00042 import interval_intersection.msg 00043 import time 00044 from trajectory_msgs.msg import JointTrajectory 00045 from trajectory_msgs.msg import JointTrajectoryPoint 00046 00047 00048 # Puts the system in a specific configuration, in preparation for collecting a sample 00049 class ConfigManager: 00050 def __init__(self, cam_config, chain_config, laser_config, controller_config): 00051 00052 # Set up Cameras 00053 print "Constructing Cameras:" 00054 self._cam_managers = dict() 00055 for name in cam_config.keys(): 00056 print " Constructing CamID [%s]" % name 00057 self._cam_managers[name] = CameraConfigManager(name, cam_config[name]) 00058 00059 # Set up Chains 00060 print "Constructing Chains:" 00061 self._chain_managers = dict() 00062 for name in chain_config.keys(): 00063 print " Constructing ChainID [%s]" % name 00064 self._chain_managers[name] = ChainConfigManager(name, chain_config[name]) 00065 00066 # Set up Controllers 00067 print "Constructing Controllers:" 00068 self._controller_managers = dict() 00069 for controller_id in controller_config.keys(): 00070 print " Constructing ControllerID [%s]" % controller_id 00071 self._controller_managers[controller_id] = ControllerCmdManager(controller_id, controller_config[controller_id]) 00072 00073 # Set up interval_intersection 00074 self._intersect_ac = actionlib.SimpleActionClient("interval_intersection_config", interval_intersection.msg.ConfigAction) 00075 00076 def reconfigure(self, config): 00077 # Reconfigure Interval Intersection 00078 00079 intersect_goal = interval_intersection.msg.ConfigGoal(); 00080 #intersect_goal.topics = [x['cam_id'] for x in config["camera_measurements"]] + [x['chain_id'] for x in config["joint_measurements"]] + [x['laser_id'] for x in config["laser_measurements"]] 00081 intersect_goal.topics = [x['cam_id'] for x in config["camera_measurements"]] + [x['chain_id'] for x in config["joint_measurements"]] 00082 self._intersect_ac.send_goal(intersect_goal) 00083 00084 # Reconfigure the cameras 00085 print "Reconfiguring The Cameras" 00086 for cur_cam in config["camera_measurements"]: 00087 self._cam_managers[cur_cam["cam_id"]].reconfigure(cur_cam["config"]) 00088 00089 # Reconfigure the chains 00090 print "Reconfiguring The Chains" 00091 for cur_chain in config["joint_measurements"]: 00092 self._chain_managers[cur_chain["chain_id"]].reconfigure(cur_chain["config"]) 00093 00094 # Send controller commands 00095 print "Sending Controller Commands" 00096 for cur_controller in config["joint_commands"]: 00097 self._controller_managers[cur_controller["controller"]].send_command(cur_controller) 00098 00099 def stop(self): 00100 pass 00101 #print "Stopping the capture pipeline... not implemented yet" 00102 00103 # Handles changing the configuration of a joint_states_settler 00104 class ChainConfigManager: 00105 def __init__(self, chain_id, configs): 00106 self._chain_id = chain_id 00107 self._configs = configs 00108 if not self.validate(): 00109 raise Exception("Invalid chain description") 00110 00111 # Initialize the ActionClient and state 00112 self._settler_ac = actionlib.SimpleActionClient(self._configs["settler_config"], joint_states_settler.msg.ConfigAction) 00113 self._state = "idle" 00114 00115 # Check to make sure that config dict has all the necessary fields. Todo: Currently a stub 00116 def validate(self): 00117 return True 00118 00119 # Reconfigure this chain's processing pipeline to the specified configuration. Do nothing if 00120 # we're already in the correct configuration 00121 def reconfigure(self, next_config_name): 00122 if self._state == next_config_name: 00123 print " %s: Configured correctly as [%s]" % (self_.chain_id, self._state) 00124 else: 00125 print " %s: Need to transition [%s] -> [%s]" % (self._chain_id, self._state, next_config_name) 00126 00127 next_config = self._configs["configs"][next_config_name] 00128 settler_config = next_config["settler"] 00129 # Convert the settler's configuration from a dictionary to a ROS message 00130 goal = joint_states_settler.msg.ConfigGoal() 00131 goal.joint_names = settler_config["joint_names"] 00132 goal.tolerances = settler_config["tolerances"] 00133 goal.max_step = roslib.rostime.Duration(settler_config["max_step"]) 00134 goal.cache_size = settler_config["cache_size"] 00135 00136 # Send the goal out 00137 self._settler_ac.send_goal(goal) 00138 00139 # Todo: Need to add code that waits for goal to activate 00140 00141 00142 # Handles changing the configuration of the image pipeline associated with a camera 00143 class CameraConfigManager: 00144 def __init__(self, cam_id, configs): 00145 self._cam_id = cam_id 00146 self._configs = configs 00147 if not self.validate(): 00148 raise Exception("Invalid camera description") 00149 00150 # Initialize the ActionClients and state 00151 self._settler_ac = actionlib.SimpleActionClient(self._configs["settler_config"], monocam_settler.msg.ConfigAction) 00152 self._led_detector_ac = actionlib.SimpleActionClient(self._configs["cb_detector_config"], image_cb_detector.msg.ConfigAction) 00153 self._state = "idle" 00154 00155 # Check to make sure that config dict has all the necessary fields. Todo: Currently a stub 00156 def validate(self): 00157 return True 00158 00159 # Reconfigure this chain's processing pipeline to the specified configuration. Do nothing if 00160 # we're already in the correct configuration 00161 def reconfigure(self, next_config_name): 00162 if self._state == next_config_name: 00163 print " %s: Configured correctly as [%s]" % (self_.cam_id, self._state) 00164 else: 00165 print " %s: Need to transition [%s] -> [%s]" % (self._cam_id, self._state, next_config_name) 00166 00167 next_config = self._configs["configs"][next_config_name] 00168 00169 # Send the Settler's Goal 00170 settler_config = next_config["settler"] 00171 goal = monocam_settler.msg.ConfigGoal() 00172 goal.tolerance = settler_config["tolerance"] 00173 goal.ignore_failures = settler_config["ignore_failures"] 00174 goal.max_step = roslib.rostime.Duration(settler_config["max_step"]) 00175 goal.cache_size = settler_config["cache_size"] 00176 self._settler_ac.send_goal(goal) 00177 00178 # Send the CB Detector Goal 00179 cb_detector_config = next_config["cb_detector"] 00180 if not cb_detector_config["active"]: 00181 print "Not sure yet how to deal with inactive cb_detector" 00182 goal = image_cb_detector.msg.ConfigGoal() 00183 goal.num_x = cb_detector_config["num_x"] 00184 goal.num_y = cb_detector_config["num_y"] 00185 goal.spacing_x = 1.0 # Hardcoded garbage value. Should eventually be removed from the msg 00186 goal.spacing_y = 1.0 # Hardcoded garbage value. Should eventually be removed from the msg 00187 goal.width_scaling = cb_detector_config["width_scaling"] 00188 goal.height_scaling = cb_detector_config["height_scaling"] 00189 goal.subpixel_window = cb_detector_config["subpixel_window"] 00190 goal.subpixel_zero_zone = cb_detector_config["subpixel_zero_zone"] 00191 self._led_detector_ac.send_goal(goal) 00192 00193 # Send the LED Detector Goal 00194 led_detector_config = next_config["led_detector"] 00195 if led_detector_config["active"]: 00196 print "Not sure yet how to deal with an active led_detector" 00197 00198 # Todo: Need to add code that waits for goal to activate 00199 00200 # Handles publishing commands to a trajectory controller 00201 class ControllerCmdManager: 00202 def __init__(self, controller_id, config): 00203 self._controller_id = controller_id 00204 self._config = config 00205 if not self.validate(): 00206 raise Exception("Invalid chain description") 00207 00208 # Initialize the Publisher 00209 self._pub = rospy.Publisher(self._config["topic"], JointTrajectory) 00210 00211 # Check to make sure that config dict has all the necessary fields. Todo: Currently a stub 00212 def validate(self): 00213 return True 00214 00215 # Reconfigure this chain's processing pipeline to the specified configuration. Do nothing if 00216 # we're already in the correct configuration 00217 def send_command(self, cmd): 00218 print " Sending cmd to controller [%s]" % self._controller_id 00219 cmd_msg = JointTrajectory() 00220 cmd_msg.header.stamp = rospy.Time().now() 00221 cmd_msg.joint_names = self._config["joint_names"] 00222 cmd_msg.points = [self._build_segment(x) for x in cmd["segments"]] 00223 self._pub.publish(cmd_msg) 00224 00225 def _build_segment(self, config): 00226 segment = JointTrajectoryPoint() 00227 segment.positions = config["positions"] 00228 segment.velocities = [0] * len(config["positions"]) 00229 segment.time_from_start = rospy.Duration(config["duration"]) 00230 return segment 00231 00232 00233