From: <mm...@us...> - 2009-07-16 00:47:14
|
Revision: 18932 http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18932&view=rev Author: mmwise Date: 2009-07-16 00:47:12 +0000 (Thu, 16 Jul 2009) Log Message: ----------- changed to use the new head controller topic Modified Paths: -------------- pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py Modified: pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py =================================================================== --- pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py 2009-07-16 00:45:07 UTC (rev 18931) +++ pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py 2009-07-16 00:47:12 UTC (rev 18932) @@ -39,19 +39,27 @@ import rospy from robot_msgs.msg import PointStamped, Point -from robot_msgs.msg import JointCmd +from mechanism_msgs.msg import JointStates, JointState def point_head_client(pan, tilt): - head_angles = rospy.Publisher('head_controller/set_command_array', JointCmd) + head_angles = rospy.Publisher('head_controller/command', JointStates) rospy.init_node('head_commander', anonymous=True) sleep(1) - head_angles.publish(JointCmd(['head_pan_joint', 'head_tilt_joint'],[0.0,0.0],[pan, tilt],[0.0, 0.0],[0.0, 0.0])) + ps = JointState() + ps.name = 'head_pan_joint' + ps.position = pan + ts = JointState() + ts.name ='head_tilt_joint' + ts.position = tilt + js = JointStates() + js.joints = [ps, ts] + head_angles.publish(js) sleep(1) def point_head_cart_client(x,y,z,frame): - head_angles = rospy.Publisher('head_controller/head_track_point', PointStamped) + head_angles = rospy.Publisher('head_controller/point_frame_on_head', PointStamped) rospy.init_node('head_commander', anonymous=True) sleep(1) head_angles.publish(PointStamped(rospy.Header(None, rospy.get_rostime(), frame), Point(x, y, z))) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |