|
From: <hsu...@us...> - 2009-02-12 20:46:53
|
Revision: 11058
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=11058&view=rev
Author: hsujohnhsu
Date: 2009-02-12 20:46:43 +0000 (Thu, 12 Feb 2009)
Log Message:
-----------
* arm_defs - increase damping on wrist_roll
* gripper_defs - update some mass/cg info. update collision boxes.
* test_arm.py - updates due to changes in gripper_defs
* test_camera.valid.ppm - new image
* set_goal.py - rostopic change for bumper feedback to /info (new /force)
* r_arm_grasping_demo.launch - new comments on rxplot
* urdf2gazebo and urdf2factory - fix axis offset, still off by a little bit, think it's gazebo error.
Modified Paths:
--------------
pkg/trunk/demos/arm_gazebo/r_arm_grasping_demo.launch
pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp
pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_arm.py
pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_camera.valid.ppm
pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp
pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/arm_defs.xml
pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/gripper_defs.xml
Modified: pkg/trunk/demos/arm_gazebo/r_arm_grasping_demo.launch
===================================================================
--- pkg/trunk/demos/arm_gazebo/r_arm_grasping_demo.launch 2009-02-12 20:37:36 UTC (rev 11057)
+++ pkg/trunk/demos/arm_gazebo/r_arm_grasping_demo.launch 2009-02-12 20:46:43 UTC (rev 11058)
@@ -32,6 +32,7 @@
<!-- for visualization -->
<!--
<node pkg="ogre_visualizer" type="standalone_visualizer.py" respawn="false" output="screen" />
+ <node pkg="rosviz" type="rxplot" args="/r_gripper_l_finger_tip_bumper/force/vector/x /r_gripper_l_finger_tip_bumper/force/vector/y /r_gripper_l_finger_tip_bumper/force/vector/z" respawn="false" output="screen" />
-->
<param name="robotdesc/table" command="$(find xacro)/xacro.py '$(find examples_gazebo)/table_defs/table_defs.xml'" />
Modified: pkg/trunk/demos/test_2dnav_gazebo/set_goal.py
===================================================================
--- pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-02-12 20:37:36 UTC (rev 11057)
+++ pkg/trunk/demos/test_2dnav_gazebo/set_goal.py 2009-02-12 20:46:43 UTC (rev 11058)
@@ -163,8 +163,8 @@
pub_goal = rospy.Publisher("goal", Planner2DGoal) #received by wavefront_player or equivalent
rospy.Subscriber("base_pose_ground_truth", PoseWithRatesStamped, self.p3dInput)
rospy.Subscriber("odom" , RobotBase2DOdom , self.odomInput)
- rospy.Subscriber("base_bumper" , String , self.bumpedInput)
- rospy.Subscriber("torso_lift_bumper" , String , self.bumpedInput)
+ rospy.Subscriber("base_bumper/info" , String , self.bumpedInput)
+ rospy.Subscriber("torso_lift_bumper/info", String , self.bumpedInput)
rospy.init_node(NAME, anonymous=True)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp 2009-02-12 20:37:36 UTC (rev 11057)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/urdf2factory.cpp 2009-02-12 20:46:43 UTC (rev 11058)
@@ -353,7 +353,7 @@
for (int j = 0 ; j < 3 ; ++j)
{
// undo Gazebo's shift of object anchor to geom xyz, stay in body cs
- tmpAnchor[j] = (link->joint->anchor)[j] - 1.0*(link->inertial->com)[j] - 0.0*(link->collision->xyz)[j]; /// @todo compensate for gazebo's error. John is fixing this one
+ tmpAnchor[j] = (link->joint->anchor)[j] - 0.0*(link->inertial->com)[j] - 1.0*(link->collision->xyz)[j]; /// @todo compensate for gazebo's error. John is fixing this one
}
addKeyValue(joint, "anchorOffset", values2str(3, tmpAnchor));
Modified: pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_arm.py
===================================================================
--- pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_arm.py 2009-02-12 20:37:36 UTC (rev 11057)
+++ pkg/trunk/drivers/simulator/test_pr2_mechanism_controllers_gazebo/test_arm.py 2009-02-12 20:46:43 UTC (rev 11058)
@@ -70,21 +70,21 @@
TEST_TIMEOUT = 50.0
# pre-recorded poses for above commands
-TARGET_PALM_TX = 0.714446037376
-TARGET_PALM_TY = 0.278116217261
-TARGET_PALM_TZ = 0.784828115329
-TARGET_PALM_QX = 0.237210502633
-TARGET_PALM_QY = -0.182803620068
-TARGET_PALM_QZ = 0.190038432015
-TARGET_PALM_QW = 0.934986314492
+TARGET_PALM_TX = 0.727619501795
+TARGET_PALM_TY = 0.313729662125
+TARGET_PALM_TZ = 0.789418474081
+TARGET_PALM_QX = 0.237324223096
+TARGET_PALM_QY = -0.182525634899
+TARGET_PALM_QZ = 0.190044686338
+TARGET_PALM_QW = 0.935010493487
-TARGET_FNGR_TX = 0.777019619684
-TARGET_FNGR_TY = 0.30750529852
-TARGET_FNGR_TZ = 0.822392652239
-TARGET_FNGR_QX = 0.201732745048
-TARGET_FNGR_QY = -0.221335744649
-TARGET_FNGR_QZ = 0.350039819038
-TARGET_FNGR_QW = 0.887573384461
+TARGET_FNGR_TX = 0.789451486586
+TARGET_FNGR_TY = 0.34264635999
+TARGET_FNGR_TZ = 0.826417972272
+TARGET_FNGR_QX = 0.207225356499
+TARGET_FNGR_QY = -0.216229383323
+TARGET_FNGR_QZ = 0.327829069225
+TARGET_FNGR_QW = 0.896008151069
class ArmTest(unittest.TestCase):
def __init__(self, *args):
Modified: pkg/trunk/drivers/simulator/test_pr2_sensors_gazebo/test_camera.valid.ppm
===================================================================
(Binary files differ)
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp 2009-02-12 20:37:36 UTC (rev 11057)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp 2009-02-12 20:46:43 UTC (rev 11058)
@@ -341,7 +341,7 @@
for (int j = 0 ; j < 3 ; ++j)
{
// undo Gazebo's shift of object anchor to geom xyz, stay in body cs
- tmpAnchor[j] = (link->joint->anchor)[j] - 1.0*(link->inertial->com)[j] - 0.0*(link->collision->xyz)[j]; /// @todo compensate for gazebo's error. John is fixing this one
+ tmpAnchor[j] = (link->joint->anchor)[j] - 0.0*(link->inertial->com)[j] - 1.0*(link->collision->xyz)[j]; /// @todo compensate for gazebo's error. John is fixing this one
}
addKeyValue(joint, "anchorOffset", values2str(3, tmpAnchor));
Modified: pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/arm_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/arm_defs.xml 2009-02-12 20:37:36 UTC (rev 11057)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/arm_defs.xml 2009-02-12 20:46:43 UTC (rev 11058)
@@ -569,7 +569,7 @@
<anchor xyz="0 0 0" />
<limit effort="10" velocity="${VELOCITY_LIMIT_SCALE*6}" k_velocity="2" />
<calibration reference_position="${1.27+wrist_roll_cal}" values="1.5 -1" />
- <joint_properties damping="0.1" />
+ <joint_properties damping="2.0" />
</joint>
Modified: pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/gripper_defs.xml
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/gripper_defs.xml 2009-02-12 20:37:36 UTC (rev 11057)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/defs/gripper_defs.xml 2009-02-12 20:46:43 UTC (rev 11058)
@@ -6,7 +6,7 @@
<property name="M_PI" value="3.1415926535897931" />
<property name="gripper_max_angle" value="0.548" />
- <property name="gripper_min_angle" value="0.05" />
+ <property name="gripper_min_angle" value="0.00" />
<property name="finger_tip_mu" value="50.0" />
<property name="finger_joint_effort_limit" value="10.0" />
@@ -19,26 +19,30 @@
<axis xyz="0 0 1" />
<anchor xyz="0 0 0" />
<calibration reference_position="0" values="1.0 -1.0" />
- <limit effort="${finger_joint_effort_limit}" min="${gripper_min_angle*0}" max="${gripper_max_angle}"
+ <limit effort="${finger_joint_effort_limit}" min="${gripper_min_angle}" max="${gripper_max_angle}"
k_position="1.0" k_velocity="1.0" velocity="0.5"
safety_length_min="0.0" safety_length_max="0.0" />
<joint_properties damping="0.2" />
<map name="${prefix}_l_finger_joint_feedback" flag="gazebo">
<elem key="provideFeedback" value="true"/>
+ <elem key="initialAngle" value="${gripper_min_angle}"/>
</map>
</joint>
<link name="${prefix}_l_finger_link">
<parent name="${parent}" />
- <origin xyz="0.07751 ${1*0.01} 0" rpy="0 0 ${gripper_min_angle}" />
+ <origin xyz="0.07691 0.01 0" rpy="0 0 0" />
<joint name="${prefix}_l_finger_joint" />
<inertial>
<mass value="0.17126" />
- <com xyz="0.03598 0.01730 -0.00164" />
- <inertia ixx="0.00007756198" ixy="0.00000149095" ixz="-0.00000983385"
- iyy="0.00019708305" iyz="-0.00000306125"
- izz="0.00018105446" />
+ <com xyz="${0.03598} 0.01730 -0.00164" />
+ <inertia ixx= "0.00007756198"
+ ixy= "0.00000149095"
+ ixz="-0.00000983385"
+ iyy= "0.00019708305"
+ iyz="-0.00000306125"
+ izz= "0.00018105446" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -50,9 +54,9 @@
</geometry>
</visual>
<collision>
- <origin xyz="0.045 0.015 0.0" rpy="0 0 0" />
+ <origin xyz="0.03598 0.01730 -0.00164" rpy="0 0 0" />
<geometry name="${prefix}_l_finger_collision">
- <box size="0.09 0.030 0.049" />
+ <box size="0.09 0.040 0.049" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -86,7 +90,7 @@
<axis xyz="0 0 1" />
<anchor xyz="0 0 0" />
<calibration reference_position="0" values="1.0 -1.0" />
- <limit effort="${finger_joint_effort_limit}" min="${-gripper_max_angle}" max="${-gripper_min_angle*0}"
+ <limit effort="${finger_joint_effort_limit}" min="${-gripper_max_angle}" max="${-gripper_min_angle}"
k_position="0" k_velocity="0" velocity="0.0"
safety_length_min="0.0" safety_length_max="0.0" />
<joint_properties damping="0.2" />
@@ -96,20 +100,24 @@
<elem key="mimicKd" value="10.0" />
<elem key="mimicFMax" value="10.0" />
<elem key="provideFeedback" value="true"/>
+ <elem key="initialAngle" value="${-gripper_min_angle}"/>
</map>
</joint>
<link name="${prefix}_r_finger_link">
<parent name="${parent}" />
- <origin xyz="0.07751 ${-1*0.01} 0" rpy="0 0 ${-gripper_min_angle}" />
+ <origin xyz="0.07691 -0.01 0" rpy="0 0 0" />
<joint name="${prefix}_r_finger_joint" />
<inertial>
<mass value="0.17389" />
- <com xyz="0.03576 -0.01736 -0.00095" />
- <inertia ixx="0.00007738410" ixy="-0.00000209309" ixz="-0.00000836228"
- iyy="0.00019847383" iyz="0.00000246110"
- izz="0.00018106988" />
+ <com xyz="${0.03576} -0.01736 -0.00095" />
+ <inertia ixx= "0.00007738410"
+ ixy="-0.00000209309"
+ ixz="-0.00000836228"
+ iyy= "0.00019847383"
+ iyz= "0.00000246110"
+ izz= "0.00018106988" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
@@ -121,9 +129,9 @@
</geometry>
</visual>
<collision>
- <origin xyz="0.045 -0.015 0.0" rpy="0 0 0" />
+ <origin xyz="0.03576 -0.01736 -0.00095" rpy="0 0 0" />
<geometry name="${prefix}_r_finger_collision">
- <box size="0.09 0.030 0.049" />
+ <box size="0.09 0.040 0.049" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -157,7 +165,7 @@
<axis xyz="0 0 1" />
<anchor xyz="0 0 0" />
<calibration reference_position="0" values="1.0 -1.0" />
- <limit effort="${finger_joint_effort_limit}" min="${-gripper_max_angle}" max="${-gripper_min_angle*0}"
+ <limit effort="${finger_joint_effort_limit}" min="${-gripper_max_angle}" max="${-gripper_min_angle}"
k_position="0" k_velocity="0" velocity="0.0"
safety_length_min="0.0" safety_length_max="0.0" />
<joint_properties damping="0.002" />
@@ -167,12 +175,13 @@
<elem key="mimicKd" value="10.0" />
<elem key="mimicFMax" value="10.0" />
<elem key="provideFeedback" value="true"/>
+ <elem key="initialAngle" value="${-gripper_min_angle}"/>
</map>
</joint>
<link name="${prefix}_l_finger_tip_link">
<parent name="${prefix}_l_finger_link" />
- <origin xyz="0.0915 0 0" rpy="0 0 ${-gripper_min_angle}" />
+ <origin xyz="0.09137 0.00495 0" rpy="0 0 0" />
<joint name="${prefix}_l_finger_tip_joint" />
<inertial>
@@ -183,7 +192,7 @@
izz="0.00001541768" />
</inertial>
<visual>
- <origin xyz="0 0 0 " rpy="0 0 0 " />
+ <origin xyz="0 0 0" rpy="0 0 0" />
<map name="gazebo_material" flag="gazebo">
<elem key="material" value="Gazebo/Green" />
</map>
@@ -192,9 +201,9 @@
</geometry>
</visual>
<collision>
- <origin xyz="0.0120 0.005 0.0" rpy="0 0 0" />
+ <origin xyz="0.00846 0.00568 0.0" rpy="0 0 0" />
<geometry name="${prefix}_l_finger_tip_collision">
- <box size="0.038 0.04 0.023" />
+ <box size="0.04577 0.0425 0.023" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -221,6 +230,7 @@
<elem key="mu2" value="${finger_tip_mu}" />
<elem key="kp" value="100000000.0" />
<elem key="kd" value="1.0" />
+ <elem key="selfCollide" value="false" />
</map>
</link>
@@ -230,7 +240,7 @@
<axis xyz="0 0 1" />
<anchor xyz="0 0 0" />
<calibration reference_position="0" values="1.0 -1.0" />
- <limit effort="${finger_joint_effort_limit}" min="${gripper_min_angle*0}" max="${gripper_max_angle}"
+ <limit effort="${finger_joint_effort_limit}" min="${gripper_min_angle}" max="${gripper_max_angle}"
k_position="0" k_velocity="0" velocity="0.0"
safety_length_min="0.0" safety_length_max="0.0" />
<joint_properties damping="0.002" />
@@ -240,17 +250,18 @@
<elem key="mimicKd" value="10.0" />
<elem key="mimicFMax" value="10.0" />
<elem key="provideFeedback" value="true"/>
+ <elem key="initialAngle" value="${gripper_min_angle}"/>
</map>
</joint>
<link name="${prefix}_r_finger_tip_link">
<parent name="${prefix}_r_finger_link" />
- <origin xyz="0.0915 0 0" rpy="0 0 ${gripper_min_angle}" />
+ <origin xyz="${0.09137} ${-0.00495} 0" rpy="0 0 0" />
<joint name="${prefix}_r_finger_tip_joint" />
<inertial>
<mass value="0.04419" />
- <com xyz="0.00423 -0.00284 0.0" />
+ <com xyz="${0.00423} ${-0.00284} ${0.0}" />
<inertia ixx="0.00000837047" ixy="-0.00000583632" ixz="0.0"
iyy="0.00000987067" iyz="0.0"
izz="0.00001541768" />
@@ -265,9 +276,9 @@
</geometry>
</visual>
<collision>
- <origin xyz="0.0120 -0.005 0.0" rpy="0 0 0" />
+ <origin xyz="${0.00846} ${-0.00568} 0.0" rpy="0 0 0" />
<geometry name="${prefix}_r_finger_tip_collision">
- <box size="0.038 0.04 0.023" />
+ <box size="0.04577 0.0425 0.023" />
</geometry>
<verbose value="Yes" />
<map flag="collision" name="mesh">
@@ -294,6 +305,7 @@
<elem key="mu2" value="${finger_tip_mu}" />
<elem key="kp" value="100000000.0" />
<elem key="kd" value="1.0" />
+ <elem key="selfCollide" value="false" />
</map>
</link>
@@ -469,9 +481,18 @@
<com xyz="0 0 0" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <map name="gazebo_material" flag="gazebo">
+ <elem key="material" value="Gazebo/Shell" />
+ </map>
+ <geometry name="${side}_gripper_tool_visual">
+ <mesh scale="0.0 0.0 0.0" />
+ </geometry>
+ </visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
- <geometry name="${side}_gripper_collision_dummy">
+ <geometry name="${side}_gripper_tool_collision">
<box size="0.1 0.1 0.1" />
</geometry>
</collision>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|