00001 #!/usr/bin/env python 00002 # Copyright (c) 2009, Willow Garage, Inc. 00003 # All rights reserved. 00004 # 00005 # Redistribution and use in source and binary forms, with or without 00006 # modification, are permitted provided that the following conditions are met: 00007 # 00008 # * Redistributions of source code must retain the above copyright 00009 # notice, this list of conditions and the following disclaimer. 00010 # * Redistributions in binary form must reproduce the above copyright 00011 # notice, this list of conditions and the following disclaimer in the 00012 # documentation and/or other materials provided with the distribution. 00013 # * Neither the name of the Willow Garage, Inc. nor the names of its 00014 # contributors may be used to endorse or promote products derived from 00015 # this software without specific prior written permission. 00016 # 00017 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 # POSSIBILITY OF SUCH DAMAGE. 00028 00029 import time 00030 00031 import roslib 00032 roslib.load_manifest('robot_mechanism_controllers') 00033 import rospy 00034 from std_msgs.msg import * 00035 00036 rospy.init_node('posture_publisher', disable_signals=True, anonymous=True) 00037 00038 controller = rospy.myargv()[1] 00039 posture = rospy.myargv()[2] 00040 00041 00042 pub_posture = rospy.Publisher("/%s/command_posture" % controller, Float64MultiArray) 00043 postures = { 00044 'off': [], 00045 'mantis': [0, 1, 0, -1, 3.14, -1, 3.14], 00046 'elbowupr': [-0.79,0,-1.6, 9999, 9999, 9999, 9999], 00047 'elbowupl': [0.79,0,1.6 , 9999, 9999, 9999, 9999], 00048 'old_elbowupr': [-0.79,0,-1.6, -0.79,3.14, -0.79,5.49], 00049 'old_elbowupl': [0.79,0,1.6, -0.79,3.14, -0.79,5.49], 00050 'elbowdownr': [-0.028262077316910873, 1.2946342642324222, -0.25785640577652386, -1.5498884526859626, -31.278913849571776, -1.0527644894829107, -1.8127318367654268], 00051 'elbowdownl': [-0.0088195719039858515, 1.2834828245284853, 0.20338442004843196, -1.5565279256852611, -0.096340012666916802, -1.0235018652439782, 1.7990893054129216] 00052 } 00053 00054 while not rospy.is_shutdown(): 00055 m = Float64MultiArray(data = postures[posture]) 00056 pub_posture.publish(m) 00057 time.sleep(1.0)