Skip to content

Commit

Permalink
kr10r3100
Browse files Browse the repository at this point in the history
  • Loading branch information
Aron Svastits committed Aug 28, 2023
1 parent 6910e29 commit 205ceb3
Show file tree
Hide file tree
Showing 3 changed files with 299 additions and 0 deletions.
58 changes: 58 additions & 0 deletions kuka_quantec_support/launch/test_kr210r3100-2.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
# Copyright 2022 Márton Antal
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from launch import LaunchDescription
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from launch_ros.actions import Node


def generate_launch_description():
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare("kuka_quantec_support"),
"urdf", "kr210_r3100-2.urdf.xacro"]
),
" ",
]
)
robot_description = {'robot_description': robot_description_content}

# RViz
rviz_config_file = PathJoinSubstitution([FindPackageShare(
'kuka_quantec_support'), "config", "quantec_urdf.rviz"])
rviz_node = Node(package='rviz2',
executable='rviz2',
name='rviz2_launch',
output='log',
arguments=['-d', rviz_config_file],
parameters=[robot_description])

# Publish TF
robot_state_publisher = Node(package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='both',
parameters=[robot_description])

# Joint state publisher
joint_state_publisher = Node(package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
output='log')

return LaunchDescription([robot_state_publisher, rviz_node, joint_state_publisher])
19 changes: 19 additions & 0 deletions kuka_quantec_support/urdf/kr210_r3100-2.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="kr210_r3100-2">
<!-- Import urdf file -->
<xacro:include filename="$(find kuka_quantec_support)/urdf/kr210_r3100-2_macro.xacro"/>

<!-- Read parameters from rsi_config -->
<xacro:property name="rsi_config" value="$(find kuka_rsi_hw_interface)/config/rsi_config.yaml" />
<xacro:property name="rsi_config_dict" value="${xacro.load_yaml(rsi_config)}"/>
<xacro:property name="client_ip" value="${rsi_config_dict['client_ip']}" />
<xacro:property name="client_port" value="${rsi_config_dict['client_port']}" />

<!-- Read additional arguments -->
<xacro:arg name="use_fake_hardware" default="false" />

<xacro:kuka_kr210_r3100-2_robot prefix=""
client_ip="${client_ip}"
client_port="${client_port}"
use_fake_hardware="$(arg use_fake_hardware)"/>
</robot>
222 changes: 222 additions & 0 deletions kuka_quantec_support/urdf/kr210_r3100-2_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,222 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find kuka_quantec_support)/urdf/kr_quantec_ros2_control.xacro" />
<xacro:include filename="$(find kuka_quantec_support)/urdf/kr_quantec_transmission.xacro" />

<xacro:macro name="kuka_kr210_r3100-2_robot" params="prefix client_ip client_port use_fake_hardware">
<!-- ros2 control instance -->
<xacro:kuka_quantec_ros2_control
name="kr210_r3100-2"
prefix="${prefix}"
client_ip="${client_ip}"
client_port="${client_port}"
use_fake_hardware="${use_fake_hardware}" />

<link name="${prefix}base_link"/>
<link name="${prefix}base_link_inertia">
<collision>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/collision/base_link.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</collision>
<inertial>
<inertia ixx="31.78631557" ixy="0.0" ixz="0.0" iyy="13.33103186" iyz="0.0" izz="34.18067231"/>
<mass value="2.2596E2"/>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/visual/base_link.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</visual>
</link>
<link name="${prefix}link_1">
<collision>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/collision/link_1.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</collision>
<inertial>
<inertia ixx="6.11156633" ixy="0.0" ixz="0.0" iyy="82.75093024" iyz="0.0" izz="83.25859672"/>
<mass value="3.6737E2"/>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/visual/link_1.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</visual>
</link>
<link name="${prefix}link_2">
<collision>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/collision/link_2.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</collision>
<inertial>
<inertia ixx="3.68215916" ixy="0.0" ixz="0.0" iyy="33.53420017" iyz="0.0" izz="34.55729351"/>
<mass value="2.5056E2"/>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/visual/link_2.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</visual>
</link>
<link name="${prefix}link_3">
<collision>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/collision/link_3.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</collision>
<inertial>
<inertia ixx="0.20114802" ixy="0.0" ixz="0.0" iyy="1.61560245" iyz="0.0" izz="1.64041745"/>
<mass value="2.0653E2"/>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/visual/link_3.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</visual>
</link>
<link name="${prefix}link_4">
<collision>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/collision/link_4.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</collision>
<inertial>
<inertia ixx="0.34306034" ixy="0.0" ixz="0.0" iyy="0.1968928" iyz="0.0" izz="0.34797641"/>
<mass value="4.7942845677E1"/>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/visual/link_4.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</visual>
</link>
<link name="${prefix}link_5">
<collision>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/collision/link_5.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</collision>
<inertial>
<inertia ixx="0.03694113" ixy="0.0" ixz="0.0" iyy="0.03695315" iyz="0.0" izz="0.048251"/>
<mass value="2.3687644624E1"/>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/visual/link_5.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</visual>
</link>
<link name="${prefix}link_6">
<collision>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/collision/link_6.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</collision>
<inertial>
<inertia ixx="0.03694113" ixy="0.0" ixz="0.0" iyy="0.03695315" iyz="0.0" izz="0.048251"/>
<mass value="6.6E0"/>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://kuka_quantec_support/meshes/kr210_r3100-2/visual/link_6.stl"/>
</geometry>
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 0.0 0.0"/>
</visual>
</link>

<joint name="${prefix}base_link-base_link_inertia" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}base_link_inertia" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<joint name="${prefix}joint_a1" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_1"/>
<limit effort="0" lower="-3.2288591161895095E0" upper="3.2288591161895095E0" velocity="5.001E3"/>
<origin rpy="-3.141592653589793 0.0 -0.0" xyz="0.0 0.0 0.0"/>
<parent link="${prefix}base_link_inertia"/>
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_2"/>
<limit effort="0" lower="-2.443460952792061E0" upper="-8.726646259971647E-2" velocity="4.783E3"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.33 0.0 -0.645"/>
<parent link="${prefix}link_1"/>
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_3"/>
<limit effort="0" lower="-2.0943951023931953E0" upper="2.9321531433504737E0" velocity="4.783E3"/>
<origin rpy="0.0 0.0 -1.5707963267948963" xyz="1.35 0.0 0.0"/>
<parent link="${prefix}link_2"/>
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_4"/>
<limit effort="0" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="6.001E3"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.115 0.0 0.0"/>
<parent link="${prefix}link_3"/>
</joint>
<joint name="${prefix}joint_a5" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_5"/>
<limit effort="0" lower="-2.138028333693054E0" upper="2.138028333693054E0" velocity="6.001E3"/>
<origin rpy="-1.5707963267948963 0.0 -0.0" xyz="0.0 0.0 -1.42"/>
<parent link="${prefix}link_4"/>
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<axis xyz="0.0 0.0 1.0"/>
<child link="${prefix}link_6"/>
<limit effort="0" lower="-6.1086523819801535E0" upper="6.1086523819801535E0" velocity="6.001E3"/>
<origin rpy="1.5707963267948963 0.0 -0.0" xyz="0.0 0.0 0.0"/>
<parent link="${prefix}link_5"/>
</joint>

<!-- ROS-Industrial 'base' frame - equivalent of 'KUKA ROBROOT'-->
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>

<!-- ROS-Industrial 'flange' frame - attachment point for EEF models -->
<link name="${prefix}flange" />
<joint name="${prefix}link6-flange" type="fixed">
<child link="${prefix}flange" />
<origin rpy="0 ${pi} -0.0" xyz="0.0 0.0 -0.153" />
<parent link="${prefix}link_6" />
</joint>

<!-- ROS-Industrial 'tool0' frame - all-zeros tool frame -->
<link name="${prefix}tool0" />
<joint name="${prefix}link6-tool0" type="fixed">
<child link="${prefix}tool0" />
<origin rpy="0 ${pi} -0.0" xyz="0.0 0.0 -0.153" />
<parent link="${prefix}link_6" />
</joint>
</xacro:macro>
</robot>

0 comments on commit 205ceb3

Please sign in to comment.