|
From: <mm...@us...> - 2008-11-20 22:22:45
|
Revision: 7082
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7082&view=rev
Author: mmwise
Date: 2008-11-20 22:22:40 +0000 (Thu, 20 Nov 2008)
Log Message:
-----------
Grand renaming of joints, motors, transmissions, etc...
Modified Paths:
--------------
pkg/trunk/drivers/motor/ethercat_hardware/actuators.conf
pkg/trunk/robot_descriptions/wg_robot_description/arm/arm.xml
pkg/trunk/robot_descriptions/wg_robot_description/head_pan_tilt/head_pan_tilt.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/cal.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups_collision.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xacro.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/groups_arm.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/lqr_control_leftarm.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/cal.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_base_lab.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/laser_controller_config.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/pr2_prototype1.xacro.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/arm_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/base_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/body_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/head_defs.xml
pkg/trunk/robot_descriptions/wg_robot_description/robo_dev_head/cal.xml
pkg/trunk/robot_descriptions/wg_robot_description/robo_dev_head/robo_dev_head.xml
pkg/trunk/robot_descriptions/wg_robot_description/tilt_laser/build_snapshots.launch
pkg/trunk/robot_descriptions/wg_robot_description/tilt_laser/cal.xml
pkg/trunk/robot_descriptions/wg_robot_description/tilt_laser/calibrate.launch
pkg/trunk/robot_descriptions/wg_robot_description/tilt_laser/control_tilt_laser_roslaunch.xml
pkg/trunk/robot_descriptions/wg_robot_description/tilt_laser/tilt_laser.xml
pkg/trunk/robot_descriptions/wg_robot_description/tilt_laser/tilt_laser_controller.xml
pkg/trunk/robot_descriptions/wg_robot_description/tilt_laser/tilt_laser_traj_controller.xml
Removed Paths:
-------------
pkg/trunk/robot_descriptions/wg_robot_description/one_armed_bandit/
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/init.launch
pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm/
Modified: pkg/trunk/drivers/motor/ethercat_hardware/actuators.conf
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/actuators.conf 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/drivers/motor/ethercat_hardware/actuators.conf 2008-11-20 22:22:40 UTC (rev 7082)
@@ -83,49 +83,53 @@
<actuators>
<!-- Casters -->
- <actuator name="caster_front_left_motor" motor="236672"/>
- <actuator name="wheel_front_left_l_motor" motor="236672"/>
- <actuator name="wheel_front_left_r_motor" motor="236672"/>
- <actuator name="caster_front_right_motor" motor="236672"/>
- <actuator name="wheel_front_right_l_motor" motor="236672"/>
- <actuator name="wheel_front_right_r_motor" motor="236672"/>
- <actuator name="caster_rear_left_motor" motor="236672"/>
- <actuator name="wheel_rear_left_l_motor" motor="236672"/>
- <actuator name="wheel_rear_left_r_motor" motor="236672"/>
- <actuator name="caster_rear_right_motor" motor="236672"/>
- <actuator name="wheel_rear_right_l_motor" motor="236672"/>
- <actuator name="wheel_rear_right_r_motor" motor="236672"/>
+ <actuator name="fl_caster_rotation_motor" motor="236672"/>
+ <actuator name="fl_caster_l_wheel_motor" motor="236672"/>
+ <actuator name="fl_caster_r_wheel_motor" motor="236672"/>
+
+ <actuator name="fr_caster_rotation_motor" motor="236672"/>
+ <actuator name="fr_caster_l_wheel_motor" motor="236672"/>
+ <actuator name="fr_caster_r_wheel_motor" motor="236672"/>
+
+ <actuator name="bl_caster_rotation_motor" motor="236672"/>
+ <actuator name="bl_caster_l_wheel_motor" motor="236672"/>
+ <actuator name="bl_caster_r_wheel_motor" motor="236672"/>
+
+ <actuator name="br_caster_rotation_motor" motor="236672"/>
+ <actuator name="br_caster_l_wheel_motor" motor="236672"/>
+ <actuator name="br_caster_r_wheel_motor" motor="236672"/>
+
<!-- Spine -->
- <actuator name="torso_motor" motor="148877"/>
+ <actuator name="torso_lift_motor" motor="148877"/>
<!-- Arm -->
- <actuator name="left_shoulder_pan_motor" motor="148877"/>
- <actuator name="left_shoulder_pitch_motor" motor="148877"/>
- <actuator name="left_upper_arm_roll_motor" motor="148877"/>
- <actuator name="left_elbow_flex_motor" motor="148877"/>
- <actuator name="left_forearm_roll_motor" motor="310007"/>
+ <actuator name="l_shoulder_pan_motor" motor="148877"/>
+ <actuator name="l_shoulder_lift_motor" motor="148877"/>
+ <actuator name="l_upper_arm_roll_motor" motor="148877"/>
+ <actuator name="l_elbow_flex_motor" motor="148877"/>
+ <actuator name="l_forearm_roll_motor" motor="310007"/>
- <actuator name="right_shoulder_pan_motor" motor="148877"/>
- <actuator name="right_shoulder_pitch_motor" motor="148877"/>
- <actuator name="right_upper_arm_roll_motor" motor="148877"/>
- <actuator name="right_elbow_flex_motor" motor="148877"/>
- <actuator name="right_forearm_roll_motor" motor="310007"/>
+ <actuator name="r_shoulder_pan_motor" motor="148877"/>
+ <actuator name="r_shoulder_lift_motor" motor="148877"/>
+ <actuator name="r_upper_arm_roll_motor" motor="148877"/>
+ <actuator name="r_elbow_flex_motor" motor="148877"/>
+ <actuator name="r_forearm_roll_motor" motor="310007"/>
<!-- Wrist -->
- <actuator name="left_wrist_l_motor" motor="310007"/>
- <actuator name="left_wrist_r_motor" motor="310007"/>
+ <actuator name="l_wrist_l_motor" motor="310007"/>
+ <actuator name="l_wrist_r_motor" motor="310007"/>
- <actuator name="right_wrist_l_motor" motor="310007"/>
- <actuator name="right_wrist_r_motor" motor="310007"/>
+ <actuator name="r_wrist_l_motor" motor="310007"/>
+ <actuator name="r_wrist_r_motor" motor="310007"/>
<!-- Gripper -->
- <actuator name="left_gripper_motor" motor="222057"/>
- <actuator name="right_gripper_motor" motor="222057"/>
+ <actuator name="l_gripper_motor" motor="222057"/>
+ <actuator name="r_gripper_motor" motor="222057"/>
<!-- Head -->
<actuator name="head_pan_motor" motor="310009-pan"/>
<actuator name="head_tilt_motor" motor="310009-tilt"/>
- <actuator name="tilt_laser_motor" motor="310009"/>
+ <actuator name="laser_tilt_motor" motor="310009"/>
</actuators>
</configuration>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/arm/arm.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/arm/arm.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/arm/arm.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -17,7 +17,7 @@
<include filename="../pr2_robot_defs/arm_defs.xml" />
<joint name="base_joint" type="planar" />
- <link name="torso">
+ <link name="torso_lift">
<parent name="world" />
<joint name="base_joint" />
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -45,10 +45,10 @@
</collision>
</link>
- <pr2_arm side="right" reflect="-1" parent="torso">
+ <pr2_arm side="right" reflect="-1" parent="torso_lift">
<origin xyz="0 0 0.7" rpy="0 0 0" />
</pr2_arm>
- <pr2_gripper side="right" parent="right_wrist_roll" />
+ <pr2_gripper side="right" parent="r_wrist_roll" />
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/head_pan_tilt/head_pan_tilt.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/head_pan_tilt/head_pan_tilt.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/head_pan_tilt/head_pan_tilt.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -3,11 +3,11 @@
<include filename="../pr2_robot_defs/head_defs.xml" />
<include filename="../pr2_robot_defs/body_defs.xml" />
- <pr2_torso name="torso" parent="world">
+ <pr2_torso name="torso_lift" parent="world">
<origin xyz="0 0 0" rpy="0 0 0" />
</pr2_torso>
- <pr2_head_pan name="head_pan" parent="torso">
+ <pr2_head_pan name="head_pan" parent="torso_lift">
<origin xyz="0 0 0.3815" rpy="0 0 0" />
</pr2_head_pan>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/cal.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/cal.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/cal.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -4,14 +4,14 @@
<include filename="../pr2_robot_defs/head_defs.xml" />
<include filename="../pr2_robot_defs/body_defs.xml" />
- <upper_arm_calibrator side="right" />
- <forearm_calibrator side="right" />
- <gripper_calibrator side="right" />
+ <upper_arm_calibrator side="r" />
+ <forearm_calibrator side="r" />
+ <gripper_calibrator side="r" />
<!--
- <upper_arm_calibrator side="left" />
- <forearm_calibrator side="left" />
- <gripper_calibrator side="left" />
+ <upper_arm_calibrator side="l" />
+ <forearm_calibrator side="l" />
+ <gripper_calibrator side="l" />
-->
<base_calibrator />
@@ -20,6 +20,6 @@
<torso_calibrator />
- <tilting_laser_calibrator name="tilt_laser" />
+ <tilting_laser_calibrator name="laser_tilt" />
</controllers>
Deleted: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -1,229 +0,0 @@
-<?xml version="1.0"?>
-
-<controllers>
-
- <controller name="base_controller" topic="base_controller" type="BaseControllerNode">
- <map name="velocity_control" flag="base_control">
- <elem key="kp_speed">100.0</elem>
- <elem key="kp_caster_steer">0</elem>
- <elem key="timeout">3</elem>
-
- <elem key="max_x_dot">1</elem>
- <elem key="max_y_dot">1</elem>
- <elem key="max_yaw_dot">1</elem>
-
- <elem key="max_x_accel">2.0</elem>
- <elem key="max_y_accel">2.0</elem>
- <elem key="max_yaw_accel">1.0</elem>
-
- </map>
- <controller name="wheel_front_left_l_controller" topic="wheel_front_left_l_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_left_l_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
- <controller name="wheel_front_left_r_controller" topic="wheel_front_left_r_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_left_r_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
- <controller name="wheel_front_right_l_controller" topic="wheel_front_right_l_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_right_l_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
- <controller name="wheel_front_right_r_controller" topic="wheel_front_right_r_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_right_r_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
- <controller name="wheel_rear_left_l_controller" topic="wheel_rear_left_l_controller" type="JointVelocityControllerNode">
- <joint name="wheel_rear_left_l_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
- <controller name="wheel_rear_left_r_controller" topic="wheel_rear_left_r_controller" type="JointVelocityControllerNode">
- <joint name="wheel_rear_left_r_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
- <controller name="wheel_rear_right_l_controller" topic="wheel_rear_right_l_controller" type="JointVelocityControllerNode">
- <joint name="wheel_rear_right_l_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
- <controller name="wheel_rear_right_r_controller" topic="wheel_rear_right_r_controller" type="JointVelocityControllerNode">
- <joint name="wheel_rear_right_r_joint" >
- <pid p="2.0" d="0" i="0.2" iClamp="2" />
- </joint>
- </controller>
-
- <controller name="caster_front_left_controller" topic="caster_front_left_controller" type="JointVelocityControllerNode">
- <joint name="caster_front_left_joint" >
- <pid p="3" d="0" i="0.1" iClamp="4" />
- </joint>
- </controller>
- <controller name="caster_front_right_controller" topic="caster_front_right_controller" type="JointVelocityControllerNode">
- <joint name="caster_front_right_joint" >
- <pid p="3" d="0" i="0.1" iClamp="4" />
- </joint>
- </controller>
- <controller name="caster_rear_left_controller" topic="caster_rear_left_controller" type="JointVelocityControllerNode">
- <joint name="caster_rear_left_joint" >
- <pid p="3" d="0" i="0.1" iClamp="4" />
- </joint>
- </controller>
- <controller name="caster_rear_right_controller" topic="caster_rear_right_controller" type="JointVelocityControllerNode">
- <joint name="caster_rear_right_joint" >
- <pid p="3" d="0" i="0.1" iClamp="4" />
- </joint>
- </controller>
-
-
- </controller>
-
- <!-- ========================================= -->
- <!-- torso array -->
- <controller name="torso_controller" topic="torso_controller" type="JointPositionControllerNode">
- <joint name="torso_joint">
- <pid p="1000" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
- <!-- ========================================= -->
- <!-- left arm array -->
- <controller name="left_arm_controller" type="ArmPositionControllerNode">
- <listen_topic name="left_arm_commands" />
- <kinematics>
- <elem key="kdl_chain_name">left_arm</elem>
- </kinematics>
- <map name="controller_param">
- <elem key="kdl_chain_name">left_arm</elem>
- </map>
- <controller name="left_shoulder_pan_controller" topic="left_shoulder_pan_controller" type="JointPositionController">
- <joint name="left_shoulder_pan_joint" >
- <pid p="100" d="200" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="left_shoulder_pitch_controller" topic="left_shoulder_pitch_controller" type="JointPositionController">
- <joint name="left_shoulder_pitch_joint" >
- <pid p="100" d="100.0" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="left_upper_arm_roll_controller" topic="left_upper_arm_roll_controller" type="JointPositionController">
- <joint name="left_upper_arm_roll_joint" >
- <pid p="400" d="400" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="left_elbow_flex_controller" topic="left_elbow_flex_controller" type="JointPositionController">
- <joint name="left_elbow_flex_joint" >
- <pid p="100" d="100" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="left_forearm_roll_controller" topic="left_forearm_roll_controller" type="JointPositionController">
- <joint name="left_forearm_roll_joint" >
- <pid p="200" d="200" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="left_wrist_flex_controller" topic="left_wrist_flex_controller" type="JointPositionController">
- <joint name="left_wrist_flex_joint" >
- <pid p="100" d="100" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="left_wrist_roll_controller" topic="left_wrist_roll_controller" type="JointPositionController">
- <joint name="left_wrist_roll_joint" >
- <pid p="100" d="100" i="0.1" iClamp="0" />
- </joint>
- </controller>
- </controller>
- <!-- Special gripper joint -->
- <controller name="gripper_left_controller" topic="gripper_left_controller" type="JointPositionControllerNode">
- <joint name="left_gripper_l_finger_joint">
- <pid p="1.0" d="0.00" i="0.00" iClamp="0.00" />
- </joint>
- </controller>
- <!-- ========================================= -->
- <!-- right arm array -->
- <controller name="right_arm_controller" type="ArmPositionControllerNode">
- <listen_topic name="right_arm_commands" />
- <kinematics>
- <elem key="kdl_chain_name">right_arm</elem>
- </kinematics>
- <map name="controller_param">
- <elem key="kdl_chain_name">right_arm</elem>
- </map>
- <controller name="right_shoulder_pan_controller" topic="right_shoulder_pan_controller" type="JointPositionController">
- <joint name="right_shoulder_pan_joint" >
- <pid p="100" d="200" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="right_shoulder_pitch_controller" topic="right_shoulder_pitch_controller" type="JointPositionController">
- <joint name="right_shoulder_pitch_joint" >
- <pid p="100" d="100.0" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="right_upper_arm_roll_controller" topic="right_upper_arm_roll_controller" type="JointPositionController">
- <joint name="right_upper_arm_roll_joint" >
- <pid p="400" d="400" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="right_elbow_flex_controller" topic="right_elbow_flex_controller" type="JointPositionController">
- <joint name="right_elbow_flex_joint" >
- <pid p="100" d="100" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="right_forearm_roll_controller" topic="right_forearm_roll_controller" type="JointPositionController">
- <joint name="right_forearm_roll_joint" >
- <pid p="200" d="200" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="right_wrist_flex_controller" topic="right_wrist_flex_controller" type="JointPositionController">
- <joint name="right_wrist_flex_joint" >
- <pid p="100" d="100" i="0.1" iClamp="1" />
- </joint>
- </controller>
- <controller name="right_wrist_roll_controller" topic="right_wrist_roll_controller" type="JointPositionController">
- <joint name="right_wrist_roll_joint" >
- <pid p="100" d="100" i="0.1" iClamp="0" />
- </joint>
- </controller>
- </controller>
- <!-- Special gripper joint -->
- <controller name="gripper_right_controller" topic="gripper_right_controller" type="JointPositionControllerNode">
- <joint name="right_gripper_l_finger_joint">
- <pid p="1.0" d="0.00" i="0.00" iClamp="0.00" />
- </joint>
- </controller>
- <!-- head and above array -->
- <controller name="head_pan_controller" topic="head_pan_controller" type="JointPositionControllerNode">
- <joint name="head_pan_joint" >
- <pid p="100" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
- <controller name="head_tilt_controller" topic="head_tilt_controller" type="JointPositionControllerNode">
- <joint name="head_tilt_joint" >
- <pid p="100" d="0" i="0" iClamp="0" />
- </joint>
- </controller>
-
- <controller name="tilt_laser_controller" topic="tilt_laser_controller" type="LaserScannerControllerNode">
- <joint name="tilt_laser_mount_joint" >
- <pid p="12" i=".1" d="1" iClamp="0.5" />
- </joint>
- </controller>
-
- <!-- this version of laser scanner controller seems to be broken
- <controller name="tilt_laser_controller" topic="laser_test" type="LaserScannerControllerNode">
- <velocity>
- <velocityFilter smoothing="0.2"/>
- <joint name="tilt_laser_mount_joint" type="velocity">
- <pid p="0.56" i = "14" d = "0.000001" iClamp = "0.02" />
- </joint>
- </velocity>
- <position>
- <joint name="single_joint" type="position">
- <pid p="4.4382" i = "31.2110" d = "0.0453" iClamp = "0.004" />
- </joint>
- </position>
- </controller>
- -->
-</controllers>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -32,13 +32,13 @@
</group>
<group name="left_arm" flags="planning kinematic">
- left_shoulder_pan
- left_shoulder_pitch
- left_upper_arm_roll
- left_elbow_flex
- left_forearm_roll
- left_wrist_flex
- left_wrist_roll
+ l_shoulder_pan
+ l_shoulder_lift
+ l_upper_arm_roll
+ l_elbow_flex
+ l_forearm_roll
+ l_wrist_flex
+ l_wrist_roll
<map name="RRT" flag="planning">
<elem key="range" value="0.75" />
@@ -56,13 +56,13 @@
<group name="right_arm" flags="planning kinematic">
- right_shoulder_pan
- right_shoulder_pitch
- right_upper_arm_roll
- right_elbow_flex
- right_forearm_roll
- right_wrist_flex
- right_wrist_roll
+ r_shoulder_pan
+ r_shoulder_lift
+ r_upper_arm_roll
+ r_elbow_flex
+ r_forearm_roll
+ r_wrist_flex
+ r_wrist_roll
<map name="RRT" flag="planning">
<elem key="range" value="0.75" />
@@ -82,25 +82,25 @@
<group name="base_left_arm" flags="planning">
base
torso
- left_shoulder_pan
- left_shoulder_pitch
- left_upper_arm_roll
- left_elbow_flex
- left_forearm_roll
- left_wrist_flex
- left_wrist_roll
+ l_shoulder_pan
+ l_shoulder_lift
+ l_upper_arm_roll
+ l_elbow_flex
+ l_forearm_roll
+ l_wrist_flex
+ l_wrist_roll
</group>
<group name="base_right_arm" flags="planning">
base
torso
- right_shoulder_pan
- right_shoulder_pitch
- right_upper_arm_roll
- right_elbow_flex
- right_forearm_roll
- right_wrist_flex
- right_wrist_roll
+ r_shoulder_pan
+ r_shoulder_lift
+ r_upper_arm_roll
+ r_elbow_flex
+ r_forearm_roll
+ r_wrist_flex
+ r_wrist_roll
<map name="RRT" flag="planning">
<elem key="range" value="0.75" />
@@ -118,39 +118,39 @@
</group>
<group name="arms" flags="planning">
- left_shoulder_pan
- left_shoulder_pitch
- left_upper_arm_roll
- left_elbow_flex
- left_forearm_roll
- left_wrist_flex
- left_wrist_roll
- right_shoulder_pan
- right_shoulder_pitch
- right_upper_arm_roll
- right_elbow_flex
- right_forearm_roll
- right_wrist_flex
- right_wrist_roll
+ l_shoulder_pan
+ l_shoulder_lift
+ l_upper_arm_roll
+ l_elbow_flex
+ l_forearm_roll
+ l_wrist_flex
+ l_wrist_roll
+ r_shoulder_pan
+ r_shoulder_lift
+ r_upper_arm_roll
+ r_elbow_flex
+ r_forearm_roll
+ r_wrist_flex
+ r_wrist_roll
</group>
<group name="base_arms" flags="planning">
base
torso
- left_shoulder_pan
- left_shoulder_pitch
- left_upper_arm_roll
- left_elbow_flex
- left_forearm_roll
- left_wrist_flex
- left_wrist_roll
- right_shoulder_pan
- right_shoulder_pitch
- right_upper_arm_roll
- right_elbow_flex
- right_forearm_roll
- right_wrist_flex
- right_wrist_roll
+ l_shoulder_pan
+ l_shoulder_lift
+ l_upper_arm_roll
+ l_elbow_flex
+ l_forearm_roll
+ l_wrist_flex
+ l_wrist_roll
+ r_shoulder_pan
+ r_shoulder_lift
+ r_upper_arm_roll
+ r_elbow_flex
+ r_forearm_roll
+ r_wrist_flex
+ r_wrist_roll
</group>
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups_collision.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups_collision.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups_collision.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -5,24 +5,24 @@
<!-- Define the parts of the robot that the robot's scanners can see -->
<group name="self_see" flags="collision">
- left_upper_arm_roll
- right_upper_arm_roll
- left_elbow_flex
- right_elbow_flex
- left_forearm_roll
- right_forearm_roll
- left_wrist_flex
- right_wrist_flex
- left_wrist_roll
- right_wrist_roll
- left_gripper_l_finger
- left_gripper_r_finger
- right_gripper_l_finger
- right_gripper_r_finger
- right_shoulder_pan
- right_shoulder_pitch
- left_shoulder_pan
- left_shoulder_pitch
+ l_upper_arm_roll
+ r_upper_arm_roll
+ l_elbow_flex
+ r_elbow_flex
+ l_forearm_roll
+ r_forearm_roll
+ l_wrist_flex
+ r_wrist_flex
+ l_wrist_roll
+ r_wrist_roll
+ l_gripper_l_finger
+ l_gripper_r_finger
+ r_gripper_l_finger
+ r_gripper_r_finger
+ r_shoulder_pan
+ r_shoulder_lift
+ l_shoulder_pan
+ l_shoulder_lift
torso
base
</group>
@@ -31,24 +31,24 @@
<group name="collision_check" flags="collision">
base
torso
- right_shoulder_pan
- right_shoulder_pitch
- left_shoulder_pan
- left_shoulder_pitch
- left_upper_arm_roll
- right_upper_arm_roll
- left_elbow_flex
- right_elbow_flex
- left_forearm_roll
- right_forearm_roll
- left_wrist_flex
- right_wrist_flex
- left_wrist_roll
- right_wrist_roll
- left_gripper_l_finger
- left_gripper_r_finger
- right_gripper_l_finger
- right_gripper_r_finger
+ r_shoulder_pan
+ r_shoulder_lift
+ l_shoulder_pan
+ l_shoulder_lift
+ l_upper_arm_roll
+ r_upper_arm_roll
+ l_elbow_flex
+ r_elbow_flex
+ l_forearm_roll
+ r_forearm_roll
+ l_wrist_flex
+ r_wrist_flex
+ l_wrist_roll
+ r_wrist_roll
+ l_gripper_l_finger
+ l_gripper_r_finger
+ r_gripper_l_finger
+ r_gripper_r_finger
head_pan
head_tilt
</group>
@@ -56,52 +56,52 @@
<!-- Define groups to check for self collision -->
<group name="collisions1" flags="self_collision">
- right_upper_arm_roll
+ r_upper_arm_roll
torso
</group>
<group name="collisions2" flags="self_collision">
- right_elbow_flex
+ r_elbow_flex
base
</group>
<group name="collisions3" flags="self_collision">
- right_forearm_roll
+ r_forearm_roll
base
</group>
<group name="collisions4" flags="self_collision">
- right_wrist_flex
+ r_wrist_flex
base
</group>
<group name="collisions5" flags="self_collision">
- right_wrist_roll
+ r_wrist_roll
base
</group>
<group name="collisions6" flags="self_collision">
- left_upper_arm_roll
+ l_upper_arm_roll
torso
</group>
<group name="collisions7" flags="self_collision">
- left_elbow_flex
+ l_elbow_flex
base
</group>
<group name="collisions8" flags="self_collision">
- left_forearm_roll
+ l_forearm_roll
base
</group>
<group name="collisions9" flags="self_collision">
- left_wrist_flex
+ l_wrist_flex
base
</group>
<group name="collisions10" flags="self_collision">
- left_wrist_roll
+ l_wrist_roll
base
</group>
Deleted: pkg/trunk/robot_descriptions/wg_robot_description/pr2/init.launch
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/init.launch 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/init.launch 2008-11-20 22:22:40 UTC (rev 7082)
@@ -1,9 +0,0 @@
-<launch>
- <include file="$(find wg_robot_description)/pr2/send_description.launch" />
- <include file="$(find wg_robot_description)/pr2/calibrate.launch" />
- <group name="wg">
- <node pkg="pr2_etherCAT" type="pr2_etherCAT" args="-i rteth0 -x /robotdesc/pr2"
- output="screen"/>
- </group>
-</launch>
-
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xacro.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xacro.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xacro.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -30,33 +30,33 @@
</pr2_base>
- <pr2_torso name="torso" parent="base">
+ <pr2_torso name="torso_lift" parent="base">
<origin xyz="-0.05 0 0.739675" rpy="0 0 0" />
</pr2_torso>
- <pr2_head name="head" parent="torso">
+ <pr2_head name="head" parent="torso_lift">
<origin xyz="0 0 0.3815" rpy="0 0 0" />
</pr2_head>
- <pr2_tilting_laser name="tilt_laser" parent="torso">
+ <pr2_tilting_laser name="laser_tilt" parent="torso_lift">
<origin xyz="0.1 0 0.19525" rpy="0 0 0" />
</pr2_tilting_laser>
- <pr2_arm side="right" reflect="-1" parent="torso">
+ <pr2_arm side="r" reflect="-1" parent="torso_lift">
<origin xyz="0 -0.188 0.0" rpy="0 0 0" />
</pr2_arm>
- <pr2_gripper side="right" parent="right_wrist_roll" />
+ <pr2_gripper side="r" parent="r_wrist_roll" />
- <pr2_arm side="left" reflect="1" parent="torso">
+ <pr2_arm side="l" reflect="1" parent="torso_lift">
<origin xyz="0.0 0.188 0.0" rpy="0 0 0" />
</pr2_arm>
- <pr2_gripper side="left" parent="left_wrist_roll" />
+ <pr2_gripper side="l" parent="l_wrist_roll" />
- <pr2_ptz side="right" reflect="-1" parent="torso">
+ <pr2_ptz side="r" reflect="-1" parent="torso_lift">
<origin xyz="0.0 -0.1975 0.2265" rpy="0 0 0" />
</pr2_ptz>
- <pr2_ptz side="left" reflect="1" parent="torso">
+ <pr2_ptz side="l" reflect="1" parent="torso_lift">
<origin xyz="0.0 0.1975 0.2265" rpy="0 0 0" />
</pr2_ptz>
@@ -65,8 +65,8 @@
<include filename="./groups_collision.xml" />
<!-- Kinematic chains -->
- <chain root="torso" tip="left_wrist_roll" />
- <chain root="torso" tip="right_wrist_roll" />
+ <chain root="torso_lift" tip="l_wrist_roll" />
+ <chain root="torso_lift" tip="r_wrist_roll" />
</robot>
Deleted: pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -1,260 +0,0 @@
-<?xml version="1.0"?>
-
-<robot name="pr2"><!-- name of the robot-->
-
- <!-- Transmissions -->
- <!-- ========================================= -->
- <!--- Casters and wheels -->
- <transmission type="SimpleTransmission" name="caster_front_left_trans">
- <actuator name="caster_front_left_motor" />
- <joint name="caster_front_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_front_left_l_trans">
- <actuator name="wheel_front_left_l_motor" />
- <joint name="wheel_front_left_l_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_front_left_r_trans">
- <actuator name="wheel_front_left_r_motor" />
- <joint name="wheel_front_left_r_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="caster_front_right_trans">
- <actuator name="caster_front_right_motor" />
- <joint name="caster_front_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_front_right_l_trans">
- <actuator name="wheel_front_right_l_motor" />
- <joint name="wheel_front_right_l_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_front_right_r_trans">
- <actuator name="wheel_front_right_r_motor" />
- <joint name="wheel_front_right_r_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="caster_rear_left_trans">
- <actuator name="caster_rear_left_motor" />
- <joint name="caster_rear_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_rear_left_l_trans">
- <actuator name="wheel_rear_left_l_motor" />
- <joint name="wheel_rear_left_l_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_rear_left_r_trans">
- <actuator name="wheel_rear_left_r_motor" />
- <joint name="wheel_rear_left_r_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="caster_rear_right_trans">
- <actuator name="caster_rear_right_motor" />
- <joint name="caster_rear_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_rear_right_l_trans">
- <actuator name="wheel_rear_right_l_motor" />
- <joint name="wheel_rear_right_l_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wheel_rear_right_r_trans">
- <actuator name="wheel_rear_right_r_motor" />
- <joint name="wheel_rear_right_r_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
-<!-- ========================================= -->
-<!-- Torso -->
- <transmission type="SimpleTransmission" name="torso_trans">
- <actuator name="torso_motor" />
- <joint name="torso_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
-<!-- ========================================= -->
-<!-- Left Arm -->
- <transmission type="SimpleTransmission" name="shoulder_pan_left_trans">
- <actuator name="shoulder_pan_left_motor" />
- <joint name="shoulder_pan_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="shoulder_pitch_left_trans">
- <actuator name="shoulder_pitch_left_motor" />
- <joint name="shoulder_pitch_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="upperarm_roll_left_trans">
- <actuator name="upperarm_roll_left_motor" />
- <joint name="upperarm_roll_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="elbow_flex_left_trans">
- <actuator name="elbow_flex_left_motor" />
- <joint name="elbow_flex_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="forearm_roll_left_trans">
- <actuator name="forearm_roll_left_motor" />
- <joint name="forearm_roll_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wrist_flex_left_trans">
- <actuator name="wrist_flex_left_motor" />
- <joint name="wrist_flex_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="gripper_roll_left_trans">
- <actuator name="gripper_roll_left_motor" />
- <joint name="gripper_roll_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
-
- <!-- fingers share a single motor -->
- <transmission type="GripperTransmission" name="gripper_left_trans">
- <actuator name="gripper_left_motor" />
- <joint name="finger_r_left_joint" reduction="-1.0" />
- <joint name="finger_tip_r_left_joint" reduction="1.0" />
- <joint name="finger_l_left_joint" reduction="1.0" />
- <joint name="finger_tip_l_left_joint" reduction="-1.0" />
- <pid p="0.10" i="0.0" d="0.005" iClamp="0.5" />
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
-<!-- ========================================= -->
-<!-- Right Arm -->
- <transmission type="SimpleTransmission" name="shoulder_pan_right_trans">
- <actuator name="shoulder_pan_right_motor" />
- <joint name="shoulder_pan_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="shoulder_pitch_right_trans">
- <actuator name="shoulder_pitch_right_motor" />
- <joint name="shoulder_pitch_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="shoulder_pitch_right_trans">
- <actuator name="shoulder_pitch_right_motor" />
- <joint name="shoulder_pitch_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="upperarm_roll_right_trans">
- <actuator name="upperarm_roll_right_motor" />
- <joint name="upperarm_roll_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="elbow_flex_right_trans">
- <actuator name="elbow_flex_right_motor" />
- <joint name="elbow_flex_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="forearm_roll_right_trans">
- <actuator name="forearm_roll_right_motor" />
- <joint name="forearm_roll_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="wrist_flex_right_trans">
- <actuator name="wrist_flex_right_motor" />
- <joint name="wrist_flex_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="gripper_roll_right_trans">
- <actuator name="gripper_roll_right_motor" />
- <joint name="gripper_roll_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
-
- <!-- fingers share a single motor -->
- <transmission type="GripperTransmission" name="gripper_right_trans">
- <actuator name="gripper_right_motor" />
- <joint name="finger_r_right_joint" reduction="-1.0" />
- <joint name="finger_tip_r_right_joint" reduction="1.0" />
- <joint name="finger_l_right_joint" reduction="1.0" />
- <joint name="finger_tip_l_right_joint" reduction="-1.0" />
- <pid p="0.10" i="0.0" d="0.005" iClamp="0.5" />
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
-<!-- ========================================= -->
-<!-- Head -->
- <transmission type="SimpleTransmission" name="head_pan_trans">
- <actuator name="head_pan_motor" />
- <joint name="head_pan_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="head_tilt_trans">
- <actuator name="head_tilt_motor" />
- <joint name="head_tilt_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="tilt_laser_trans">
- <actuator name="tilt_laser_motor" />
- <joint name="tilt_laser_mount_joint" />
- <mechanicalReduction>6</mechanicalReduction> <!-- per hw test dl 2008 08 22 -->
- <motorTorqueConstant>-0.538</motorTorqueConstant> <!-- per hw test dl 2008 08 22 -->
- <pulsesPerRevolution>10000</pulsesPerRevolution> <!-- per hw test dl 2008 08 22 -->
- </transmission>
-
-</robot>
-
-
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -8,7 +8,7 @@
<kinematics>left_arm</kinematics>
<joints>
<joint name="shoulder_pan_left_joint"/>
- <joint name="shoulder_pitch_left_joint"/>
+ <joint name="shoulder_lift_left_joint"/>
<joint name="upperarm_roll_left_joint"/>
<joint name="elbow_flex_left_joint"/>
<joint name="forearm_roll_left_joint"/>
@@ -26,44 +26,44 @@
<map name="controller_param">
<elem key="kdl_chain_name">left_arm</elem>
</map>
- <controller name="left_shoulder_pan_controller" topic="left_shoulder_pan_controller" type="JointPositionController">
- <joint name="left_shoulder_pan_joint" >
+ <controller name="l_shoulder_pan_controller" topic="l_shoulder_pan_controller" type="JointPositionController">
+ <joint name="l_shoulder_pan_joint" >
<pid p="100" d="200" i="0.1" iClamp="1" />
</joint>
</controller>
- <controller name="left_shoulder_pitch_controller" topic="left_shoulder_pitch_controller" type="JointPositionController">
- <joint name="left_shoulder_pitch_joint" >
+ <controller name="l_shoulder_lift_controller" topic="l_shoulder_lift_controller" type="JointPositionController">
+ <joint name="l_shoulder_lift_joint" >
<pid p="100" d="100.0" i="0.1" iClamp="1" />
</joint>
</controller>
- <controller name="left_upper_arm_roll_controller" topic="left_upper_arm_roll_controller" type="JointPositionController">
- <joint name="left_upper_arm_roll_joint" >
+ <controller name="l_upper_arm_roll_controller" topic="l_upper_arm_roll_controller" type="JointPositionController">
+ <joint name="l_upper_arm_roll_joint" >
<pid p="400" d="400" i="0.1" iClamp="1" />
</joint>
</controller>
- <controller name="left_elbow_flex_controller" topic="left_elbow_flex_controller" type="JointPositionController">
- <joint name="left_elbow_flex_joint" >
+ <controller name="l_elbow_flex_controller" topic="l_elbow_flex_controller" type="JointPositionController">
+ <joint name="l_elbow_flex_joint" >
<pid p="100" d="100" i="0.1" iClamp="1" />
</joint>
</controller>
- <controller name="left_forearm_roll_controller" topic="left_forearm_roll_controller" type="JointPositionController">
- <joint name="left_forearm_roll_joint" >
+ <controller name="l_forearm_roll_controller" topic="l_forearm_roll_controller" type="JointPositionController">
+ <joint name="l_forearm_roll_joint" >
<pid p="200" d="200" i="0.1" iClamp="1" />
</joint>
</controller>
- <controller name="left_wrist_flex_controller" topic="left_wrist_flex_controller" type="JointPositionController">
- <joint name="left_wrist_flex_joint" >
+ <controller name="l_wrist_flex_controller" topic="l_wrist_flex_controller" type="JointPositionController">
+ <joint name="l_wrist_flex_joint" >
<pid p="100" d="100" i="0.1" iClamp="1" />
</joint>
</controller>
- <controller name="left_wrist_roll_controller" topic="left_wrist_roll_controller" type="JointPositionController">
- <joint name="left_wrist_roll_joint" >
+ <controller name="l_wrist_roll_controller" topic="l_wrist_roll_controller" type="JointPositionController">
+ <joint name="l_wrist_roll_joint" >
<pid p="100" d="100" i="0.1" iClamp="0" />
</joint>
</controller>
</controller>
<controller name="gripper_left_controller" topic="gripper_left_controller" type="JointPositionControllerNode">
- <joint name="left_gripper_l_finger_joint">
+ <joint name="l_gripper_l_finger_joint">
<pid p="1.0" d="0.00" i="0.00" iClamp="0.00" />
</joint>
</controller>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/groups_arm.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/groups_arm.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/groups_arm.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -3,13 +3,13 @@
<robot name="pr2"><!-- name of the robot-->
<group name="left_arm" flags="planning kinematic">
- left_shoulder_pan
- left_shoulder_pitch
- left_upper_arm_roll
- left_elbow_flex
- left_forearm_roll
- left_wrist_flex
- left_wrist_roll
+ l_shoulder_pan
+ l_shoulder_lift
+ l_upper_arm_roll
+ l_elbow_flex
+ l_forearm_roll
+ l_wrist_flex
+ l_wrist_roll
<map name="RRT" flag="planning">
<elem key="range" value="0.75" />
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/lqr_control_leftarm.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/lqr_control_leftarm.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/lqr_control_leftarm.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -6,7 +6,7 @@
<controller name="left_arm_controller" type="LQRControllerNode">
<joints>
<joint name="shoulder_pan_left_joint"/>
- <joint name="shoulder_pitch_left_joint"/>
+ <joint name="shoulder_lift_left_joint"/>
<joint name="upperarm_roll_left_joint"/>
<joint name="elbow_flex_left_joint"/>
<joint name="forearm_roll_left_joint"/>
@@ -32,8 +32,8 @@
<pid p="100" d="200" i="0.1" iClamp="1" />
</joint>
</controller>
- <controller name="shoulder_pitch_left_controller" topic="shoulder_pitch_left_controller" type="JointPositionController">
- <joint name="shoulder_pitch_left_joint" >
+ <controller name="shoulder_lift_left_controller" topic="shoulder_lift_left_controller" type="JointPositionController">
+ <joint name="shoulder_lift_left_joint" >
<pid p="100" d="100.0" i="0.1" iClamp="1" />
</joint>
</controller>
@@ -64,7 +64,7 @@
</controller>
</controller>
<controller name="gripper_left_controller" topic="gripper_left_controller" type="JointPositionControllerNode">
- <listen_topic name="left_gripper_commands" />
+ <listen_topic name="l_gripper_commands" />
<joint name="finger_l_left_joint">
<pid p="10" d="0" i="0" iClamp="0" />
<gripper_defaults effortLimit="100" velocityLimit="10" />
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm.xacro.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -21,10 +21,10 @@
<include filename="../pr2_robot_defs/gazebo_defs.xml" />
<include filename="./groups_arm.xml" />
- <pr2_arm side="left" reflect="1" parent="base">
+ <pr2_arm side="l" reflect="1" parent="base">
<origin xyz="0.0 0.0 1.0" rpy="0 0 0" />
</pr2_arm>
- <pr2_gripper side="left" parent="left_wrist_roll" />
+ <pr2_gripper side="l" parent="l_wrist_roll" />
<!-- Solid Base -->
<joint name="base_joint" type="planar">
@@ -61,13 +61,13 @@
<map name="gazebo_material" flag="gazebo">
<verbatim>
<!-- P3D for position groundtruth -->
- <controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
+ <controller:P3D name="p3d_l_wrist_controller" plugin="libP3D.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
- <bodyName>left_gripper_palm</bodyName>
- <topicName>left_gripper_palm_pose_ground_truth</topicName>
+ <bodyName>l_gripper_palm</bodyName>
+ <topicName>l_gripper_palm_pose_ground_truth</topicName>
<frameName>map</frameName>
- <interface:position name="p3d_left_wrist_position"/>
+ <interface:position name="p3d_l_wrist_position"/>
</controller:P3D>
</verbatim>
</map>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -12,9 +12,9 @@
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
- <transmission type="SimpleTransmission" name="shoulder_pitch_left_trans">
- <actuator name="shoulder_pitch_left_motor" />
- <joint name="shoulder_pitch_left_joint" />
+ <transmission type="SimpleTransmission" name="shoulder_lift_left_trans">
+ <actuator name="shoulder_lift_left_motor" />
+ <joint name="shoulder_lift_left_joint" />
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/cal.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/cal.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/cal.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -7,6 +7,6 @@
<base_calibrator />
<head_calibrator />
<torso_calibrator />
- <tilting_laser_calibrator name="tilt_laser" />
+ <tilting_laser_calibrator name="laser_tilt" />
</controllers>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_base_lab.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_base_lab.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_base_lab.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -16,23 +16,23 @@
<elem key="max_y_accel">2.0</elem>
<elem key="max_yaw_accel">1.0</elem>
</map>
- <controller name="wheel_front_left_l_controller" topic="wheel_front_left_l_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_left_l_joint" >
+ <controller name="fl_caster_l_wheel_controller" topic="fl_caster_l_wheel_controller" type="JointVelocityControllerNode">
+ <joint name="fl_caster_l_wheel_joint" >
<pid p="2.0" d="0" i="0.01" iClamp="0.4" />
</joint>
</controller>
- <controller name="wheel_front_left_r_controller" topic="wheel_front_left_r_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_left_r_joint" >
+ <controller name="fl_caster_r_wheel_controller" topic="fl_caster_r_wheel_controller" type="JointVelocityControllerNode">
+ <joint name="fl_caster_r_wheel_joint" >
<pid p="2.0" d="0" i="0.01" iClamp="0.4" />
</joint>
</controller>
- <controller name="wheel_front_right_l_controller" topic="wheel_front_right_l_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_right_l_joint" >
+ <controller name="fr_caster_l_wheel_controller" topic="fr_caster_l_wheel_controller" type="JointVelocityControllerNode">
+ <joint name="fr_caster_l_wheel_joint" >
<pid p="2.0" d="0" i="0.01" iClamp="0.4" />
</joint>
</controller>
- <controller name="wheel_front_right_r_controller" topic="wheel_front_right_r_controller" type="JointVelocityControllerNode">
- <joint name="wheel_front_right_r_joint" >
+ <controller name="fr_caster_r_wheel_controller" topic="fr_caster_r_wheel_controller" type="JointVelocityControllerNode">
+ <joint name="fr_caster_r_wheel_joint" >
<pid p="2.0" d="0" i="0.01" iClamp="0.4" />
</joint>
</controller>
@@ -57,23 +57,23 @@
</joint>
</controller>
- <controller name="caster_front_left_controller" topic="caster_front_left_controller" type="JointVelocityControllerNode">
- <joint name="caster_front_left_joint" >
+ <controller name="fl_caster_rotation_controller" topic="fl_caster_rotation_controller" type="JointVelocityControllerNode">
+ <joint name="fl_caster_rotation_joint" >
<pid p="3" d="0" i="0.1" iClamp="4" />
</joint>
</controller>
- <controller name="caster_front_right_controller" topic="caster_front_right_controller" type="JointVelocityControllerNode">
- <joint name="caster_front_right_joint" >
+ <controller name="fr_caster_rotation_controller" topic="fr_caster_rotation_controller" type="JointVelocityControllerNode">
+ <joint name="fr_caster_rotation_joint" >
<pid p="3" d="0" i="0.1" iClamp="4" />
</joint>
</controller>
- <controller name="caster_rear_left_controller" topic="caster_rear_left_controller" type="JointVelocityControllerNode">
- <joint name="caster_rear_left_joint" >
+ <controller name="bl_caster_rotation_controller" topic="bl_caster_rotation_controller" type="JointVelocityControllerNode">
+ <joint name="bl_caster_rotation_joint" >
<pid p="3" d="0" i="0.1" iClamp="4" />
</joint>
</controller>
- <controller name="caster_rear_right_controller" topic="caster_rear_right_controller" type="JointVelocityControllerNode">
- <joint name="caster_rear_right_joint" >
+ <controller name="br_caster_rotation_controller" topic="br_caster_rotation_controller" type="JointVelocityControllerNode">
+ <joint name="br_caster_rotation_joint" >
<pid p="3" d="0" i="0.1" iClamp="4" />
</joint>
</controller>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/controllers_head_tilt_laser_torso_gazebo.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -25,8 +25,8 @@
</joint>
</controller>
- <controller name="tilt_laser_controller" topic="tilt_laser_controller" type="LaserScannerControllerNode">
- <joint name="tilt_laser_mount_joint" >
+ <controller name="laser_tilt_controller" topic="laser_tilt_controller" type="LaserScannerControllerNode">
+ <joint name="laser_tilt_mount_joint" >
<pid p="12" i=".1" d="1" iClamp="0.5" />
</joint>
</controller>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/laser_controller_config.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/laser_controller_config.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/laser_controller_config.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -1,6 +1,6 @@
<controller name="laser_controller" topic="laser_controller" type="LaserScannerControllerNode">
<filter smoothing_factor="0.1" />
- <joint name="tilt_laser_mount_joint">
+ <joint name="laser_tilt_mount_joint">
<pid p="12" i=".1" d="1" iClamp="0.5" />
</joint>
</controller>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/pr2_prototype1.xacro.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/pr2_prototype1.xacro.xml 2008-11-20 22:20:53 UTC (rev 7081)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_prototype1/pr2_prototype1.xacro.xml 2008-11-20 22:22:40 UTC (rev 7082)
@@ -10,16 +10,16 @@
<origin xyz="0 0 0.0408" rpy="0 0 0" />
</pr2_base>
- <pr2_torso name="torso" parent="base">
+ <pr2_torso name="torso_lift" parent="base">
<!-- TODO: if the spine is at all raised, the z offset is incorrect -->
<origin xyz="-0.05 0 0.739675" rpy="0 0 0" />
</pr2_torso>
- <pr2_head name="head" parent="torso">
+ <pr2_head name="head" parent="torso_lift">
<origin xyz="0 0 0.3815" rpy="0 0 0" />
</pr2_head>
- <pr2_tilting_laser name="tilt_laser" parent="torso">
+ <pr2_tilting_laser name="laser_tilt" parent="torso_lift">
<origin xyz="0.1 0 0.19525" rpy="0 0 0" />
</pr2_tilting_laser>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_robot_defs/arm_defs.xml
========================...
[truncated message content] |