|
From: <wa...@us...> - 2009-08-17 21:06:48
|
Revision: 22033
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=22033&view=rev
Author: wattsk
Date: 2009-08-17 21:06:37 +0000 (Mon, 17 Aug 2009)
Log Message:
-----------
Updates from hot box test (left arm, head)
Modified Paths:
--------------
pkg/trunk/pr2/life_test/arm_life_test/random_poses_left.py
pkg/trunk/pr2/life_test/head_test/life_test/life_test.launch
pkg/trunk/pr2/life_test/scripts/run_head_test.py
Modified: pkg/trunk/pr2/life_test/arm_life_test/random_poses_left.py
===================================================================
--- pkg/trunk/pr2/life_test/arm_life_test/random_poses_left.py 2009-08-17 21:05:00 UTC (rev 22032)
+++ pkg/trunk/pr2/life_test/arm_life_test/random_poses_left.py 2009-08-17 21:06:37 UTC (rev 22033)
@@ -33,13 +33,13 @@
import rospy
from geometry_msgs.msg import PoseStamped
-#pub = rospy.Publisher('cartesian_pose/command', PoseStamped)
-pub = rospy.Publisher('cartesian_trajectory_left/command', PoseStamped)
+#pub = rospy.Publisher('l_arm_cartesian_pose_controller/command', PoseStamped)
+pub = rospy.Publisher('/l_arm_cartesian_trajectory_controller/command', PoseStamped)
def p(x, y, z, rx, ry, rz, w):
m = PoseStamped()
- m.header.frame_id = 'base_link'
+ m.header.frame_id = '/base_link'
m.header.stamp = rospy.get_rostime()
m.pose.position.x = x
m.pose.position.y = y
Modified: pkg/trunk/pr2/life_test/head_test/life_test/life_test.launch
===================================================================
--- pkg/trunk/pr2/life_test/head_test/life_test/life_test.launch 2009-08-17 21:05:00 UTC (rev 22032)
+++ pkg/trunk/pr2/life_test/head_test/life_test/life_test.launch 2009-08-17 21:06:37 UTC (rev 22033)
@@ -3,14 +3,7 @@
<!-- May need to put in to to scripts folder -->
<node pkg="life_test" type="run_head_test.py" />
- <group ns="head_controller" clear_params="true">
- <param name="pan_link_name" type="string" value="head_pan_link" />
- <param name="tilt_link_name" type="string" value="head_tilt_link" />
- <param name="pan_output" type="string" value="head_pan_joint_position_controller" />
- <param name="tilt_output" type="string" value="head_tilt_joint_position_controller" />
- </group>
+ <include file="$(find pr2_default_controllers)/head_position_controller.launch" />
- <node pkg="mechanism_control" type="spawner.py" args="$(find life_test)/head_test/life_test/test_controller.xml" />
-
<node pkg="life_test" type="laser_test.bash" />
</launch>
\ No newline at end of file
Modified: pkg/trunk/pr2/life_test/scripts/run_head_test.py
===================================================================
--- pkg/trunk/pr2/life_test/scripts/run_head_test.py 2009-08-17 21:05:00 UTC (rev 22032)
+++ pkg/trunk/pr2/life_test/scripts/run_head_test.py 2009-08-17 21:06:37 UTC (rev 22033)
@@ -62,11 +62,9 @@
sleep(1)
while 1:
- #point_head_client(0.0, -0.4)
pan = random.uniform(-2.7, 2.7)
print pan
tilt = random.uniform(-0.5, 1.35)
print tilt
- #point_head_client(0.0, 1.2)
point_head_client(pan, tilt)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|