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 support for MH80 #52

Open
wants to merge 13 commits into
base: kinetic-devel
Choose a base branch
from
1 change: 1 addition & 0 deletions motoman_mh_support/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ catkin_package()
if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(test/roslaunch_test_mh180_120.xml)
roslaunch_add_file_check(test/roslaunch_test_mh80.xml)
endif()

install(DIRECTORY config launch meshes urdf
Expand Down
1 change: 1 addition & 0 deletions motoman_mh_support/config/joint_names_mh80.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
controller_joint_names: ['joint_s', 'joint_l', 'joint_u', 'joint_r', 'joint_b', 'joint_t']
4 changes: 4 additions & 0 deletions motoman_mh_support/launch/load_mh80.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.py '$(find motoman_mh_support)/urdf/mh80.xacro'" />
</launch>
22 changes: 22 additions & 0 deletions motoman_mh_support/launch/robot_interface_streaming_mh80.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 MH80:
- 6 joints

Usage:
robot_interface_streaming_mh80.launch robot_ip:=<value> controller:=<dx200>
-->
<launch>
<arg name="robot_ip" />

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

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

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

Defaults provided for MH80:
- 6 joints

Usage:
robot_state_visualize_mh80.launch robot_ip:=<value> controller:=<dx200>
-->
<launch>
<arg name="robot_ip" />
<arg name="controller" /> <!-- controller: Controller name (dx200) -->

<rosparam command="load" file="$(find motoman_mh_support)/config/joint_names_mh80.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_mh_support)/launch/load_mh80.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_mh_support/launch/test_mh80.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<?xml version="1.0" ?>
<launch>
<include file="$(find motoman_mh_support)/launch/load_mh80.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.
Binary file not shown.
Binary file added motoman_mh_support/meshes/mh80/visual/link_b.stl
Binary file not shown.
Binary file added motoman_mh_support/meshes/mh80/visual/link_l.stl
Binary file not shown.
Binary file added motoman_mh_support/meshes/mh80/visual/link_r.stl
Binary file not shown.
Binary file added motoman_mh_support/meshes/mh80/visual/link_s.stl
Binary file not shown.
Binary file added motoman_mh_support/meshes/mh80/visual/link_t.stl
Binary file not shown.
Binary file added motoman_mh_support/meshes/mh80/visual/link_u.stl
Binary file not shown.
10 changes: 8 additions & 2 deletions motoman_mh_support/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,14 @@
<p>
This package contains configuration data, 3D models and launch files
for Motoman MH series manipulators. This currently includes the MH180-120
only.
and MH80 models.
</p>
<p>
Joint limits and max joint velocities are based on the information in the
<a href="https://cdn2.hubspot.net/hubfs/366775/Blog_Robots/MH180-120.pdf?t=1494345552355">
Motoman MH180-120 product specification document</a>.
Motoman MH180-120 product specification document</a>. and
<a href="https://cdn2.hubspot.net/hubfs/366775/Robots/MH80II.pdf">
Motoman MH80 product specification document</a>.
All URDFs / XACROs are based on the
default motion and joint velocity limits, unless noted otherwise (ie:
no support for high speed joints, extended / limited motion ranges or
Expand All @@ -25,6 +27,10 @@
in this package, be sure to check they are correct for the particular
robot model and configuration you intend to use them with.
</p>
<p><b>Contributors</b>:</p>
<p>
This support package has received contributions from: Ademola Oridate (UT Austin) (MH80).
</p>
</description>
<author email="michael.ripperger@swri.org">Michael Ripperger</author>
<maintainer email="michael.ripperger@swri.org">Michael Ripperger</maintainer>
Expand Down
27 changes: 27 additions & 0 deletions motoman_mh_support/test/roslaunch_test_mh80.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<launch>
<arg name="ip_str" value="127.0.0.1" />
<arg name="ctrlr" value="dx200" />

<group ns="load_mh80__">
<include file="$(find motoman_mh_support)/launch/load_mh80.launch"/>
</group>

<group ns="test_mh80__">
<include file="$(find motoman_mh_support)/launch/test_mh80.launch"/>
</group>

<group ns="robot_interface_streaming_mh80__">
<include file="$(find motoman_mh_support)/launch/robot_interface_streaming_mh80.launch">
<arg name="robot_ip" value="$(arg ip_str)" />
<arg name="controller" value="$(arg ctrlr)" />
</include>
</group>

<group ns="robot_state_visualize_mh80__">
<include file="$(find motoman_mh_support)/launch/robot_state_visualize_mh80.launch">
<arg name="robot_ip" value="$(arg ip_str)" />
<arg name="controller" value="$(arg ctrlr)" />
</include>
</group>
</launch>
5 changes: 5 additions & 0 deletions motoman_mh_support/urdf/mh80.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0" ?>
<robot name="motoman_mh80" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_mh_support)/urdf/mh80_macro.xacro"/>
<xacro:motoman_mh80 prefix=""/>
</robot>
182 changes: 182 additions & 0 deletions motoman_mh_support/urdf/mh80_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,182 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="motoman_mh80" params="prefix">
<!-- link list -->
<link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/visual/base_link.stl"/>
</geometry>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/collision/base_link.stl"/>
</geometry>
<material name="collision_material">
<color rgba="1 0 0 1"/>
</material>
</collision>
</link>
<link name="${prefix}link_s">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/visual/link_s.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/collision/link_s.stl"/>
</geometry>
<material name="collision_material"/>
</collision>
</link>
<link name="${prefix}link_l">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/visual/link_l.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/collision/link_l.stl"/>
</geometry>
<material name="collision_material"/>
</collision>
</link>
<link name="${prefix}link_u">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/visual/link_u.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/collision/link_u.stl"/>
</geometry>
<material name="collision_material"/>
</collision>
</link>
<link name="${prefix}link_r">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/visual/link_r.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/collision/link_r.stl"/>
</geometry>
<material name="collision_material"/>
</collision>
</link>
<link name="${prefix}link_b">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/visual/link_b.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/collision/link_b.stl"/>
</geometry>
<material name="collision_material"/>
</collision>
</link>
<link name="${prefix}link_t">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/visual/link_t.stl"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://motoman_mh_support/meshes/mh80/collision/link_t.stl"/>
</geometry>
<material name="collision_material"/>
</collision>
</link>
<link name="${prefix}tool0"/>
<!-- end of link list -->

<!-- joint list -->
<joint name="${prefix}joint_s" type="revolute">
<origin xyz="0 0 0.540" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_s"/>
<axis xyz="0 0 1"/>
EricMarcil marked this conversation as resolved.
Show resolved Hide resolved
<limit lower="-3.14159" upper="3.14159" effort="100" velocity="2.967" />
gavanderhoorn marked this conversation as resolved.
Show resolved Hide resolved
</joint>
<joint name="${prefix}joint_l" type="revolute">
<origin xyz="0.145 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_s"/>
<child link="${prefix}link_l"/>
<axis xyz="0 1 0" />
<limit lower="-1.5707" upper="2.3561" effort="100" velocity="2.443" />
</joint>
<joint name="${prefix}joint_u" type="revolute">
<origin xyz="0 0 0.870" rpy="0 0 0"/>
<parent link="${prefix}link_l"/>
<child link="${prefix}link_u"/>
<axis xyz="0 -1 0"/>
<limit lower="-2.9670" upper="4.3807" effort="100" velocity="2.792" />
</joint>
<joint name="${prefix}joint_r" type="revolute">
<origin xyz="0 0 0.210" rpy="0 0 0"/>
<parent link="${prefix}link_u"/>
<child link="${prefix}link_r"/>
<axis xyz="-1 0 0"/>
<limit lower="-6.2831" upper="6.2831" effort="100" velocity="4.014" />
</joint>
<joint name="${prefix}joint_b" type="revolute">
<origin xyz="1.025 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_r"/>
<child link="${prefix}link_b"/>
<axis xyz="0 -1 0" />
<limit lower="-2.1816" upper="2.1816" effort="100" velocity="4.014" />
</joint>
<joint name="${prefix}joint_t" type="revolute">
<origin xyz="0.175 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_b"/>
<child link="${prefix}link_t"/>
<axis xyz="-1 0 0" />
<limit lower="-6.2831" upper="6.2831" effort="100" velocity="6.108" />
</joint>
<joint name="${prefix}joint_t-tool0" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_t"/>
<child link="${prefix}tool0"/>
</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>
</xacro:macro>
</robot>