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 gp200r support #452

Merged
Merged
15 changes: 15 additions & 0 deletions motoman_gp200r_support/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
cmake_minimum_required(VERSION 2.8.3)

project(motoman_gp200r_support)

find_package(catkin REQUIRED)

catkin_package()

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

install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
1 change: 1 addition & 0 deletions motoman_gp200r_support/config/joint_names_gp200r.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']
3 changes: 3 additions & 0 deletions motoman_gp200r_support/launch/load_gp200r.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_gp200r_support)/urdf/gp200r.xacro'" />
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<!--
Manipulator specific version of 'robot_interface_streaming.launch'.
Defaults provided for gp200r:
- joints
Usage:
robot_interface_streaming_gp1200r.launch robot_ip:=<value> controller:=<yrc1000>
-->
<launch>
<arg name="robot_ip" />

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

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

<include file="$(find motoman_driver)/launch/robot_interface_streaming_$(arg controller).launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
</include>
</launch>
25 changes: 25 additions & 0 deletions motoman_gp200r_support/launch/robot_state_visualize_gp200r.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<!--
Manipulator specific version of the state visualizer.
Defaults provided for gp200r:
- joints
Usage:
robot_state_visualize_gp200r.launch robot_ip:=<value> controller:=<yrc1000>
-->
<launch>
<arg name="robot_ip" />

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

<rosparam command="load" file="$(find motoman_gp200r_support)/config/joint_names_gp200r.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_gp200r_support)/launch/load_gp200r.launch" />

<node name="rviz" pkg="rviz" type="rviz" args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" required="true" />
</launch>
10 changes: 10 additions & 0 deletions motoman_gp200r_support/launch/test_gp200r.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<launch>
<include file="$(find motoman_gp200r_support)/launch/load_gp200r.launch" />

<param name="use_gui" value="true" />

<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<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.
55 changes: 55 additions & 0 deletions motoman_gp200r_support/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
<?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_gp200r_support</name>
<version>0.1.0</version>
<description>
<p>ROS-Industrial support for the Motoman GP200r (and variants).</p>
<p>
This package contains configuration data, 3D models and launch files
for Motoman GP200r series of manipulators.
</p>
<p>
<b>Specifications</b>
</p>
<ul>
<li>GP200R - Default</li>
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
found in the online documentation files for the robot (GP200R_2D.zip
and GP200R_3D.zip from
https://www.motoman.com/en-us/products/robots/industrial/assembly-handling/gp-series/gp200r)
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>Dylan Rolleigh</author>
<maintainer email="[email protected]">Dylan Rolleigh (Bastian Solutions)</maintainer>
<maintainer email="[email protected]">Akash Jinandra (Bastian Solutions)</maintainer>
<maintainer email="[email protected]">G.A. vd. Hoorn (TU Delft Robotics Institute)</maintainer>
<license>BSD</license>
gavanderhoorn marked this conversation as resolved.
Show resolved Hide resolved

<url type="website">http://wiki.ros.org/motoman_gp200r_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>motoman_driver</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz</exec_depend>
<exec_depend>xacro</exec_depend>

<export>
<architecture_independent/>
</export>
</package>
51 changes: 51 additions & 0 deletions motoman_gp200r_support/test/launch_test.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
<!--
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_gp200r">
<include file="$(find motoman_gp200r_support)/launch/load_gp200r.launch" />
</group>

<group ns="test_gp200r">
<include file="$(find motoman_gp200r_support)/launch/test_gp200r.launch" />
</group>

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

<group ns="robot_state_visualize_gp200r">
<group ns="yrc1000">
<include file="$(find motoman_gp200r_support)/launch/robot_state_visualize_gp200r.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_gp200r_support/urdf/gp200r.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0" ?>
<robot name="motoman_gp200r" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_gp200r_support)/urdf/gp200r_macro.xacro" />
<xacro:motoman_gp200r prefix=""/>
</robot>
172 changes: 172 additions & 0 deletions motoman_gp200r_support/urdf/gp200r_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,172 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="motoman_gp200r" params="prefix">

<!-- Properties -->
<xacro:include filename="$(find motoman_resources)/urdf/common_materials.xacro"/>

<!-- link list -->
<link name="${prefix}base_link">
<visual>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/visual/base_link.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_1_s">
<visual>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/visual/link_1_s.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/collision/link_1_s.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_2_l">
<visual>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/visual/link_2_l.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/collision/link_2_l.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_3_u">
<visual>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/visual/link_3_u.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/collision/link_3_u.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_4_r">
<visual>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/visual/link_4_r.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/collision/link_4_r.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_5_b">
<visual>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/visual/link_5_b.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/collision/link_5_b.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_6_t">
<visual>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/visual/link_6_t.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp200r_support/meshes/gp200r/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(-180)}" upper="${radians(180)}" effort="7060.79" velocity="${radians(90)}"/>
</joint>
<joint name="${prefix}joint_2_l" type="revolute">
<parent link="${prefix}link_1_s"/>
<child link="${prefix}link_2_l"/>
<origin xyz="0.740 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit lower="${radians(-130)}" upper="${radians(80)}" effort="11032.48" velocity="${radians(85)}"/>
</joint>
<joint name="${prefix}joint_3_u" type="revolute">
<parent link="${prefix}link_2_l"/>
<child link="${prefix}link_3_u"/>
<origin xyz="1.150 0 0" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="${radians(-78.4)}" upper="${radians(78)}" effort="9929.23" velocity="${radians(85)}"/>
</joint>
<joint name="${prefix}joint_4_r" type="revolute">
<parent link="${prefix}link_3_u"/>
<child link="${prefix}link_4_r"/>
<origin xyz="0.250 0 0" rpy="0 ${radians(90)} 0" />
<axis xyz="-1 0 0" />
<limit lower="${radians(-180)}" upper="${radians(180)}" effort="2621.3" velocity="${radians(120)}"/>
</joint>
<joint name="${prefix}joint_5_b" type="revolute">
<parent link="${prefix}link_4_r"/>
<child link="${prefix}link_5_b"/>
<origin xyz="1.225 0 0" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="${radians(-125)}" upper="${radians(180)}" effort="3530.38" velocity="${radians(120)}"/>
</joint>
<joint name="${prefix}joint_6_t" type="revolute">
<parent link="${prefix}link_5_b"/>
<child link="${prefix}link_6_t"/>
<origin xyz="0.250 0 0" rpy="0 0 0" />
<axis xyz="1 0 0" />
<limit lower="${radians(-180)}" upper="${radians(180)}" effort="1765.19" velocity="${radians(190)}"/>
</joint>
<!-- end of joint list -->

gavanderhoorn marked this conversation as resolved.
Show resolved Hide resolved
<!-- 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>

<!-- 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 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>

</xacro:macro>
</robot>