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

Add GP20HL Support Package #566

Open
wants to merge 1 commit 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
15 changes: 15 additions & 0 deletions motoman_gp20_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_gp20_support)

find_package(catkin REQUIRED)

catkin_package()

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

install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
1 change: 1 addition & 0 deletions motoman_gp20_support/config/joint_names_gp20_hl.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']
4 changes: 4 additions & 0 deletions motoman_gp20_support/launch/load_gp20_hl.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<?xml version="1.0" ?>
<launch>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find motoman_gp20_support)/urdf/gp20_hl.xacro'" />
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0" ?>
<!--
Manipulator specific version of 'robot_interface_streaming.launch'.

Defaults provided for gp20_hl:
- 6 joints

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

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

<rosparam command="load" file="$(find motoman_gp20_support)/config/joint_names_gp20_hl.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_gp20_support/launch/robot_state_visualize_gp20_hl.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0" ?>
<!--
Manipulator specific version of the state visualizer.

Defaults provided for gp20_hl:
- 6 joints

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

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

<rosparam command="load" file="$(find motoman_gp20_support)/config/joint_names_gp20_hl.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_gp20_support)/launch/load_gp20_hl.launch" />

<node name="rviz" pkg="rviz" type="rviz" args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" required="true" />
</launch>
9 changes: 9 additions & 0 deletions motoman_gp20_support/launch/test_gp20_hl.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<?xml version="1.0" ?>
<launch>
<include file="$(find motoman_gp20_support)/launch/load_gp20_hl.launch" />

<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.
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.
58 changes: 58 additions & 0 deletions motoman_gp20_support/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
<?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_gp20_support</name>
<version>0.1.0</version>
<description>
<p>ROS-Industrial support for the Motoman GP20 (and variants).</p>
<p>
This package contains configuration data, 3D models and launch files
for Motoman GP20 manipulators.
</p>
<p>
<b>Specifications</b>
</p>
<ul>
<li>GP20 - Default</li>
<li>GP20HL - Hollow, Long Arm</li>
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
found in the online
https://www.motoman.com/hubfs/Robots/gp20.pdf
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>A.C. Buynak</author>
<maintainer email="buynak.9@osu.edu">A.C. Buynak (The Ohio State University)</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_gp20_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</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>

<exec_depend>motoman_driver</exec_depend>
<exec_depend>motoman_resources</exec_depend>

<exec_depend>rviz</exec_depend>
<exec_depend>xacro</exec_depend>

<export>
<architecture_independent/>
</export>
</package>
59 changes: 59 additions & 0 deletions motoman_gp20_support/test/launch_test_gp20_hl.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@

<!--
launch_test.xml - ROSlaunch tests

Usage Instructions:

1. Add the following to your CMakeLists.txt:

find_package(roslaunch)
roslaunch_add_file_check(test/launch_test.xml)

2. Create a test directory under your package
3. Add the "launch_text.xml" file and fill out the test below. Use the
following conventions:
a. Encapsulate each launch file test in it's own namespace. By
convention the namespace should have the same name as the launch
file (minus ".launch" extension)
b. Create tests for each possible combination of parameters. Utilize
sub-namespaces under the main namespace.

Notes:

1. XML extension is used in order to avoid beinging included
in roslaunch auto-complete.

2. Group tags with namespaces are used to avoid node name collisions when
testing multpile launch files
-->
<launch>
<arg name="req_arg" value="default"/>
<arg name="yrc1000" value="yrc1000"/>

<group ns="load_gp20_hl">
<include file="$(find motoman_gp20_support)/launch/load_gp20_hl.launch"/>
</group>

<group ns="test_gp20_hl">
<include file="$(find motoman_gp20_support)/launch/test_gp20_hl.launch"/>
</group>

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

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

</launch>
6 changes: 6 additions & 0 deletions motoman_gp20_support/urdf/gp20_hl.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0" ?>

<robot name="motoman_gp20_hl" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_gp20_support)/urdf/gp20_hl_macro.xacro" />
<xacro:motoman_gp20_hl prefix=""/>
</robot>
173 changes: 173 additions & 0 deletions motoman_gp20_support/urdf/gp20_hl_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,173 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="motoman_gp20_hl" 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_gp20_support/meshes/gp20_hl/visual/base_link.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_1_s">
<visual>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/visual/link_1_s.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/collision/link_1_s.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_2_l">
<visual>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/visual/link_2_l.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/collision/link_2_l.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_3_u">
<visual>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/visual/link_3_u.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/collision/link_3_u.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_4_r">
<visual>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/visual/link_4_r.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/collision/link_4_r.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_5_b">
<visual>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/visual/link_5_b.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/collision/link_5_b.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_6_t">
<visual>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/visual/link_6_t.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp20_support/meshes/gp20_hl/collision/link_6_t.stl"/>
</geometry>
</collision>
</link>
<!-- end of link list -->

<!-- joint list -->
<!-- Joints are specified such that the driver rotates the joints about the positive Z axis. -->
<joint name="${prefix}joint_1_s" type="revolute">
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1_s"/>
<origin xyz="0 0 0.540" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit lower="-${radians(180)}" upper="${radians(180)}" effort="212.66" velocity="${radians(125)}"/>
</joint>
<joint name="${prefix}joint_2_l" type="revolute">
<parent link="${prefix}link_1_s"/>
<child link="${prefix}link_2_l"/>
<origin xyz="0.145 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit lower="-${radians(90)}" upper="${radians(135)}" effort="205.80" velocity="${radians(115)}"/>
</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 1.150" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="-${radians(80)}" upper="${radians(206)}" effort="106.82" velocity="${radians(125)}"/>
</joint>
<joint name="${prefix}joint_4_r" type="revolute">
<parent link="${prefix}link_3_u"/>
<child link="${prefix}link_4_r"/>
<origin xyz="0 0 0.250" rpy="0 0 0" />
<axis xyz="-1 0 0" />
<limit lower="-${radians(200)}" upper="${radians(200)}" effort="55.86" velocity="${radians(182)}"/>
</joint>
<joint name="${prefix}joint_5_b" type="revolute">
<parent link="${prefix}link_4_r"/>
<child link="${prefix}link_5_b"/>
<origin xyz="1.812 0 0" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="-${radians(150)}" upper="${radians(150)}" effort="32.68" velocity="${radians(175)}"/>
</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(455)}" upper="${radians(455)}" effort="22.54" velocity="${radians(265)}"/>
</joint>
<!-- end of joint list -->

<!-- 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.540" 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}joint_6_t-flange" type="fixed">
<origin xyz="0.100 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="${pi} ${-pi/2.0} 0"/>
<parent link="${prefix}flange"/>
<child link="${prefix}tool0"/>
</joint>

</xacro:macro>

</robot>