|
From: <mm...@us...> - 2009-07-15 21:03:32
|
Revision: 18886
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18886&view=rev
Author: mmwise
Date: 2009-07-15 21:03:21 +0000 (Wed, 15 Jul 2009)
Log Message:
-----------
changing to new head controller and getting rid of robot_msgs/JointCmd #1306
Modified Paths:
--------------
pkg/trunk/pr2/life_test/head_test/impact_test/test_gui.launch
pkg/trunk/pr2/life_test/head_test/life_test/life_test.launch
pkg/trunk/pr2/life_test/head_test/life_test/test_controller.xml
pkg/trunk/pr2/life_test/scripts/run_head_test.py
Modified: pkg/trunk/pr2/life_test/head_test/impact_test/test_gui.launch
===================================================================
--- pkg/trunk/pr2/life_test/head_test/impact_test/test_gui.launch 2009-07-15 20:48:43 UTC (rev 18885)
+++ pkg/trunk/pr2/life_test/head_test/impact_test/test_gui.launch 2009-07-15 21:03:21 UTC (rev 18886)
@@ -1,4 +1,4 @@
-l<launch>
+<launch>
<param name="robotdesc/pr2" command="$(find xacro)/xacro.py '$(find life_test)/head_test/impact_test/head.xml'" />
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-07-15 20:48:43 UTC (rev 18885)
+++ pkg/trunk/pr2/life_test/head_test/life_test/life_test.launch 2009-07-15 21:03:21 UTC (rev 18886)
@@ -2,6 +2,13 @@
<!-- Runs the test on or off the test cart. -->
<!-- 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>
<node pkg="mechanism_control" type="spawner.py" args="$(find life_test)/head_test/life_test/test_controller.xml" />
Modified: pkg/trunk/pr2/life_test/head_test/life_test/test_controller.xml
===================================================================
--- pkg/trunk/pr2/life_test/head_test/life_test/test_controller.xml 2009-07-15 20:48:43 UTC (rev 18885)
+++ pkg/trunk/pr2/life_test/head_test/life_test/test_controller.xml 2009-07-15 21:03:21 UTC (rev 18886)
@@ -1,25 +1,25 @@
-<controllers>
-<controller name="head_controller" type="HeadPanTiltControllerNode">
- <controller name="head_pan_controller" topic="head_pan_controller" type="JointPositionController">
- <joint name="head_pan_joint" >
- <pid p="2.5" d="0.5" i="12.0" iClamp="0.5" />
- </joint>
- </controller>
+<controller type="HeadPositionController" name="head_controller"/>
+
+<controller name="head_pan_joint_position_controller" type="JointPositionController">
+ <joint name="head_pan_joint" >
+ <pid p="2.5" d="0.5" i="12.0" iClamp="0.5" />
+ </joint>
+</controller>
- <controller name="head_tilt_controller" topic="head_tilt_controller" type="JointPositionController">
- <joint name="head_tilt_joint" >
- <pid p="15" d="0.5" i="5" iClamp="1.0" />
- </joint>
- </controller>
+<controller name="head_tilt_joint_position_controller" type="JointPositionController">
+ <joint name="head_tilt_joint" >
+ <pid p="15" d="0.5" i="5" iClamp="1.0" />
+ </joint>
+</controller>
-</controller>
+
<controller name="laser_controller" topic="laser_controller" type="LaserScannerControllerNode">
<filter smoothing_factor="0.1" />
<joint name="laser_tilt_mount_joint">
<pid p="12" i=".1" d="1" iClamp="0.5" />
</joint>
- </controller>
+</controller>
</controllers>
Modified: pkg/trunk/pr2/life_test/scripts/run_head_test.py
===================================================================
--- pkg/trunk/pr2/life_test/scripts/run_head_test.py 2009-07-15 20:48:43 UTC (rev 18885)
+++ pkg/trunk/pr2/life_test/scripts/run_head_test.py 2009-07-15 21:03:21 UTC (rev 18886)
@@ -38,16 +38,26 @@
from time import sleep
import random
import rospy
-from robot_msgs.msg import JointCmd
+from mechanism_msgs.msg import JointStates, JointState
+
def point_head_client(pan, tilt):
- 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(0.5)
if __name__ == "__main__":
- 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)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|