From: <hsu...@us...> - 2009-07-14 22:55:27
|
Revision: 18805 http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18805&view=rev Author: hsujohnhsu Date: 2009-07-14 22:55:25 +0000 (Tue, 14 Jul 2009) Log Message: ----------- publish with current ros time. None defaults to system time. 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-14 22:55:10 UTC (rev 18804) +++ pkg/trunk/controllers/pr2_mechanism_controllers/scripts/pointhead.py 2009-07-14 22:55:25 UTC (rev 18805) @@ -54,7 +54,7 @@ head_angles = rospy.Publisher('head_controller/head_track_point', PointStamped) rospy.init_node('head_commander', anonymous=True) sleep(1) - head_angles.publish(PointStamped(rospy.Header(None, None, frame), Point(x, y, z))) + head_angles.publish(PointStamped(rospy.Header(None, rospy.get_rostime(), frame), Point(x, y, z))) sleep(1) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |