Skip to content

Commit

Permalink
Merge branch 'release/7.0'
Browse files Browse the repository at this point in the history
  • Loading branch information
coord-e committed Feb 8, 2019
2 parents bb9e65d + c908423 commit 2e95e71
Show file tree
Hide file tree
Showing 3 changed files with 26 additions and 32 deletions.
48 changes: 17 additions & 31 deletions robots/yamax.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,43 +8,29 @@

<xacro:include filename="$(cwd)/xacro/material.xacro" />

<link name="base_link" />
<xacro:link name="base_link" w="0.090" h="0.150" d="0.004" mass="0.07061" x="0" y="0" z="0" material="Orange" has_imu="true" />
<xacro:link name="board" w="0.085" h="0.115" d="0.020" mass="0.1000" x="0" y="0" z="0.010" material="Black" />
<xacro:fixed_joint name="board" parent="base_link" child="board" z="0.004" />

<xacro:link name="hip" w="0.100" h="0.160" d="0.004" mass="0.207" x="0" y="0" z="0" material="Orange" has_imu="true" />
<xacro:link name="board" w="0.085" h="0.115" d="0.065" mass="0.220" x="0" y="0" z="0.0325" material="Black" />
<xacro:joint name="ignore_board" aname="board" parent="hip" child="board" z="0.004" axis="x" />

<xacro:joint name="ignore_hip_right" aname="ignore_hip_right" parent="hip" child="hip_right" y="-0.051" z="-0.004" axis="x" />
<xacro:fixed_joint name="hip_right" parent="base_link" child="hip_right" y="-0.04325" z="-0.004" />
<xacro:link name="hip_right" w="0.0325" h="0.032" d="0.043" y="0" z="-0.0215" mass="0.0552" material="Black" />
<xacro:joint name="hip_joint_right_r" aname="K" parent="hip_right" child="virtual_hip_right" z="-0.030" axis="x" />
<xacro:virtual_link name="virtual_hip_right" w="0.01" h="0.01" d="0.01" z="-0.020" mass="0.0113" />
<xacro:joint name="hip_joint_right_p" aname="L" parent="virtual_hip_right" child="leg_right_1" z="-0.040" axis="y" />
<xacro:link name="leg_right_1" w="0.0325" h="0.032" d="0.043" z="-0.013" mass="0.0742" material="Black" />
<xacro:joint name="hip_joint_right_p" aname="L" parent="hip_right" child="leg_right_1" z="-0.031" axis="y" />
<xacro:link name="leg_right_1" w="0.0325" h="0.032" d="0.043" z="-0.0415" mass="0.06772" material="Black" />
<xacro:joint name="knee_right" aname="M" parent="leg_right_1" child="leg_right_2" z="-0.051" axis="y" />
<xacro:link name="leg_right_2" w="0.0325" h="0.032" d="0.043" z="-0.013" mass="0.0742" material="Black" />
<xacro:joint name="ankle_right_p" aname="N" parent="leg_right_2" child="leg_right_3" z="-0.051" axis="y" />
<xacro:link name="leg_right_3" w="0.0325" h="0.032" d="0.086" z="-0.034" mass="0.135" material="Black" />
<xacro:joint name="ankle_right_r" aname="O" parent="leg_right_3" child="foot_right" z="-0.065" axis="x" />
<xacro:link name="foot_right" w="0.094" h="0.064" d="0.013" z="-0.0275" mass="0.102" material="Orange" />
<xacro:link name="leg_right_2" w="0.0325" h="0.032" d="0.043" z="-0.0385" mass="0.07270" material="Black" />
<xacro:joint name="ankle_right_r" aname="O" parent="leg_right_2" child="foot_right" z="-0.0475" axis="x" />
<xacro:link name="foot_right" w="0.098" h="0.066" d="0.009" z="-0.0245" mass="0.05252" material="Orange" />

<xacro:joint name="ignore_hip_left" aname="ignore_hip_left" parent="hip" child="hip_left" y="0.051" z="-0.004" axis="x" />

<xacro:fixed_joint name="hip_left" parent="base_link" child="hip_left" y="0.04325" z="-0.004" />
<xacro:link name="hip_left" w="0.0325" h="0.032" d="0.043" y="0" z="-0.0215" mass="0.0552" material="Black" />
<xacro:joint name="hip_joint_left_r" aname="Q" parent="hip_left" child="virtual_hip_left" z="-0.030" axis="x" />
<xacro:virtual_link name="virtual_hip_left" w="0.01" h="0.01" d="0.01" z="-0.020" mass="0.0113" />
<xacro:joint name="hip_joint_left_p" aname="R" parent="virtual_hip_left" child="leg_left_1" z="-0.040" axis="y" />
<xacro:link name="leg_left_1" w="0.0325" h="0.032" d="0.043" z="-0.013" mass="0.0742" material="Black" />
<xacro:joint name="knee_left" aname="S" parent="leg_left_1" child="leg_left_2" z="-0.051" axis="y" />
<xacro:link name="leg_left_2" w="0.0325" h="0.032" d="0.043" z="-0.013" mass="0.0742" material="Black" />
<xacro:joint name="ankle_left_p" aname="T" parent="leg_left_2" child="leg_left_3" z="-0.051" axis="y" />
<xacro:link name="leg_left_3" w="0.0325" h="0.032" d="0.086" z="-0.034" mass="0.135" material="Black" />
<xacro:joint name="ankle_left_r" aname="U" parent="leg_left_3" child="foot_left" z="-0.065" axis="x" />
<xacro:link name="foot_left" w="0.094" h="0.064" d="0.013" z="-0.0275" mass="0.102" material="Orange" />


<joint name="dummy_joint" type="fixed">
<parent link="base_link"/>
<child link="hip"/>
</joint>
<xacro:joint name="hip_joint_left_p" aname="L" parent="hip_left" child="leg_left_1" z="-0.031" axis="y" />
<xacro:link name="leg_left_1" w="0.0325" h="0.032" d="0.043" z="-0.0415" mass="0.06772" material="Black" />
<xacro:joint name="knee_left" aname="M" parent="leg_left_1" child="leg_left_2" z="-0.051" axis="y" />
<xacro:link name="leg_left_2" w="0.0325" h="0.032" d="0.043" z="-0.0385" mass="0.07270" material="Black" />
<xacro:joint name="ankle_left_r" aname="O" parent="leg_left_2" child="foot_left" z="-0.0475" axis="x" yaw="${-pi}" />
<xacro:link name="foot_left" w="0.098" h="0.066" d="0.009" z="-0.0245" mass="0.05252" material="Orange" />

<gazebo>
<plugin name="ground_truth" filename="libgazebo_ros_p3d.so">
Expand Down
2 changes: 1 addition & 1 deletion xacro/config/joint.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

<!-- 13.0kgf・cm -->
<!-- 0.16s/60° -->
<xacro:property name="effort" value="13.0" />
<xacro:property name="effort" value="${13.0 / 0.09807}" />
<xacro:property name="velocity" value="${pi / 3 / 0.16}" />

<xacro:property name="hardware_interface" value="hardware_interface/PositionJointInterface" />
Expand Down
8 changes: 8 additions & 0 deletions xacro/joint.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -31,4 +31,12 @@
</transmission>
</xacro:macro>

<xacro:macro name="fixed_joint" params="x:=0 y:=0 z:=0 roll:=0 pitch:=0 yaw:=0 name parent child">
<joint name="ignore_${name}" type="fixed">
<parent link="${parent}"/>
<child link="${child}"/>

<origin xyz="${x} ${y} ${z}" rpy="${roll} ${pitch} ${yaw}" />
</joint>
</xacro:macro>
</robot>

0 comments on commit 2e95e71

Please sign in to comment.