Skip to content

Commit

Permalink
testing
Browse files Browse the repository at this point in the history
  • Loading branch information
gdiazh committed Jan 27, 2018
1 parent a9678cf commit abc66f5
Show file tree
Hide file tree
Showing 2 changed files with 31 additions and 20 deletions.
27 changes: 19 additions & 8 deletions urdf/leg.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@
<xacro:property name="phalange_height" value="0.0745" />
<xacro:property name="phalange_width" value="0.020" />
<xacro:property name="phalange_large" value="0.020" />
<!-- Friction model from "Characterization and modeling of a Dynamixel servo" by Arno Mensin (model AX12, better than nothing) -->
<!-- Damping N.m.s/rad -->
<xacro:property name="dxl_damping" value="0.15" />
<!-- Friccion N.m -->
<xacro:property name="dxl_friction" value="0.3" />
<xacro:macro name="cuboid_inertia_def" params="x y z mass">
<inertia
iyy="${mass*(z*z+x*x)/12.0}"
Expand Down Expand Up @@ -159,52 +164,58 @@
</collision>
</link>

<joint name="${side}_pelvis_joint" type="revolute">
<joint name="${side}_pelvis_joint" type="fixed">
<parent link="${parent}"/>
<child link="${side}_pelvis"/>
<origin xyz="${-body_large/6} ${reflect*body_width/2} ${body_height/5}" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit effort="4" velocity="1" lower="0" upper="0.01" />
<!--limit effort="1" velocity="4" lower="0" upper="0.01" /-->
<!--dynamics damping="${dxl_damping}" friction="${dxl_friction}" /-->
</joint>

<joint name="${side}_thigh_yaw_joint" type="revolute">
<joint name="${side}_thigh_yaw_joint" type="fixed">
<parent link="${side}_pelvis"/>
<child link="${side}_thigh_yaw"/>
<origin xyz="0 ${reflect*pelvis_width/2} ${-1*pelvis_height}" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit effort="4" velocity="1" lower="0" upper="0.01" />
<!--limit effort="1" velocity="4" lower="0" upper="0.01" /-->
<!--dynamics damping="${dxl_damping}" friction="${dxl_friction}" /-->
</joint>

<joint name="${side}_thigh_pitch_joint" type="revolute">
<parent link="${side}_thigh_yaw"/>
<child link="${side}_thigh"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit effort="4" velocity="1" lower="${-75*M_PI/180}" upper="${45*M_PI/180}" />
<limit effort="1" velocity="4" lower="${-75*M_PI/180}" upper="${45*M_PI/180}" />
<!--dynamics damping="${dxl_damping}" friction="${dxl_friction}" /-->
</joint>

<joint name="${side}_tibia_joint" type="revolute">
<parent link="${side}_thigh"/>
<child link="${side}_tibia"/>
<origin xyz="0 0 ${-1*thigh_height}" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit effort="4" velocity="1" lower="${0*M_PI/180}" upper="${150*M_PI/180}" />
<limit effort="1" velocity="4" lower="${0*M_PI/180}" upper="${150*M_PI/180}" />
<!--dynamics damping="${dxl_damping}" friction="${dxl_friction}" /-->
</joint>

<joint name="${side}_ankle_joint" type="revolute">
<parent link="${side}_tibia"/>
<child link="${side}_ankle"/>
<origin xyz="0 0 ${-1*tibia_height}" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit effort="4" velocity="1" lower="${-90*M_PI/180}" upper="${0*M_PI/180}" />
<limit effort="1" velocity="4" lower="${-90*M_PI/180}" upper="${0*M_PI/180}" />
<!--dynamics damping="${dxl_damping}" friction="${dxl_friction}" /-->
</joint>

<joint name="${side}_phalange_joint" type="revolute">
<parent link="${side}_ankle"/>
<child link="${side}_phalange"/>
<origin xyz="0 0 ${-1*ankle_height}" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit effort="4" velocity="1" lower="${-45*M_PI/180}" upper="0" />
<limit effort="1" velocity="4" lower="${-45*M_PI/180}" upper="0" />
<!--dynamics damping="${dxl_damping}" friction="${dxl_friction}" /-->
</joint>
</xacro:macro>
</robot>
24 changes: 12 additions & 12 deletions urdf/structure.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -31,18 +31,18 @@
<child link="${child}"/>
<origin xyz="0 0 ${-support_height}" rpy="0 0 0" />
</joint>
<joint name="beam_to_slider" type="prismatic">
<joint name="beam_to_slider" type="fixed">
<parent link="beam"/>
<child link="slider"/>
<origin xyz="0 0 ${-1*cross_length}" rpy="0 0 ${90*M_PI/180}" />
<origin xyz="0 0 ${-1*cross_length}" rpy="0 0 ${90*M_PI/180}"/>
<axis xyz="1 0 0" />
<limit effort="3" velocity="2" lower="5" upper="20" />
<!--limit effort="3" velocity="2" lower="5" upper="20" /-->
</joint>
<link name="column">
<inertial>
<origin xyz="0 0 0" />
<mass value="1"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${cross_length}" z="${column_height}" mass="10"/>
<mass value="3"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${cross_length}" z="${column_height}" mass="3"/>
</inertial>
<visual>
<!--origin xyz="-0.0235 0 -0.03525" rpy="0 0 0" /-->
Expand All @@ -61,8 +61,8 @@
<link name="slider">
<inertial>
<origin xyz="0 0 0" />
<mass value="10"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${cross_length}" z="${cross_length}" mass="10"/>
<mass value="0.1"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${cross_length}" z="${cross_length}" mass="0.1"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
Expand All @@ -78,9 +78,9 @@
</link>
<link name="support">
<inertial>
<origin xyz="0 0 ${-1*support_height/2}" />
<mass value="10"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${cross_length}" z="${support_height}" mass="10"/>
<origin xyz="0 0 0" />
<mass value="0.4"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${cross_length}" z="${support_height}" mass="0.4"/>
</inertial>
<visual>
<origin xyz="0 0 ${-1*support_height/2}" rpy="0 0 0" />
Expand All @@ -98,8 +98,8 @@
<link name="beam">
<inertial>
<origin xyz="0 ${beam_height/2} 0" />
<mass value="2"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${beam_height}" z="${cross_length}" mass="10"/>
<mass value="8"/>
<xacro:cuboid_inertia_def x="${cross_length}" y="${beam_height}" z="${cross_length}" mass="8"/>
</inertial>
<visual>
<!--origin xyz="-0.0235 0 -0.03525" rpy="0 0 0" /-->
Expand Down

0 comments on commit abc66f5

Please sign in to comment.