|
From: <wa...@us...> - 2009-09-01 03:01:02
|
Revision: 23460
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23460&view=rev
Author: wattsk
Date: 2009-09-01 03:00:53 +0000 (Tue, 01 Sep 2009)
Log Message:
-----------
Use texas.launch, ps3_drive.launch, /joy/joy
Modified Paths:
--------------
pkg/trunk/sandbox/texas/dallas_base_controller.yaml
pkg/trunk/sandbox/texas/texas.launch
Added Paths:
-----------
pkg/trunk/sandbox/texas/ps3_drive.launch
Modified: pkg/trunk/sandbox/texas/dallas_base_controller.yaml
===================================================================
--- pkg/trunk/sandbox/texas/dallas_base_controller.yaml 2009-09-01 02:57:08 UTC (rev 23459)
+++ pkg/trunk/sandbox/texas/dallas_base_controller.yaml 2009-09-01 03:00:53 UTC (rev 23460)
@@ -31,7 +31,7 @@
kp_caster_steer: 40.0
timeout: 0.4
max_accel:
- ax: 0.5
+ ax: 1.0
ay: 2.0
alphaz: 2.0
@@ -43,4 +43,4 @@
omegaz: 2.0
cmd_topic:
- /cmd_vel
\ No newline at end of file
+ /cmd_vel
Added: pkg/trunk/sandbox/texas/ps3_drive.launch
===================================================================
--- pkg/trunk/sandbox/texas/ps3_drive.launch (rev 0)
+++ pkg/trunk/sandbox/texas/ps3_drive.launch 2009-09-01 03:00:53 UTC (rev 23460)
@@ -0,0 +1,46 @@
+<launch>
+
+ <rosparam command="load" file="$(find texas)/dallas_base_controller.yaml" ns="pr2_base_controller" />
+ <node pkg="mechanism_control" type="spawner.py" args="pr2_base_controller" />
+
+
+ <group name="ps3_teleop">
+ <!-- Axes -->
+ <param name="axis_vx" value="3" type="int"/>
+ <param name="axis_vy" value="-1" type="int"/>
+ <param name="axis_vw" value="2" type="int"/>
+ <param name="axis_pan" value="0" type="int"/>
+ <param name="axis_tilt" value="3" type="int"/>
+
+ <!-- Base velocities -->
+ <param name="max_vw" value="0.8" />
+ <param name="max_vx" value="0.5" />
+ <param name="max_vy" value="0.5" />
+ <param name="max_vw_run" value="1.4" />
+ <param name="max_vx_run" value="1.0" />
+ <param name="max_vy_run" value="1.0" />
+
+ <!-- Head -->
+ <param name="max_pan" value="2.7" />
+ <param name="max_tilt" value="1.4" />
+ <param name="min_tilt" value="-0.4" />
+ <param name="tilt_step" value="0.015" />
+ <param name="pan_step" value="0.02" />
+
+ <!-- Buttons have changed for PS3 controller mapping -->
+ <param name="run_button" value="11" type="int" />
+ <param name="torso_dn_button" value="14" type="int" />
+ <param name="torso_up_button" value="12" type="int" />
+ <param name="head_button" value="8" type="int" />
+ <param name="deadman_button" value="10" type="int"/>
+
+ <param name="walk_vel" value="0.20" />
+ <param name="run_vel" value="0.5" />
+ <param name="yaw_rate" value="0.3" />
+ <param name="yaw_run_rate" value="1.5" />
+ <node pkg="teleop_pr2" type="teleop_pr2" output="screen">
+ </node>
+
+ </group>
+</launch>
+
Modified: pkg/trunk/sandbox/texas/texas.launch
===================================================================
--- pkg/trunk/sandbox/texas/texas.launch 2009-09-01 02:57:08 UTC (rev 23459)
+++ pkg/trunk/sandbox/texas/texas.launch 2009-09-01 03:00:53 UTC (rev 23460)
@@ -13,8 +13,6 @@
<!-- pr2_etherCAT -->
<node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x /robotdesc/pr2" output="screen"/>
- <node pkg="pr2_mechanism_control" type="spawner.py" args="pr2_base_controller" />
-
<!-- Runtime Diagnostics Logging -->
<node pkg="rosrecord" type="rosrecord" args="-f /hwlog/pre_runtime_automatic /diagnostics" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|