|
From: <wa...@us...> - 2009-08-27 03:05:41
|
Revision: 23099
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23099&view=rev
Author: wattsk
Date: 2009-08-27 03:05:34 +0000 (Thu, 27 Aug 2009)
Log Message:
-----------
running the dallas bot with the same base controller as the pr2 with just a new urdf :-)
Modified Paths:
--------------
pkg/trunk/sandbox/texas/drive.launch
pkg/trunk/sandbox/texas/texas.launch
pkg/trunk/sandbox/texas/texas.xml
Added Paths:
-----------
pkg/trunk/sandbox/texas/dallas_base_controller.yaml
pkg/trunk/sandbox/texas/drive_base.launch
Added: pkg/trunk/sandbox/texas/dallas_base_controller.yaml
===================================================================
--- pkg/trunk/sandbox/texas/dallas_base_controller.yaml (rev 0)
+++ pkg/trunk/sandbox/texas/dallas_base_controller.yaml 2009-08-27 03:05:34 UTC (rev 23099)
@@ -0,0 +1,46 @@
+caster_names: bl_caster_rotation_link
+
+type: Pr2BaseController
+
+caster_pid_gains: &caster_pid_gains
+ p: 3.0
+ d: 0.0
+ i: 0.1
+ i_clamp: 4.0
+wheel_pid_gains: &wheel_pid_gains
+ p: 2.0
+ d: 0.0
+ i: 0.01
+ i_clamp: 0.4
+
+bl_caster_l_wheel_joint:
+ *wheel_pid_gains
+bl_caster_r_wheel_joint:
+ *wheel_pid_gains
+
+bl_caster_rotation_joint:
+ *caster_pid_gains
+
+caster_speed_threshold: 0.2
+caster_position_error_threshold: 0.05
+wheel_speed_threshold: 0.2
+caster_effort_threshold: 3.45
+wheel_effort_threshold: 3.45
+kp_wheel_steer: 2.0
+alpha_stall: 0.5
+kp_caster_steer: 40.0
+timeout: 0.4
+max_accel:
+ ax: 0.5
+ ay: 2.0
+ alphaz: 2.0
+
+state_publish_time: 0.25
+
+max_vel:
+ vx: 1.0
+ vy: 1.0
+ omegaz: 2.0
+
+cmd_topic:
+ /cmd_vel
\ No newline at end of file
Modified: pkg/trunk/sandbox/texas/drive.launch
===================================================================
--- pkg/trunk/sandbox/texas/drive.launch 2009-08-27 03:02:49 UTC (rev 23098)
+++ pkg/trunk/sandbox/texas/drive.launch 2009-08-27 03:05:34 UTC (rev 23099)
@@ -3,23 +3,13 @@
<rosparam command="load" file="$(find texas)/dallas.yaml" />
<node pkg="mechanism_control" type="spawner.py" args="dallas_controller" />
- <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" />
+ <!-- Swapping walk and run. Run (Caps) is now super slow -->
+ <param name="walk_vel" value="0.4" />
+ <param name="run_vel" value="0.1" />
+ <param name="yaw_rate" value="0.5" />
+ <param name="yaw_run_rate" value="0.2" />
<node pkg="teleop_pr2" type="teleop_pr2_keyboard" output="screen">
<remap from="cmd_vel" to="/dallas_controller/cmd_vel" />
</node>
- <!--
-<rosparam command="load" file="$(find texas)/caster.yaml" />
-<node pkg="mechanism_control" type="spawner.py" args="caster_bl" />
-
-<node pkg="texas" type="tdrive.py" output="screen" />
-
-<node pkg="texas" type="teleop_texas_keyboard" output="screen" >
- <param name="max_vel" type="double" value="6.0" />
-</node>
--->
-
</launch>
Added: pkg/trunk/sandbox/texas/drive_base.launch
===================================================================
--- pkg/trunk/sandbox/texas/drive_base.launch (rev 0)
+++ pkg/trunk/sandbox/texas/drive_base.launch 2009-08-27 03:05:34 UTC (rev 23099)
@@ -0,0 +1,14 @@
+<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" />
+
+ <!-- Swapping walk and run. Run (Caps) is now super slow -->
+ <param name="walk_vel" value="0.4" />
+ <param name="run_vel" value="0.1" />
+ <param name="yaw_rate" value="0.5" />
+ <param name="yaw_run_rate" value="0.2" />
+ <node pkg="teleop_pr2" type="teleop_pr2_keyboard" output="screen">
+ </node>
+
+</launch>
Modified: pkg/trunk/sandbox/texas/texas.launch
===================================================================
--- pkg/trunk/sandbox/texas/texas.launch 2009-08-27 03:02:49 UTC (rev 23098)
+++ pkg/trunk/sandbox/texas/texas.launch 2009-08-27 03:05:34 UTC (rev 23099)
@@ -8,7 +8,7 @@
<!-- Definitions for calibration controllers -->
<rosparam command="load" file="$(find pr2_default_controllers)/pr2_calibration_controllers.yaml" />
- <node pkg="mechanism_bringup" type="calibrate.py" args="cal_caster_bl_alpha2"/>
+ <node pkg="mechanism_bringup" type="calibrate.py" args="cal_caster_bl"/>
<!-- pr2_etherCAT -->
<node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i eth0 -x /robotdesc/pr2" output="screen"/>
Modified: pkg/trunk/sandbox/texas/texas.xml
===================================================================
--- pkg/trunk/sandbox/texas/texas.xml 2009-08-27 03:02:49 UTC (rev 23098)
+++ pkg/trunk/sandbox/texas/texas.xml 2009-08-27 03:05:34 UTC (rev 23099)
@@ -1,10 +1,10 @@
<robot name="texas">
<include filename="$(find pr2_defs)/calibration/default_cal.xml" />
- <include filename="$(find pr2_defs)/defs/alpha2_base_defs.xml" />
+ <include filename="$(find pr2_defs)/defs/base_defs.xml" />
-<pr2_caster_alpha2 suffix="bl" parent="base_link" ref_position="-0.785">
- <origin xyz="0 0 0" rpy="0 0 0" />
-</pr2_caster_alpha2>
+<pr2_caster suffix="bl" parent="base_link" ref_position="-0.785" >
+ <origin xyz="-0.43 0 0" rpy="0 0 0" />
+</pr2_caster>
<!-- Solid Base for visualizer -->
<joint name="base_joint" type="planar" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|