Skip to content

Commit

Permalink
Merge pull request #20 from pal-robotics/public_sim
Browse files Browse the repository at this point in the history
Updating robot model to work in last Gazebo
  • Loading branch information
Sammy Pfeiffer committed Dec 10, 2014
2 parents 2cec3cf + 322d1de commit 2b60455
Show file tree
Hide file tree
Showing 6 changed files with 96 additions and 210 deletions.
248 changes: 61 additions & 187 deletions reem_description/meshes/hand/hand_thumb.dae

Large diffs are not rendered by default.

Binary file modified reem_description/meshes/hand/hand_thumb_collision.stl
Binary file not shown.
22 changes: 15 additions & 7 deletions reem_description/urdf/arm/arm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,17 @@
<!--Constant parameters-->
<xacro:property name="arm_friction" value="1.0" />
<xacro:property name="arm_damping" value="1.0" />
<xacro:property name="arm_max_vel" value="1.0" />
<xacro:property name="arm_1_max_vel" value="2.7" />
<xacro:property name="arm_2_max_vel" value="3.66" />
<xacro:property name="arm_3_max_vel" value="4.58" />
<xacro:property name="arm_4_max_vel" value="4.58" />
<xacro:property name="arm_1_max_effort" value="44.64" />
<xacro:property name="arm_2_max_effort" value="22.32" />
<xacro:property name="arm_3_max_effort" value="17.86" />
<xacro:property name="arm_4_max_effort" value="17.86" />
<xacro:property name="arm_eps" value="0.02" />


<!-- TODO: Update dynamic models -->

<xacro:macro name="reem_arm" params="name parent side reflect">
Expand Down Expand Up @@ -54,7 +62,7 @@
<child link="${name}_${side}_1_link" />
<origin xyz="-0.015 -0.273 0" rpy="${(-165.0*reflect) * deg_to_rad} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${-45.0 * deg_to_rad}" upper="${180.0 * deg_to_rad}" effort="39" velocity="${arm_max_vel}" />
<limit lower="${-45.0 * deg_to_rad}" upper="${180.0 * deg_to_rad}" effort="${arm_1_max_effort}" velocity="${arm_1_max_vel}" />
<dynamics friction="${arm_friction}" damping="${arm_damping}"/>

<safety_controller k_position="20"
Expand Down Expand Up @@ -90,7 +98,7 @@
<child link="${name}_${side}_2_link" />
<origin xyz="0 0 ${0.2385 * reflect}" rpy="${-90.0 * reflect * deg_to_rad} ${-75.0 * reflect * deg_to_rad} ${90.0 * deg_to_rad}" />
<axis xyz="0 0 1" />
<limit lower="${-15.0 * deg_to_rad}" upper="${120.0 * deg_to_rad}" effort="21.7" velocity="${arm_max_vel}" />
<limit lower="${-15.0 * deg_to_rad}" upper="${120.0 * deg_to_rad}" effort="${arm_2_max_effort}" velocity="${arm_2_max_vel}" />
<dynamics friction="${arm_friction}" damping="${arm_damping}"/>

<safety_controller k_position="20"
Expand Down Expand Up @@ -126,7 +134,7 @@
<child link="${name}_${side}_3_link" />
<origin xyz="0.02 -0.142 0" rpy="${90.0 * reflect * deg_to_rad} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${-135.0 * deg_to_rad}" upper="${157.5 * deg_to_rad}" effort="17.4" velocity="${arm_max_vel}" />
<limit lower="${-135.0 * deg_to_rad}" upper="${157.5 * deg_to_rad}" effort="${arm_3_max_effort}" velocity="${arm_3_max_vel}" />
<dynamics friction="${arm_friction}" damping="${arm_damping}"/>

<safety_controller k_position="20"
Expand Down Expand Up @@ -165,7 +173,7 @@
<child link="${name}_${side}_4_link" />
<origin xyz="0 -0.02 ${0.088 * reflect}" rpy="0 ${90.0 * reflect * deg_to_rad} 0" />
<axis xyz="0 0 1" />
<limit lower="0" upper="${130.0 * deg_to_rad}" effort="17.4" velocity="${arm_max_vel}" />
<limit lower="0" upper="${130.0 * deg_to_rad}" effort="${arm_4_max_effort}" velocity="${arm_4_max_vel}" />
<dynamics friction="${arm_friction}" damping="${arm_damping}"/>

<safety_controller k_position="20"
Expand Down Expand Up @@ -215,8 +223,8 @@
<!--***********************-->
<link name="${name}_${side}_tool_link">
<inertial>
<mass value="0.1" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0" />
<mass value="0.001" />
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
</inertial>
<visual>
<origin xyz="0.001 0 0" rpy="0 ${90.0 * deg_to_rad} 0" />
Expand Down
20 changes: 13 additions & 7 deletions reem_description/urdf/arm/wrist.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,13 @@

<!--Constant parameters-->
<xacro:property name="wrist_friction" value="1.0" />
<xacro:property name="wrist_max_vel" value="1.0" />
<xacro:property name="wrist_damping" value="1.0" />
<xacro:property name="wrist_1_max_vel" value="1.95" />
<xacro:property name="wrist_2_max_vel" value="1.76" />
<xacro:property name="wrist_3_max_vel" value="1.76" />
<xacro:property name="wrist_1_max_effort" value="3" />
<xacro:property name="wrist_2_max_effort" value="6.6" />
<xacro:property name="wrist_3_max_effort" value="6.6" />
<xacro:property name="wrist_eps" value="0.02" />

<!-- TODO: Update dynamic models -->
Expand Down Expand Up @@ -53,8 +59,8 @@
<child link="${name}_${side}_5_link" />
<origin xyz="-0.088 0.02 0" rpy="0 ${-90.0 * reflect * deg_to_rad} 0" />
<axis xyz="0 0 1" />
<limit lower="${-120.0 * deg_to_rad}" upper="${120.0 * deg_to_rad}" effort="16" velocity="${wrist_max_vel}" /> <!--TODO: Check effort value!-->
<dynamics friction="${wrist_friction}" damping="0.5"/>
<limit lower="${-120.0 * deg_to_rad}" upper="${120.0 * deg_to_rad}" effort="${wrist_1_max_effort}" velocity="${wrist_1_max_vel}" /> <!--TODO: Check effort value!-->
<dynamics friction="${wrist_friction}" damping="${wrist_damping}"/>

<safety_controller k_position="20"
k_velocity="20"
Expand Down Expand Up @@ -89,8 +95,8 @@
<child link="${name}_${side}_6_link" />
<origin xyz="0 0 ${0.15 * reflect}" rpy="${-90.0 * reflect * deg_to_rad} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${-90.0 * deg_to_rad}" upper="${90.0 * deg_to_rad}" effort="12" velocity="${wrist_max_vel}" />
<dynamics friction="${wrist_friction}" damping="0.1"/>
<limit lower="${-90.0 * deg_to_rad}" upper="${90.0 * deg_to_rad}" effort="${wrist_2_max_effort}" velocity="${wrist_2_max_vel}" />
<dynamics friction="${wrist_friction}" damping="${wrist_damping}"/>

<safety_controller k_position="20"
k_velocity="20"
Expand Down Expand Up @@ -126,8 +132,8 @@
<child link="${name}_${side}_7_link" />
<origin xyz="0 0 0" rpy="${90.0 * reflect * deg_to_rad} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${-120.0 * deg_to_rad}" upper="${120.0 * deg_to_rad}" effort="12" velocity="${wrist_max_vel}" />
<dynamics friction="${wrist_friction}" damping="0.1"/>
<limit lower="${-120.0 * deg_to_rad}" upper="${120.0 * deg_to_rad}" effort="${wrist_3_max_effort}" velocity="${wrist_3_max_vel}" />
<dynamics friction="${wrist_friction}" damping="${wrist_damping}"/>

<safety_controller k_position="20"
k_velocity="20"
Expand Down
8 changes: 4 additions & 4 deletions reem_description/urdf/hand/hand.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -261,10 +261,10 @@
<link name="${name}_${side}_grasping_frame">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.01" /> <!-- matrix below must not be zero, or Gazebo won't load -->
<inertia ixx="0.1" ixy="0.0" ixz="0.0"
iyy="0.1" iyz="0.0"
izz="0.1" />
<mass value="0.0001" /> <!-- matrix below must not be zero, or Gazebo won't load -->
<inertia ixx="0.00001" ixy="0.0" ixz="0.0"
iyy="0.00001" iyz="0.0"
izz="0.00001" />
</inertial>
</link>

Expand Down
8 changes: 3 additions & 5 deletions reem_description/urdf/head/head.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@
<origin xyz="0.01741 0.00466 -0.00434" rpy="0 0 0" />
<mass value="0.98547" />
<!-- NOTE: Assuming cylinder with r=0.06, h=0.08 -->
<!-- <inertia ixx="0.0014125" ixy="0" ixz="0" iyy="0.0014125" iyz="0" izz="0.0017738" /> -->
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
<inertia ixx="0.0014125" ixy="0" ixz="0" iyy="0.0014125" iyz="0" izz="0.0017738" />

</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
Expand Down Expand Up @@ -86,9 +86,7 @@
<origin xyz="-0.04431 -0.13008 0.00011" rpy="0 0 0" />
<mass value="1.20862" />
<!-- NOTE: Assuming box with d=0.28433, w=0.20302, h=0.26741 -->
<!-- <inertia ixx="0.011353" ixy="0" ixz="0" iyy="0.012294" iyz="0" izz="0.015345" /> -->
<!--NOTE: Low (0.1 or lower) diagonal inertia values make Gazebo 1.0.2 simulation unstable when head sensors are added.-->
<inertia ixx="0.25" ixy="0" ixz="0" iyy="0.25" iyz="0" izz="0.25" />
<inertia ixx="0.011353" ixy="0" ixz="0" iyy="0.012294" iyz="0" izz="0.015345" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand Down

0 comments on commit 2b60455

Please sign in to comment.