posture.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright (c) 2009, Willow Garage, Inc.
3 # All rights reserved.
4 #
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above copyright
11 # notice, this list of conditions and the following disclaimer in the
12 # documentation and/or other materials provided with the distribution.
13 # * Neither the name of the Willow Garage, Inc. nor the names of its
14 # contributors may be used to endorse or promote products derived from
15 # this software without specific prior written permission.
16 #
17 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 # POSSIBILITY OF SUCH DAMAGE.
28 
29 import time
30 
31 import roslib
32 roslib.load_manifest('robot_mechanism_controllers')
33 import rospy
34 from std_msgs.msg import *
35 
36 rospy.init_node('posture_publisher', disable_signals=True, anonymous=True)
37 
38 controller = rospy.myargv()[1]
39 posture = rospy.myargv()[2]
40 
41 
42 pub_posture = rospy.Publisher("/%s/command_posture" % controller, Float64MultiArray)
43 postures = {
44  'off': [],
45  'mantis': [0, 1, 0, -1, 3.14, -1, 3.14],
46  'elbowupr': [-0.79,0,-1.6, 9999, 9999, 9999, 9999],
47  'elbowupl': [0.79,0,1.6 , 9999, 9999, 9999, 9999],
48  'old_elbowupr': [-0.79,0,-1.6, -0.79,3.14, -0.79,5.49],
49  'old_elbowupl': [0.79,0,1.6, -0.79,3.14, -0.79,5.49],
50  'elbowdownr': [-0.028262077316910873, 1.2946342642324222, -0.25785640577652386, -1.5498884526859626, -31.278913849571776, -1.0527644894829107, -1.8127318367654268],
51  'elbowdownl': [-0.0088195719039858515, 1.2834828245284853, 0.20338442004843196, -1.5565279256852611, -0.096340012666916802, -1.0235018652439782, 1.7990893054129216]
52 }
53 
54 while not rospy.is_shutdown():
55  m = Float64MultiArray(data = postures[posture])
56  pub_posture.publish(m)
57  time.sleep(1.0)


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Mon Jun 10 2019 14:26:26