Skip to content

Commit

Permalink
Added gp180 support.
Browse files Browse the repository at this point in the history
  • Loading branch information
Alec Tiefenthal committed Mar 5, 2021
1 parent 3056cde commit 7d08b75
Show file tree
Hide file tree
Showing 15 changed files with 295 additions and 1 deletion.
3 changes: 2 additions & 1 deletion motoman_gp180_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/launch_test.xml)
roslaunch_add_file_check(test/launch_test_gp180.xml)
roslaunch_add_file_check(test/launch_test_gp180_120.xml)
endif()

install(DIRECTORY config launch meshes urdf
Expand Down
1 change: 1 addition & 0 deletions motoman_gp180_support/config/joint_names_gp180.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_gp180_support/launch/load_gp180.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_gp180_support)/urdf/gp180.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 gp180:
- joints
Usage:
robot_interface_streaming_gp180_120.launch robot_ip:=<value> controller:=<yrc1000>
-->
<launch>
<arg name="robot_ip" />

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

<rosparam command="load" file="$(find motoman_gp180_support)/config/joint_names_gp180.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_gp180_support/launch/robot_state_visualize_gp180.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 gp180:
- joints
Usage:
robot_state_visualize_gp180.launch robot_ip:=<value> controller:=<yrc1000>
-->
<launch>
<arg name="robot_ip" />

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

<rosparam command="load" file="$(find motoman_gp180_support)/config/joint_names_gp180.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_gp180_support)/launch/load_gp180.launch" />

<node name="rviz" pkg="rviz" type="rviz" args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" required="true" />
</launch>
8 changes: 8 additions & 0 deletions motoman_gp180_support/launch/test_gp180.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<launch>
<include file="$(find motoman_gp180_support)/launch/load_gp180.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.
1 change: 1 addition & 0 deletions motoman_gp180_support/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
<test_depend>roslaunch</test_depend>

<exec_depend>joint_state_publisher</exec_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>
Expand Down
51 changes: 51 additions & 0 deletions motoman_gp180_support/test/launch_test_gp180.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_gp180">
<include file="$(find motoman_gp180_support)/launch/load_gp180.launch" />
</group>

<group ns="test_gp180">
<include file="$(find motoman_gp180_support)/launch/test_gp180.launch" />
</group>

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

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

</launch>
File renamed without changes.
5 changes: 5 additions & 0 deletions motoman_gp180_support/urdf/gp180.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0" ?>
<robot name="motoman_gp180" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_gp180_support)/urdf/gp180_macro.xacro" />
<xacro:motoman_gp180 prefix=""/>
</robot>
180 changes: 180 additions & 0 deletions motoman_gp180_support/urdf/gp180_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,180 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="motoman_gp180" 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_gp180_support/meshes/gp180_120/visual/base_link.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_1_s">
<visual>
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/visual/link_1_s.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/collision/link_1_s.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_2_l">
<visual>
<origin rpy="${radians(90)} ${radians(0)} ${radians(90)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/visual/link_2_l.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<origin rpy="${radians(90)} ${radians(0)} ${radians(90)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/collision/link_2_l.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_3_u">
<visual>
<origin rpy="${radians(-90)} ${radians(0)} ${radians(-90)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180/visual/link_3_u.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<origin rpy="${radians(-90)} ${radians(0)} ${radians(-90)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180/collision/link_3_u.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_4_r">
<visual>
<origin rpy="${radians(0)} ${radians(90)} ${radians(0)}" xyz="0 0 1.225"/>
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180/visual/link_4_r.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<origin rpy="${radians(0)} ${radians(90)} ${radians(0)}" xyz="0 0 1.225"/>
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180/collision/link_4_r.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_5_b">
<visual>
<origin rpy="${radians(-90)} ${radians(0)} ${radians(-90)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/visual/link_5_b.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<origin rpy="${radians(-90)} ${radians(0)} ${radians(-90)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/collision/link_5_b.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_6_t">
<visual>
<origin rpy="${radians(0)} ${radians(90)} ${radians(0)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/visual/link_6_t.stl"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<origin rpy="${radians(0)} ${radians(90)} ${radians(0)}" />
<geometry>
<mesh filename="package://motoman_gp180_support/meshes/gp180_120/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.650" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit lower="${radians(-180)}" upper="${radians(180)}" effort="8237.59" 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.325 0 0" rpy="0 ${radians(-90)} ${radians(-90)}" />
<axis xyz="0 0 1" />
<limit lower="${radians(-60)}" upper="${radians(76)}" effort="10419.57" 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="1.150 0 0" rpy="${radians(180)} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${radians(-86)}" upper="${radians(90)}" effort="7453.05" 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.300 -1.225 0" rpy="${radians(-90)} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${radians(-360)}" upper="${radians(360)}" effort="1671.05" 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="0 0 0" rpy="${radians(90)} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${radians(-130)}" upper="${radians(130)}" effort="1081.18" 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.225 0" rpy="${radians(-90)} 0 0" />
<axis xyz="0 0 1" />
<limit lower="${radians(-360)}" upper="${radians(360)}" effort="926.73" 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.650" 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 ${radians(90)} 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>

0 comments on commit 7d08b75

Please sign in to comment.