|
From: <stu...@us...> - 2009-08-07 02:52:19
|
Revision: 21000
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21000&view=rev
Author: stuglaser
Date: 2009-08-07 02:52:13 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
PRE now calibrates
Modified Paths:
--------------
pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py
pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch
pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml
Modified: pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py 2009-08-07 02:51:54 UTC (rev 20999)
+++ pkg/trunk/stacks/mechanism/mechanism_bringup/scripts/calibrate_pr2.py 2009-08-07 02:52:13 UTC (rev 21000)
@@ -174,7 +174,7 @@
else:
casters = ['caster_fl', 'caster_fr', 'caster_bl', 'caster_br']
if '--alpha-head' in flags:
- head = ['head_pan_alpha2', 'head_tilt_alpha2']
+ head = ['head_pan_alpha2', 'head_tilt_alpha2b']
else:
head = ['head_pan', 'head_tilt']
Modified: pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch
===================================================================
--- pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch 2009-08-07 02:51:54 UTC (rev 20999)
+++ pkg/trunk/stacks/pr2/pr2_alpha/pre_ethercat_reset.launch 2009-08-07 02:52:13 UTC (rev 21000)
@@ -7,7 +7,7 @@
<!-- pr2_etherCAT -->
<node machine="realtime_root" pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i ecat0 -x /robot_description"/>
- <node pkg="mechanism_bringup" type="calibrate_pr2.py"
- args="$(find pr2_default_controllers)/calibration_controllers/pre_calibration_controller.xml"
- output="screen" />
+ <rosparam command="load" file="$(find pr2_default_controllers)/pr2_calibration_controllers.yaml" />
+ <rosparam command="load" file="$(find pr2_default_controllers)/pr2_joint_position_controllers.yaml" />
+ <node pkg="mechanism_bringup" type="calibrate_pr2.py" args="--alpha-head --alpha-casters" output="screen" />
</launch>
Modified: pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml 2009-08-07 02:51:54 UTC (rev 20999)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/pr2_calibration_controllers.yaml 2009-08-07 02:52:13 UTC (rev 21000)
@@ -58,7 +58,7 @@
joint: r_upper_arm_roll_joint
actuator: r_upper_arm_roll_motor
transmission: r_upper_arm_roll_trans
- velocity: 1.0
+ velocity: 1.5
pid:
p: 6
i: 0.2
@@ -69,7 +69,7 @@
joint: l_upper_arm_roll_joint
actuator: l_upper_arm_roll_motor
transmission: l_upper_arm_roll_trans
- velocity: 1.0
+ velocity: 1.5
pid:
p: 6
i: 0.2
@@ -319,7 +319,7 @@
cal_head_tilt_alpha2b:
type: JointUDCalibrationController
joint: head_tilt_joint
- actuator: head_tilt_motor_alpha2b
+ actuator: head_tilt_motor
transmission: head_tilt_trans
velocity: -1.0
pid:
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|