Skip to content
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
3 changes: 2 additions & 1 deletion kuka_kr16_support/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@ catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(test/roslaunch_test.xml)
roslaunch_add_file_check(test/roslaunch_test_kr16_2.xml)
roslaunch_add_file_check(test/roslaunch_test_kr16r1610cybertech.xml)
endif()

install(DIRECTORY config launch meshes urdf
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
controller_joint_names: ['joint_a1', 'joint_a2', 'joint_a3', 'joint_a4', 'joint_a5', 'joint_a6']
20 changes: 20 additions & 0 deletions kuka_kr16_support/config/opw_parameters_kr16r1610cybertech.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#
# Parameters for use with IK solvers which support OPW (Ortho-Parallel Wrist)
# kinematic configurations, as described in the paper "An Analytical Solution
# of the Inverse Kinematics Problem of Industrial Serial Manipulators with an
# Ortho-parallel Basis and a Spherical Wrist" by Mathias Brandstötter, Arthur
# Angerer, and Michael Hofbaur (Proceedings of the Austrian Robotics Workshop
# 2014, 22-23 May, 2014, Linz, Austria).
#
# The moveit_opw_kinematics_plugin package provides such a solver.
#
opw_kinematics_geometric_parameters:
a1: 0.260
a2: 0.035
b: 0.000
c1: 0.675
c2: 0.680
c3: 0.670
c4: 0.158
opw_kinematics_joint_offsets: [0.0, -1.57079632679, 0.0, 0.0, 0.0, 0.0]
opw_kinematics_joint_sign_corrections: [-1, 1, 1, -1, 1, -1]
5 changes: 5 additions & 0 deletions kuka_kr16_support/launch/load_kr16r1610cybertech.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0"?>
<launch>
<!-- Load robot description to parameter server -->
<param name="robot_description" command="$(find xacro)/xacro '$(find kuka_kr16_support)/urdf/kr16r1610cybertech.xacro'"/>
</launch>
9 changes: 9 additions & 0 deletions kuka_kr16_support/launch/test_kr16r1610cybertech.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<?xml version="1.0"?>
<launch>
<include file="$(find kuka_kr16_support)/launch/load_kr16r1610cybertech.launch" />
<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.
250 changes: 250 additions & 0 deletions kuka_kr16_support/meshes/kr16r1610cybertech/visual/base_link.dae

Large diffs are not rendered by default.

Loading