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

Fix for issue #4: misc cleanup of KR 210 L150 support pkg #25

Merged
Merged
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
5 changes: 3 additions & 2 deletions kuka_kr210_support/launch/test_kr210l150.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
<launch>
<include file="$(find kuka_kr210_support)/launch/load_kr210l150.launch" />
<param name="use_gui" value="true" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="true" />
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" required="true" />
</launch>
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
6 changes: 4 additions & 2 deletions kuka_kr210_support/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,7 @@
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
found in the online
http://www.kuka-robotics.com/res/sps/e6c77545-9030-49b1-93f5-4d17c92173aa_Spez_KR_QUANTEC_extra_en.pdf
found in the online <a href="http://www.kuka-robotics.com/res/sps/e6c77545-9030-49b1-93f5-4d17c92173aa_Spez_KR_QUANTEC_extra_en.pdf">datasheet</a>.
All urdfs are based on the default motion and joint velocity limits,
unless noted otherwise.
</p>
Expand All @@ -26,6 +25,9 @@
in this package, be sure to check they are correct for the particular
robot model and configuration you intend to use them with.
</p>
<p>
<b>NB</b>: this package currently uses non-valid inertia parameters.
</p>
</description>
<author>Shaun Edwards</author>
<maintainer email="shaun.edwards@gmail.com">Shaun Edwards</maintainer>
Expand Down
80 changes: 43 additions & 37 deletions kuka_kr210_support/urdf/kr210l150.urdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/ros/ros/catkin_ws/src/kuka_experimental/kuka_kr210_support/urdf/kr210l150.xacro | -->
<!-- | This document was autogenerated by xacro from kr210l150.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!--Generates a urdf from the macro in kr210_macro.xacro -->
Expand Down Expand Up @@ -49,13 +49,6 @@
</geometry>
</collision>
</link>
<joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="-0.00262 0.00097586 0.33099"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit effort="0" lower="-3.228859205" upper="3.228859205" velocity="2.146755039"/>
</joint>
<link name="link_2">
<inertial>
<origin rpy="0 0 0" xyz="0.016923 -0.19196 0.44751"/>
Expand All @@ -78,13 +71,6 @@
</geometry>
</collision>
</link>
<joint name="joint_2" type="revolute">
<origin rpy="0 0 0" xyz="0.35277 -0.037476 0.4192"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-0.785398185" upper="1.483529905" velocity="2.007128695"/>
</joint>
<link name="link_3">
<inertial>
<origin rpy="0 0 0" xyz="0.18842 0.18344 -0.042799"/>
Expand All @@ -107,13 +93,6 @@
</geometry>
</collision>
</link>
<joint name="joint_3" type="revolute">
<origin rpy="0 0 0" xyz="-9.8483E-05 -0.1475 1.2499"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-3.66519153" upper="1.134464045" velocity="1.954768816"/>
</joint>
<link name="link_4">
<inertial>
<origin rpy="0 0 0" xyz="0.27146 -0.007326 5.2775E-05"/>
Expand All @@ -136,13 +115,6 @@
</geometry>
</collision>
</link>
<joint name="joint_4" type="revolute">
<origin rpy="0 0 0" xyz="0.95795 0.184 -0.055059"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="1 0 0"/>
<limit effort="0" lower="-6.10865255" upper="6.10865255" velocity="3.124139447"/>
</joint>
<link name="link_5">
<inertial>
<origin rpy="0 0 0" xyz="0.04379 0.025984 3.5491E-07"/>
Expand All @@ -165,13 +137,6 @@
</geometry>
</collision>
</link>
<joint name="joint_5" type="revolute">
<origin rpy="0 0 0" xyz="0.542 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.181661625" upper="2.181661625" velocity="3.001966396"/>
</joint>
<link name="link_6">
<inertial>
<origin rpy="0 0 0" xyz="-0.017956 -1.5237E-05 0.00015484"/>
Expand All @@ -194,18 +159,59 @@
</geometry>
</collision>
</link>
<link name="tool0"/>
<joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="-0.00262 0.00097586 0.33099"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit effort="0" lower="-3.228859205" upper="3.228859205" velocity="2.146755039"/>
</joint>
<joint name="joint_2" type="revolute">
<origin rpy="0 0 0" xyz="0.35277 -0.037476 0.4192"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-0.785398185" upper="1.483529905" velocity="2.007128695"/>
</joint>
<joint name="joint_3" type="revolute">
<origin rpy="0 0 0" xyz="-9.8483E-05 -0.1475 1.2499"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-3.66519153" upper="1.134464045" velocity="1.954768816"/>
</joint>
<joint name="joint_4" type="revolute">
<origin rpy="0 0 0" xyz="0.95795 0.184 -0.055059"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="1 0 0"/>
<limit effort="0" lower="-6.10865255" upper="6.10865255" velocity="3.124139447"/>
</joint>
<joint name="joint_5" type="revolute">
<origin rpy="0 0 0" xyz="0.542 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.181661625" upper="2.181661625" velocity="3.001966396"/>
</joint>
<joint name="joint_6" type="revolute">
<origin rpy="0 0 0" xyz="0.1925 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="1 0 0"/>
<limit effort="0" lower="-6.10865255" upper="6.10865255" velocity="3.822271167"/>
</joint>
<link name="tool0"/>
<joint name="link_6-tool0" type="fixed">
<parent link="link_6"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="0.0375 0 -0.00023924"/>
</joint>
<link name="Link1"/>
<joint name="Link1-link_1" type="fixed">
<parent link="link_1"/>
<child link="Link1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
</robot>

8 changes: 2 additions & 6 deletions kuka_kr210_support/urdf/kr210l150.xacro
Original file line number Diff line number Diff line change
@@ -1,9 +1,5 @@
<?xml version="1.0" ?>

<!--Generates a urdf from the macro in kr210_macro.xacro -->

<robot name="kuka_kr210" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find kuka_kr210_support)/urdf/kr210l150_macro.xacro"/>
<xacro:kuka_kr210l150 prefix=""/>
<xacro:include filename="$(find kuka_kr210_support)/urdf/kr210l150_macro.xacro"/>
<xacro:kuka_kr210l150 prefix=""/>
</robot>

Loading