pointhead.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright (c) 2008, 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 # Author: Melonee Wise
30 
31 PKG = "pr2_mechanism_controllers"
32 
33 import roslib; roslib.load_manifest(PKG)
34 
35 import sys
36 import os
37 import string
38 from time import sleep
39 
40 import rospy
41 from geometry_msgs.msg import PointStamped, Point
42 from sensor_msgs.msg import JointState
43 
44 def point_head_client(pan, tilt):
45 
46  head_angles = rospy.Publisher('head_controller/command', JointState)
47  rospy.init_node('head_commander', anonymous=True)
48  sleep(1)
49  js = JointState()
50  js.name = ['head_pan_joint', 'head_tilt_joint'];
51  js.position = [pan,tilt];
52  head_angles.publish(js)
53  sleep(1)
54 
55 def point_head_cart_client(x,y,z,frame):
56 
57  head_angles = rospy.Publisher('head_controller/point_head', PointStamped)
58  rospy.init_node('head_commander', anonymous=True)
59  sleep(1)
60  head_angles.publish(PointStamped(rospy.Header(None, rospy.get_rostime(), frame), Point(x, y, z)))
61  sleep(1)
62 
63 
64 def usage():
65  return "%s [pan tilt] or [x,y,z,frame]"%sys.argv[0]
66 
67 if __name__ == "__main__":
68 
69  if len(sys.argv) < 3:
70  print usage()
71  sys.exit(1)
72  elif len(sys.argv) ==3:
73  point_head_client(float(sys.argv[1]), float(sys.argv[2]))
74  elif len(sys.argv) ==5:
75  point_head_cart_client(float(sys.argv[1]), float(sys.argv[2]), float(sys.argv[3]), sys.argv[4])
def point_head_client(pan, tilt)
Definition: pointhead.py:44
def point_head_cart_client(x, y, z, frame)
Definition: pointhead.py:55
def usage()
Definition: pointhead.py:64


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Mon Jun 10 2019 14:26:33