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

Update joint_names_irb5400.yaml #198

Open
wants to merge 2 commits 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
16 changes: 8 additions & 8 deletions abb_irb5400_support/urdf/irb5400.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -171,50 +171,50 @@
<link name="tool0"/>
<!-- end of link list -->
<!-- joint list -->
<joint name="joint1" type="revolute">
<joint name="joint_1" type="revolute">
<parent link="base_link"/>
<child link="link_1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="100" lower="-2.617" upper="2.617" velocity="2.3911"/>
</joint>
<joint name="joint2" type="revolute">
<joint name="joint_2" type="revolute">
<parent link="link_1"/>
<child link="link_2"/>
<origin rpy="0 0 0" xyz="0.300 0 0.660"/>
<axis xyz="0 1 0"/>
<limit effort="100" lower="-1.396" upper="1.396" velocity="2.3911"/>
</joint>
<joint name="joint3" type="revolute">
<joint name="joint_3" type="revolute">
<parent link="link_2"/>
<child link="link_3"/>
<origin rpy="0 0 0" xyz="0 0 1.200"/>
<axis xyz="0 1 0"/>
<limit effort="100" lower="-1.308" upper="1.308" velocity="2.3911"/>
</joint>
<joint name="joint4" type="revolute">
<joint name="joint_4" type="revolute">
<parent link="link_3"/>
<child link="link_4"/>
<origin rpy="0 0 0" xyz="1.339 0 0.186"/>
<axis xyz="1 0 0"/>
<limit effort="100" lower="-6.0" upper="6.0" velocity="8.1157"/>
</joint>
<joint name="joint5" type="revolute">
<joint name="joint_5" type="revolute">
<parent link="link_4"/>
<child link="link_5"/>
<origin rpy="0 0.6109 0" xyz="0.0693 0 0"/>
<axis xyz="1 0 0"/>
<limit effort="100" lower="-6.0" upper="6.0" velocity="6.1086"/>
</joint>
<joint name="joint5b" type="revolute">
<joint name="joint_5b" type="revolute">
<parent link="link_5"/>
<child link="link_5b"/>
<origin rpy="0 -1.2217 0" xyz=".106246 0 0.074394"/>
<axis xyz="1 0 0"/>
<limit effort="100" lower="-6.0" upper="6.0" velocity="6.1086"/>
<mimic joint="joint5" multiplier="-1.0" offset="0"/>
<mimic joint="joint_5" multiplier="-1.0" offset="0"/>
</joint>
<joint name="joint6" type="revolute">
<joint name="joint_6" type="revolute">
<parent link="link_5b"/>
<child link="link_6"/>
<origin rpy="0 0.6109 0" xyz="0.0672 0 -0.0470"/>
Expand Down
16 changes: 8 additions & 8 deletions abb_irb5400_support/urdf/irb5400_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -120,50 +120,50 @@
<!-- end of link list -->

<!-- joint list -->
<joint name="${prefix}joint1" type="revolute">
<joint name="${prefix}joint_1" type="revolute">
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-2.617" upper="2.617" effort="100" velocity="2.3911"/>
</joint>
<joint name="${prefix}joint2" type="revolute">
<joint name="${prefix}joint_2" type="revolute">
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<origin xyz="0.300 0 0.660" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="-1.396" upper="1.396" effort="100" velocity="2.3911"/>
</joint>
<joint name="${prefix}joint3" type="revolute">
<joint name="${prefix}joint_3" type="revolute">
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<origin xyz="0 0 1.200" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="-1.308" upper="1.308" effort="100" velocity="2.3911"/>
</joint>
<joint name="${prefix}joint4" type="revolute">
<joint name="${prefix}joint_4" type="revolute">
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<origin xyz="1.339 0 0.186" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
<limit lower="-6.0" upper="6.0" effort="100" velocity="8.1157"/>
</joint>
<joint name="${prefix}joint5" type="revolute">
<joint name="${prefix}joint_5" type="revolute">
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<origin xyz="0.0693 0 0" rpy="0 0.6109 0"/>
<axis xyz="1 0 0"/>
<limit lower="-6.0" upper="6.0" effort="100" velocity="6.1086"/>
</joint>
<joint name="${prefix}joint5b" type="revolute">
<joint name="${prefix}joint_5b" type="revolute">
<parent link="${prefix}link_5"/>
<child link="${prefix}link_5b"/>
<origin xyz=".106246 0 0.074394" rpy="0 -1.2217 0"/>
<axis xyz="1 0 0"/>
<limit lower="-6.0" upper="6.0" effort="100" velocity="6.1086"/>
<mimic joint="joint5" multiplier="-1.0" offset="0"/>
<mimic joint="joint_5" multiplier="-1.0" offset="0"/>
</joint>
<joint name="${prefix}joint6" type="revolute">
<joint name="${prefix}joint_6" type="revolute">
<parent link="${prefix}link_5b"/>
<child link="${prefix}link_6"/>
<origin xyz="0.0672 0 -0.0470" rpy="0 0.6109 0"/>
Expand Down