Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

corrected arm dynamics #15

Open
wants to merge 1 commit into
base: kinetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
247 changes: 247 additions & 0 deletions urdf/youbot_arm/arm_corrected_dynamics.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,247 @@
<?xml version="1.0"?>
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://www.ros.org/wiki/xacro/#interface">

<xacro:include filename="$(find youbot_description)/urdf/youbot_arm/arm.gazebo.xacro" />
<xacro:include filename="$(find youbot_description)/urdf/youbot_arm/arm.transmission.xacro" />
<xacro:include filename="$(find youbot_description)/urdf/youbot_arm/limits_corrected_dynamics.urdf.xacro" />

<xacro:macro name="youbot_arm" params="parent name *origin">

<!-- joint between base_link and arm_0_link -->
<joint name="${name}_joint_0" type="fixed" >
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${name}_link_0" />

</joint>

<link name="${name}_link_0">
<inertial>
<!--<origin xyz="0.023 0 0.006" rpy="0 0 0"/>-->
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${link_0_mass}"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
</inertial>

<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm0.dae" />
</geometry>
<material name="youBot/DarkGrey" />
</visual>

<collision>
<!--<origin xyz="0.023 0 0.006" rpy="0 0 0"/>-->
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm0_convex.dae" />
<!--<cylinder length="0.078" radius="0.093"/>-->
</geometry>
</collision>

</link>

<!-- joint between arm_0_link and arm_1_link -->
<joint name="${name}_joint_1" type="revolute">
<origin xyz="0.024 0 0.115" rpy="${M_PI} 0 0"/>
<parent link="${name}_link_0"/>
<child link="${name}_link_1"/>
<axis xyz="0 0 1"/>
<!--<calibration rising="${arm_1_ref}" falling="${arm_1_ref}"/>-->
<dynamics damping="1" friction="0.5" />
<!-- damping - N*s/m, N*s*m/rad -->
<!-- friction - N, N*m -->
<limit effort="${9.5}" velocity="${M_PI / 2.0}" lower="${-169 * M_PI / 180}" upper="${169 * M_PI / 180}"/>
<!--effort - N, N*m-->
<!--velocity - m/s, rad/s-->
<!--safety_controller k_position="20" k_velocity="${9.5/M_PI / 2.0}" soft_lower_limit="${threshold}" soft_upper_limit="${joint_1_limit_soft}" /-->
<!--k_position N/m, N/rad-->
<!--k_velocity N*s/m, N*s*m/rad-->
<!--for details: http://www.ros.org/wiki/pr2_controller_manager/safety_limits-->
</joint>

<link name="${name}_link_1">
<inertial>
<mass value="${link_1_mass}"/>
<xacro:link_1_inertia_tensor />
</inertial>

<visual>
<origin xyz="0.0 0 0.02" rpy="-${M_PI} 0 0" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm1.dae" />
</geometry>
<material name="youBot/Orange" />
</visual>

<collision>
<origin xyz="0.0 0 0.02" rpy="-${M_PI} 0 0" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm1_convex.dae" />
<!--<cylinder length="0.102" radius="0.080"/>-->
</geometry>
</collision>
</link>

<!-- joint between arm_1_link and arm_2_link -->
<joint name="${name}_joint_2" type="revolute">
<origin xyz="0.033 0 0.0" rpy="${M_PI_2} ${M_PI_2} 0"/>
<parent link="${name}_link_1"/>
<child link="${name}_link_2"/>
<axis xyz="0 0 1"/>
<!--<calibration rising="${arm_2_ref}" falling="${arm_2_ref}"/>-->
<dynamics damping="1" friction="0.5" />
<limit effort="${9.5}" velocity="${M_PI / 2.0}" lower="${-65 * M_PI / 180}" upper="${90 * M_PI / 180}"/>
<!--safety_controller k_position="20" k_velocity="${2*9.5/M_PI}" soft_lower_limit="${threshold}" soft_upper_limit="${joint_2_limit_soft}" /-->
</joint>

<link name="${name}_link_2">
<inertial>
<mass value="${link_2_mass}"/>
<xacro:link_2_inertia_tensor />
</inertial>

<visual>
<origin xyz="0.078 0.0 -0.032" rpy="${M_PI_2} 0 ${M_PI_2}" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm2.dae" />
</geometry>
</visual>

<collision>
<!--<origin xyz="0.001 -0.041 0.074" rpy="0 0 0" />-->
<origin xyz="0.078 0.0 -0.032" rpy="${M_PI_2} 0 ${M_PI_2}" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm2_convex.dae" />
<!--<box size="0.074 0.082 0.222"/>-->
</geometry>
</collision>
</link>

<!-- joint between arm_2_link and arm_3_link -->
<!--<joint name="${name}_joint_3" type="revolute">
<origin xyz="0.000 0.000 0.155" rpy="0 ${146 * M_PI / 180} 0"/>
<parent link="${name}_link_2"/>
<child link="${name}_link_3"/>
<axis xyz="0 1 0"/>
<dynamics damping="1" friction="1" />
<limit effort="${6}" velocity="${M_PI / 2.0}" lower="-${joint_3_limit}" upper="0"/>
<safety_controller k_position="20" k_velocity="50" soft_lower_limit="-${joint_3_limit_soft}" soft_upper_limit="${threshold}" />
</joint>-->
<joint name="${name}_joint_3" type="revolute">
<origin xyz="0.155 0.000 0.0" rpy="0 0 -${M_PI_2}"/>
<parent link="${name}_link_2"/>
<child link="${name}_link_3"/>
<axis xyz="0 0 1"/>
<dynamics damping="1" friction="0.5" />
<limit effort="${6.0}" velocity="${M_PI / 2.0}" lower="${-151 * M_PI / 180}" upper="${146 * M_PI / 180}"/>
<!--safety_controller k_position="20" k_velocity="50" soft_lower_limit="-${joint_3_limit_soft}" soft_upper_limit="-${threshold}" /-->
</joint>

<link name="${name}_link_3">
<inertial>
<mass value="${link_3_mass}"/>
<xacro:link_3_inertia_tensor />
</inertial>

<visual>
<origin xyz="0.000 0.079 0.028" rpy="-${M_PI_2} ${M_PI} 0" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm3.dae" />
</geometry>
<material name="youBot/Orange" />
</visual>

<collision>
<!--<origin xyz="0.000 0.025 0.067" rpy="0 0 0" />-->
<origin xyz="0.000 0.079 0.028" rpy="-${M_PI_2} ${M_PI} 0" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm3_convex.dae" />
<!--<box size="0.064 0.054 0.192"/>-->
</geometry>
</collision>
</link>

<!-- joint between arm_3_link and arm_4_link -->
<joint name="${name}_joint_4" type="revolute">
<origin xyz="0.000 0.135 0.0" rpy="0 0 0" />
<parent link="${name}_link_3"/>
<child link="${name}_link_4"/>
<axis xyz="0 0 1" />
<!--<calibration rising="${arm_4_ref}" falling="${arm_4_ref}"/>-->
<dynamics damping="1" friction="0.5" />
<limit effort="${2.0}" velocity="${M_PI / 2.0}" lower="${-102.5 * M_PI / 180}" upper="${102.5 * M_PI / 180}"/>
<!--safety_controller k_position="20" k_velocity="100" soft_lower_limit="0" soft_upper_limit="${joint_4_limit_soft}" /-->
</joint>

<link name="${name}_link_4">
<inertial>
<mass value="${link_4_mass}"/>
<xacro:link_4_inertia_tensor />
</inertial>

<visual>
<!-- <origin xyz="0 -0.010 0.029" rpy="${M_PI} 0 0"/> -->
<origin xyz="0 0.029 -0.010" rpy="-${M_PI_2} ${M_PI} 0"/>
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm4.dae" />
</geometry>
<material name="youBot/Orange" />
</visual>

<collision>
<!--<origin xyz="0 0 0.026" rpy="0 0 0" />-->
<origin xyz="0 0.029 -0.010" rpy="-${M_PI_2} ${M_PI} 0"/>
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm4_convex.dae" />
<!--<box size="0.058 0.100 0.118"/>-->
</geometry>
</collision>
</link>

<!-- joint between arm_4_link and arm_5_link -->
<joint name="${name}_joint_5" type="revolute">
<origin xyz="0.00 0.1136 0.0" rpy="-${M_PI_2} 0 0" />
<parent link="${name}_link_4"/>
<child link="${name}_link_5"/>
<axis xyz="0 0 -1" />
<!--<calibration rising="${arm_5_ref}" falling="${arm_5_ref}"/>-->
<dynamics damping="0.5" friction="0.5" />
<limit effort="${1.0}" velocity="${M_PI / 2.0}" lower="${-165 * M_PI / 180}" upper="${165 * M_PI / 180}" />
<!--safety_controller k_position="20" k_velocity="100" soft_lower_limit="0" soft_upper_limit="${joint_5_limit_soft}" /-->
</joint>

<link name="${name}_link_5">
<inertial>
<mass value="${link_5_mass}"/>
<xacro:link_5_inertia_tensor />
</inertial>

<visual>
<origin xyz="0.00 0 -0.019" rpy="0 0 0" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm5.dae" />
</geometry>
<material name="youBot/DarkGrey" />
</visual>

<collision>
<origin xyz="0.00 0 -0.019" rpy="0 0 0" />
<geometry>
<mesh filename="package://youbot_description/meshes/youbot_arm/arm5_convex.dae" />
<!--<box size="0.054 0.096 0.030"/>-->
</geometry>
</collision>
</link>

<!-- extensions -->
<xacro:youbot_arm_gazebo name="${name}" />
<xacro:youbot_arm_transmission name="${name}" />

</xacro:macro>

</robot>
79 changes: 79 additions & 0 deletions urdf/youbot_arm/limits_corrected_dynamics.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro/#interface">

<!-- common properties -->
<xacro:property name="M_PI" value="3.1415926535897931" />
<xacro:property name="M_PI_2" value="1.570796327" />
<xacro:property name="threshold" value="0.01" />

<!-- arm limits positions (deg) -->
<xacro:property name="joint_1_limit" value="${M_PI * (169 + 169) / 180}" />
<xacro:property name="joint_2_limit" value="${M_PI * (90 + 65) / 180}" />
<xacro:property name="joint_3_limit" value="${M_PI * (146 + 151) / 180}" />
<xacro:property name="joint_4_limit" value="${M_PI * (102.5 + 102.5) / 180}" />
<xacro:property name="joint_5_limit" value="${M_PI * (167.5 + 167.5) / 180}" />

<xacro:property name="joint_1_limit_soft" value="${joint_1_limit - threshold}" />
<xacro:property name="joint_2_limit_soft" value="${joint_2_limit - threshold}" />
<xacro:property name="joint_3_limit_soft" value="${joint_3_limit - threshold}" />
<xacro:property name="joint_4_limit_soft" value="${joint_4_limit - threshold}" />
<xacro:property name="joint_5_limit_soft" value="${joint_5_limit - threshold}" />

<!-- dynamic properties : mass (kg) Alu data sheet -->
<xacro:property name="link_0_mass" value="0.961" />
<xacro:property name="link_1_mass" value="1.390" />
<xacro:property name="link_2_mass" value="1.318" />
<xacro:property name="link_3_mass" value="0.821" />
<xacro:property name="link_4_mass" value="0.769" />
<xacro:property name="link_5_mass" value="0.687" />
<!--<xacro:property name="link_0_mass" value="0.845" />
<xacro:property name="link_1_mass" value="0.1" />
<xacro:property name="link_2_mass" value="0.1" />
<xacro:property name="link_3_mass" value="0.1" />
<xacro:property name="link_4_mass" value="0.1" />
<xacro:property name="link_5_mass" value="0.1" />-->
<!-- TODO: add inertia tensor-->

<xacro:macro name="default_origin">
<origin xyz="0 0 0" rpy="0 0 0"/> <!-- no data known -->
</xacro:macro>

<xacro:macro name="link_default_inertia_tensor">
<origin xyz="0 0 0"
rpy="0 0 0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</xacro:macro>

<xacro:macro name="link_1_inertia_tensor">
<origin xyz="${15.16/1000} ${3.59/1000} ${31.05/1000}"
rpy="0 ${-20 * M_PI / 180} ${M_PI}" />
<inertia ixx="0.0029525" ixy="0.0" ixz="0.0" iyy="0.0060091" iyz="0.0" izz="0.0058821"/>
</xacro:macro>

<xacro:macro name="link_2_inertia_tensor">
<origin xyz="${113.97/1000} ${15.0/1000} ${-19.03/1000}"
rpy="-${M_PI_2} -${M_PI_2} 0" />
<inertia ixx="0.0031145" ixy="0.0" ixz="0.0" iyy="0.0005843" iyz="0.0" izz="0.0031631"/>
</xacro:macro>

<xacro:macro name="link_3_inertia_tensor">
<origin xyz="${0.13/1000} ${104.41/1000} ${20.22/1000}"
rpy="${M_PI_2} 0 0" />
<inertia ixx="0.00172767" ixy="0.0" ixz="0.0" iyy="0.00041967" iyz="0.0" izz="0.0018468"/>
</xacro:macro>

<xacro:macro name="link_4_inertia_tensor">
<origin xyz="${0.15/1000} ${53.53/1000} ${-24.64/1000}"
rpy="${140 * M_PI / 180} 0 ${M_PI}" />
<inertia ixx="0.0006764" ixy="0.0" ixz="0.0" iyy="0.0010573" iyz="0.0" izz="0.0006610"/>
</xacro:macro>

<xacro:macro name="link_5_inertia_tensor">
<origin xyz="${0/1000} ${1.2/1000} ${-16.48/1000}"
rpy="0 ${M_PI_2} 0" />
<inertia ixx="0.0001934" ixy="0.0" ixz="0.0" iyy="0.0001602" iyz="0.0" izz="0.0000689"/>

</xacro:macro>


</robot>