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

GP8L robot support package #606

Open
wants to merge 3 commits into
base: kinetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
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
15 changes: 15 additions & 0 deletions motoman_gp8l_support/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
cmake_minimum_required(VERSION 3.0.2)

project(motoman_gp8l_support)

find_package(catkin REQUIRED)

catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(test/roslaunch_test_gp8l.xml)
endif()

install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
1 change: 1 addition & 0 deletions motoman_gp8l_support/config/joint_names_gp8l.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
controller_joint_names: ['joint_1_s', 'joint_2_l', 'joint_3_u', 'joint_4_r', 'joint_5_b', 'joint_6_t']
20 changes: 20 additions & 0 deletions motoman_gp8l_support/config/opw_parameters_gp8l.yaml
gavanderhoorn marked this conversation as resolved.
Show resolved Hide resolved
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.155
a2: -0.200
b: 0.000
c1: 0.450
c2: 0.714
c3: 0.740
c4: 0.080
opw_kinematics_joint_offsets: [0.0, 0.0, deg(-90.0), 0.0, 0.0, deg(180.0)]
opw_kinematics_joint_sign_corrections: [1, 1, -1, -1, -1, -1]
3 changes: 3 additions & 0 deletions motoman_gp8l_support/launch/load_gp8l.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find motoman_gp8l_support)/urdf/gp8l.xacro'" />
</launch>
21 changes: 21 additions & 0 deletions motoman_gp8l_support/launch/robot_interface_streaming_gp8l.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<!--
Manipulator specific version of 'robot_interface_streaming.launch'.

Defaults provided for GP8L:
- 7 joints

Usage:
robot_interface_streaming_gp8l.launch robot_ip:=<value> controller:=<yrc1000>
-->
<launch>
<arg name="robot_ip" />

<!-- controller: Controller name (yrc1000) -->
<arg name="controller"/>

<rosparam command="load" file="$(find motoman_gp8l_support)/config/joint_names_gp8l.yaml" />

<include file="$(find motoman_driver)/launch/robot_interface_streaming_$(arg controller).launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
</include>
</launch>
28 changes: 28 additions & 0 deletions motoman_gp8l_support/launch/robot_state_visualize_gp8l.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<!--
Manipulator specific version of the state visualizer.

Defaults provided for GP8L:
- 7 joints

Usage:
robot_state_visualize_gp8l.launch robot_ip:=<value> controller:=<yrc1000>
-->
<launch>
<arg name="robot_ip" />

<!-- controller: Controller name (yrc1000) -->
<arg name="controller" />

<rosparam command="load" file="$(find motoman_gp8l_support)/config/joint_names_gp8l.yaml" />

<include file="$(find motoman_driver)/launch/robot_state_$(arg controller).launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
</include>

<node name="robot_state_publisher" pkg="robot_state_publisher"
type="robot_state_publisher" />

<include file="$(find motoman_gp8l_support)/launch/load_gp8l.launch" />

<node name="rviz" pkg="rviz" type="rviz" args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" required="true" />
</launch>
7 changes: 7 additions & 0 deletions motoman_gp8l_support/launch/test_gp8l.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<include file="$(find motoman_gp8l_support)/launch/load_gp8l.launch" />
<param name="use_gui" value="true" />
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />
<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.
89 changes: 89 additions & 0 deletions motoman_gp8l_support/meshes/gp8l/visual/base_link.dae

Large diffs are not rendered by default.

141 changes: 141 additions & 0 deletions motoman_gp8l_support/meshes/gp8l/visual/link_1_s.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions motoman_gp8l_support/meshes/gp8l/visual/link_2_l.dae

Large diffs are not rendered by default.

141 changes: 141 additions & 0 deletions motoman_gp8l_support/meshes/gp8l/visual/link_3_u.dae

Large diffs are not rendered by default.

213 changes: 213 additions & 0 deletions motoman_gp8l_support/meshes/gp8l/visual/link_4_r.dae

Large diffs are not rendered by default.

89 changes: 89 additions & 0 deletions motoman_gp8l_support/meshes/gp8l/visual/link_5_b.dae

Large diffs are not rendered by default.

89 changes: 89 additions & 0 deletions motoman_gp8l_support/meshes/gp8l/visual/link_6_t.dae

Large diffs are not rendered by default.

56 changes: 56 additions & 0 deletions motoman_gp8l_support/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>motoman_gp8l_support</name>
<version>0.1.0</version>
<description>
<p>ROS-Industrial support for the Motoman GP8L.</p>
<p>
This package contains configuration data, 3D models and launch files
for Motoman GP8L manipulators.
</p>
<p>
<b>Specifications</b>
</p>
<ul>
<li>GP8L - Default</li>
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
found in the <em>YASKAWA MOTOMAN-GP8L INSTRUCTIONS (HW1486242)</em>
version <em>194163-1CD, rev 2</em>
</p>
<p>
All urdfs are based on the default motion and joint velocity limits,
unless noted otherwise.
</p>
<p>
Before using any of the configuration files and / or meshes included
in this package, be sure to check they are correct for the particular
robot model and configuration you intend to use them with.
</p>
</description>
<author>Eric Marcil</author>
<maintainer email="eric.marcil@motoman.com">Eric Marcil</maintainer>
<maintainer email="g.a.vanderhoorn@tudelft.nl">G.A. vd. Hoorn (TU Delft Robotics Institute)</maintainer>
<license>BSD</license>

<url type="website">http://wiki.ros.org/motoman_gp8l_support</url>
<url type="bugtracker">https://github.com/ros-industrial/motoman/issues</url>
<url type="repository">https://github.com/ros-industrial/motoman</url>

<buildtool_depend>catkin</buildtool_depend>

<test_depend>roslaunch</test_depend>

<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>motoman_driver</exec_depend>
<exec_depend>motoman_resources</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz</exec_depend>
<exec_depend>xacro</exec_depend>

<export>
<architecture_independent/>
</export>
</package>
30 changes: 30 additions & 0 deletions motoman_gp8l_support/test/roslaunch_test_gp8l.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
<launch>
<arg name="req_arg" value="default"/>
<arg name="yrc1000" value="yrc1000"/>

<group ns="load_gp8l">
<include file="$(find motoman_gp8l_support)/launch/load_gp8l.launch"/>
</group>

<group ns="test_gp8l">
<include file="$(find motoman_gp8l_support)/launch/test_gp8l.launch"/>
</group>

<group ns="robot_interface_streaming_gp8l">
<group ns="yrc1000" >
<include file="$(find motoman_gp8l_support)/launch/robot_interface_streaming_gp8l.launch">
<arg name="robot_ip" value="$(arg req_arg)" />
<arg name="controller" value="$(arg yrc1000)"/>
</include>
</group>
</group>

<group ns="robot_state_visualize_gp8l">
<group ns="yrc1000" >
<include file="$(find motoman_gp8l_support)/launch/robot_state_visualize_gp8l.launch">
<arg name="robot_ip" value="$(arg req_arg)" />
<arg name="controller" value="$(arg yrc1000)"/>
</include>
</group>
</group>
</launch>
5 changes: 5 additions & 0 deletions motoman_gp8l_support/urdf/gp8l.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0" ?>
<robot name="motoman_gp8l" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_gp8l_support)/urdf/gp8l_macro.xacro" />
<xacro:motoman_gp8l prefix=""/>
</robot>
169 changes: 169 additions & 0 deletions motoman_gp8l_support/urdf/gp8l_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,169 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="motoman_gp8l" params="prefix">
<xacro:include filename="$(find motoman_resources)/urdf/common_materials.xacro"/>

<!-- link list -->
<link name="${prefix}base_link">
<visual>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/visual/base_link.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_1_s">
<visual>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/visual/link_1_s.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/collision/link_1_s.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_2_l">
<visual>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/visual/link_2_l.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/collision/link_2_l.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_3_u">
<visual>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/visual/link_3_u.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/collision/link_3_u.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_4_r">
<visual>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/visual/link_4_r.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/collision/link_4_r.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_5_b">
<visual>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/visual/link_5_b.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/collision/link_5_b.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_6_t">
<visual>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/visual/link_6_t.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp8l_support/meshes/gp8l/collision/link_6_t.stl"/>
</geometry>
</collision>
</link>
<!-- end of link list -->

<!-- joint list -->
<joint name="${prefix}joint_1_s" type="revolute">
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1_s"/>
<origin xyz="0 0 0.450" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit lower="${radians(-170)}" upper="${radians(170)}" effort="926.1" velocity="${radians(260)}"/>
</joint>
<joint name="${prefix}joint_2_l" type="revolute">
<parent link="${prefix}link_1_s"/>
<child link="${prefix}link_2_l"/>
<origin xyz="0.155 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit lower="${radians(-90)}" upper="${radians(155)}" effort="1029" velocity="${radians(230)}"/>
</joint>
<joint name="${prefix}joint_3_u" type="revolute">
<parent link="${prefix}link_2_l"/>
<child link="${prefix}link_3_u"/>
<origin xyz="0 0 0.714" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="${radians(-85)}" upper="${radians(150)}" effort="551.2" velocity="${radians(260)}"/>
</joint>
<joint name="${prefix}joint_4_r" type="revolute">
<parent link="${prefix}link_3_u"/>
<child link="${prefix}link_4_r"/>
<origin xyz="0.740 0 0.200" rpy="0 0 0" />
<axis xyz="-1 0 0" />
<limit lower="${radians(-200)}" upper="${radians(200)}" effort="89.96" velocity="${radians(470)}"/>
</joint>
<joint name="${prefix}joint_5_b" type="revolute">
<parent link="${prefix}link_4_r"/>
<child link="${prefix}link_5_b"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="${radians(-135)}" upper="${radians(135)}" effort="32.68" velocity="${radians(550)}"/>
</joint>
<joint name="${prefix}joint_6_t" type="revolute">
<parent link="${prefix}link_5_b"/>
<child link="${prefix}link_6_t"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="-1 0 0" />
<limit lower="${radians(-360)}" upper="${radians(360)}" effort="22.54" velocity="${radians(1000)}"/>
</joint>
<!-- end of joint list -->

<!-- ROS-Industrial 'flange' frame: attachment point for EEF models -->
<link name="${prefix}flange"/>
<joint name="${prefix}joint_6_t-flange" type="fixed">
<origin xyz="0.080 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_6_t"/>
<child link="${prefix}flange"/>
</joint>

<!-- ROS-Industrial 'tool0' frame: all-zeros tool frame -->
<link name="${prefix}tool0"/>
<joint name="${prefix}flange-tool0" type="fixed">
<origin xyz="0 0 0" rpy="${radians(180)} ${radians(-90)} 0"/>
<parent link="${prefix}flange"/>
<child link="${prefix}tool0"/>
</joint>

<!-- ROS base_link to Robot Manufacturer World Coordinates transform -->
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<origin xyz="0 0 0.450" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>
</xacro:macro>
</robot>