|
From: <goo...@us...> - 2009-09-04 19:55:01
|
Revision: 23856
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23856&view=rev
Author: goodfellow
Date: 2009-09-04 19:54:50 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
Updated script to use new version of JointState
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-09-04 19:47:26 UTC (rev 23855)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py 2009-09-04 19:54:50 UTC (rev 23856)
@@ -39,21 +39,16 @@
import rospy
from geometry_msgs.msg import PointStamped, Point
-from pr2_mechanism_msgs.msg import JointStates, JointState
+from sensor_msgs.msg import JointState
def point_head_client(pan, tilt):
- head_angles = rospy.Publisher('head_controller/command', JointStates)
+ head_angles = rospy.Publisher('head_controller/command', JointState)
rospy.init_node('head_commander', anonymous=True)
sleep(1)
- 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]
+ js = JointState()
+ js.name = ['head_pan_joint', 'head_tilt_joint'];
+ js.position = [pan,tilt];
head_angles.publish(js)
sleep(1)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|