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

HC20DTP and HC30PL Update #597

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
3 changes: 3 additions & 0 deletions motoman_hc20_support/launch/load_hc20dtp.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_hc20_support)/urdf/hc20dtp.xacro'" />
</launch>
3 changes: 3 additions & 0 deletions motoman_hc20_support/launch/load_hc30pl.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_hc20_support)/urdf/hc30pl.xacro'" />
</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 HC20DTP:
- 6 joints

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

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

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

<include file="$(find motoman_driver)/launch/robot_interface_streaming_$(arg controller).launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
</include>
</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 HC30PL:
- 6 joints

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

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

<rosparam command="load" file="$(find motoman_hc20_support)/config/joint_names_hc20.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_hc20_support/launch/robot_state_visualize_hc20dtp.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 HC20DTP:
- 6 joints

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

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

<rosparam command="load" file="$(find motoman_hc20_support)/config/joint_names_hc20.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_hc20_support)/launch/load_hc20dtp.launch" />

<node name="rviz" pkg="rviz" type="rviz" args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" required="true" />
</launch>
28 changes: 28 additions & 0 deletions motoman_hc20_support/launch/robot_state_visualize_hc30pl.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 HC30PL:
- 6 joints

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

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

<rosparam command="load" file="$(find motoman_hc20_support)/config/joint_names_hc20.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_hc20_support)/launch/load_hc30pl.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_hc20_support/launch/test_hc20dtp.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<include file="$(find motoman_hc20_support)/launch/load_hc20dtp.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>
7 changes: 7 additions & 0 deletions motoman_hc20_support/launch/test_hc30pl.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<include file="$(find motoman_hc20_support)/launch/load_hc30pl.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>
89 changes: 89 additions & 0 deletions motoman_hc20_support/meshes/hc20/visual/base_link.dae

Large diffs are not rendered by default.

Binary file not shown.
115 changes: 115 additions & 0 deletions motoman_hc20_support/meshes/hc20/visual/link_1_s.dae

Large diffs are not rendered by default.

Binary file not shown.
151 changes: 151 additions & 0 deletions motoman_hc20_support/meshes/hc20/visual/link_2_l.dae

Large diffs are not rendered by default.

Binary file not shown.
115 changes: 115 additions & 0 deletions motoman_hc20_support/meshes/hc20/visual/link_3_u.dae

Large diffs are not rendered by default.

Binary file not shown.
151 changes: 151 additions & 0 deletions motoman_hc20_support/meshes/hc20/visual/link_4_r.dae

Large diffs are not rendered by default.

Binary file not shown.
141 changes: 141 additions & 0 deletions motoman_hc20_support/meshes/hc20/visual/link_5_b.dae

Large diffs are not rendered by default.

Binary file not shown.
115 changes: 115 additions & 0 deletions motoman_hc20_support/meshes/hc20/visual/link_6_t.dae

Large diffs are not rendered by default.

Binary file not shown.
Binary file not shown.
Binary file not shown.
141 changes: 141 additions & 0 deletions motoman_hc20_support/meshes/hc20dtp/visual/link_5_b.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions motoman_hc20_support/meshes/hc20dtp/visual/link_6_t.dae

Large diffs are not rendered by default.

17 changes: 13 additions & 4 deletions motoman_hc20_support/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,13 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>motoman_hc20_support</name>
<version>0.1.0</version>
<version>1.0.0</version>
<description>
<p>ROS-Industrial support for the Motoman HC20 (and variants).</p>
<p>
This package contains configuration data, 3D models and launch files
for Motoman HC20 manipulators. This currently includes the base model
which also supports the DT and XP variants.
which also supports the DT, XP, DTP and HC30PL variants.
</p>
<p>
<b>Specifications</b>
Expand All @@ -17,11 +17,20 @@
<li>HC20 - Default</li>
<li>HC20DT - Default</li>
<li>HC20XP - Default</li>
<li>HC20DTP</li>
<li>HC30PL</li>
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
found in <em>YASKAWA MOTOMAN-HC20DT INSTRUCTIONS (HW1486129)</em>
version <em>190085-1CD, rev 1</em>.
found in:
<ul>
<li><em>YASKAWA MOTOMAN-HC20DT INSTRUCTIONS (HW1486129)</em>
version <em>190085-1CD, rev 1</em>.</li>
<li><em>YASKAWA MOTOMAN-HC20DTP INSTRUCTIONS (HW2480394)</em>
version <em>193888-1CD, rev 3</em>.</li>
<li><em>YASKAWA MOTOMAN-HC30PL INSTRUCTIONS (HW2480886)</em>
version <em>196230-1CD, rev 2</em>.</li>
</ul>
</p>
<p>
All urdfs are based on the default motion and joint velocity limits,
Expand Down
30 changes: 30 additions & 0 deletions motoman_hc20_support/test/roslaunch_test_hc20dtp.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_hc20dtp">
<include file="$(find motoman_hc20_support)/launch/load_hc20dtp.launch"/>
</group>

<group ns="test_hc20dtp">
<include file="$(find motoman_hc20_support)/launch/test_hc20dtp.launch"/>
</group>

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

<group ns="robot_state_visualize_hc20dtp">
<group ns="yrc1000" >
<include file="$(find motoman_hc20_support)/launch/robot_state_visualize_hc20dtp.launch">
<arg name="robot_ip" value="$(arg req_arg)" />
<arg name="controller" value="$(arg yrc1000)"/>
</include>
</group>
</group>
</launch>
30 changes: 30 additions & 0 deletions motoman_hc20_support/test/roslaunch_test_hc30pl.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_hc30pl">
<include file="$(find motoman_hc20_support)/launch/load_hc30pl.launch"/>
</group>

<group ns="test_hc30pl">
<include file="$(find motoman_hc20_support)/launch/test_hc30pl.launch"/>
</group>

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

<group ns="robot_state_visualize_hc30pl">
<group ns="yrc1000" >
<include file="$(find motoman_hc20_support)/launch/robot_state_visualize_hc30pl.launch">
<arg name="robot_ip" value="$(arg req_arg)" />
<arg name="controller" value="$(arg yrc1000)"/>
</include>
</group>
</group>
</launch>
14 changes: 7 additions & 7 deletions motoman_hc20_support/urdf/hc20_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<link name="${prefix}base_link">
<visual>
<geometry>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/base_link.stl"/>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/base_link.dae"/>
</geometry>
<xacro:material_yaskawa_white/>
</visual>
Expand All @@ -20,7 +20,7 @@
<link name="${prefix}link_1_s">
<visual>
<geometry>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_1_s.stl"/>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_1_s.dae"/>
</geometry>
<xacro:material_yaskawa_white/>
</visual>
Expand All @@ -33,7 +33,7 @@
<link name="${prefix}link_2_l">
<visual>
<geometry>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_2_l.stl"/>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_2_l.dae"/>
</geometry>
<xacro:material_yaskawa_white/>
</visual>
Expand All @@ -46,7 +46,7 @@
<link name="${prefix}link_3_u">
<visual>
<geometry>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_3_u.stl"/>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_3_u.dae"/>
</geometry>
<xacro:material_yaskawa_white/>
</visual>
Expand All @@ -59,7 +59,7 @@
<link name="${prefix}link_4_r">
<visual>
<geometry>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_4_r.stl"/>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_4_r.dae"/>
</geometry>
<xacro:material_yaskawa_white/>
</visual>
Expand All @@ -72,7 +72,7 @@
<link name="${prefix}link_5_b">
<visual>
<geometry>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_5_b.stl"/>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_5_b.dae"/>
</geometry>
<xacro:material_yaskawa_white/>
</visual>
Expand All @@ -85,7 +85,7 @@
<link name="${prefix}link_6_t">
<visual>
<geometry>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_6_t.stl"/>
<mesh filename="package://motoman_hc20_support/meshes/hc20/visual/link_6_t.dae"/>
</geometry>
<xacro:material_yaskawa_white/>
</visual>
Expand Down
5 changes: 5 additions & 0 deletions motoman_hc20_support/urdf/hc20dtp.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0" ?>
<robot name="motoman_hc20dtp" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_hc20_support)/urdf/hc20dtp_macro.xacro" />
<xacro:motoman_hc20dtp prefix=""/>
</robot>
Loading
Loading