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

Alternative for: Added variant model HC10DT-B10 #434

Merged
Merged
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
1 change: 1 addition & 0 deletions motoman_hc10_support/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(test/roslaunch_test_hc10.xml)
roslaunch_add_file_check(test/roslaunch_test_hc10dt.xml)
roslaunch_add_file_check(test/roslaunch_test_hc10dt_b10.xml)
endif()

install(DIRECTORY config launch meshes urdf
Expand Down
1 change: 1 addition & 0 deletions motoman_hc10_support/config/joint_names_hc10dt_b10.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_hc10_support/launch/load_hc10dt_b10.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_hc10_support)/urdf/hc10dt_b10.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 HC10DT IP67 (B10):
- 6 joints

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

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

<rosparam command="load" file="$(find motoman_hc10_support)/config/joint_names_hc10dt_b10.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
@@ -1,7 +1,7 @@
<!--
Manipulator specific version of the state visualizer.

Defaults provided for HC10:
Defaults provided for HC10DT:
- 6 joints

Usage:
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<!--
Manipulator specific version of the state visualizer.

Defaults provided for HC10DT IP67 (B10):
- 6 joints

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

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

<rosparam command="load" file="$(find motoman_hc10_support)/config/joint_names_hc10dt_b10.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_hc10_support)/launch/load_hc10dt_b10.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_hc10_support/launch/test_hc10dt_b10.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<include file="$(find motoman_hc10_support)/launch/load_hc10dt_b10.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.
89 changes: 89 additions & 0 deletions motoman_hc10_support/meshes/hc10dt_b10/visual/base_link.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions motoman_hc10_support/meshes/hc10dt_b10/visual/link_1_s.dae

Large diffs are not rendered by default.

151 changes: 151 additions & 0 deletions motoman_hc10_support/meshes/hc10dt_b10/visual/link_2_l.dae

Large diffs are not rendered by default.

141 changes: 141 additions & 0 deletions motoman_hc10_support/meshes/hc10dt_b10/visual/link_3_u.dae

Large diffs are not rendered by default.

151 changes: 151 additions & 0 deletions motoman_hc10_support/meshes/hc10dt_b10/visual/link_4_r.dae

Large diffs are not rendered by default.

167 changes: 167 additions & 0 deletions motoman_hc10_support/meshes/hc10dt_b10/visual/link_5_b.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions motoman_hc10_support/meshes/hc10dt_b10/visual/link_6_t.dae

Large diffs are not rendered by default.

10 changes: 7 additions & 3 deletions motoman_hc10_support/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,9 @@
<b>Specifications</b>
</p>
<ul>
<li>HC10 - Default</li>
<li>HC10DT - Default</li>
<li>HC10 - model 1-06VXHC10-A00</li>
<li>HC10DT - model 1-06VXHC10-A10</li>
<li>HC10DT-B10 - model 1-06VXHC10-B10</li>
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
Expand All @@ -26,7 +27,10 @@
<em>180571-1CD, rev 2</em>.
</li>
<li><em>YASKAWA MOTOMAN-HC10DT INSTRUCTIONS (HW1485083)</em> version
<em>180572-1CD, rev 2</em>.
<em>184672-1CD, rev 2</em>.
</li>
<li><em>YASKAWA MOTOMAN-HC10DT INSTRUCTIONS DUST-PROOF/DRIP-PROOF (HW1485083)</em> version
<em>188669-1CD, rev 1</em>.
</li>
</ul>
<p>
Expand Down
30 changes: 30 additions & 0 deletions motoman_hc10_support/test/roslaunch_test_hc10dt_b10.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_hc10dt_b10">
<include file="$(find motoman_hc10_support)/launch/load_hc10dt_b10.launch"/>
</group>

<group ns="test_hc10dt_b10">
<include file="$(find motoman_hc10_support)/launch/test_hc10dt_b10.launch"/>
</group>

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

<group ns="robot_state_visualize_hc10dt_b10">
<group ns="yrc1000" >
<include file="$(find motoman_hc10_support)/launch/robot_state_visualize_hc10dt_b10.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_hc10_support/urdf/hc10dt_b10.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0" ?>
<robot name="motoman_hc10dt_b10" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_hc10_support)/urdf/hc10dt_b10_macro.xacro" />
<xacro:motoman_hc10dt_b10 prefix=""/>
</robot>
169 changes: 169 additions & 0 deletions motoman_hc10_support/urdf/hc10dt_b10_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,169 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="motoman_hc10dt_b10" 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_hc10_support/meshes/hc10dt_b10/visual/base_link.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_1_s">
<visual>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/visual/link_1_s.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/collision/link_1_s.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_2_l">
<visual>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/visual/link_2_l.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/collision/link_2_l.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_3_u">
<visual>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/visual/link_3_u.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/collision/link_3_u.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_4_r">
<visual>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/visual/link_4_r.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/collision/link_4_r.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_5_b">
<visual>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/visual/link_5_b.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/collision/link_5_b.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_6_t">
<visual>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/visual/link_6_t.dae"/>
</geometry>
<xacro:material_yaskawa_blue/>
</visual>
<collision>
<geometry>
<mesh filename="package://motoman_hc10_support/meshes/hc10dt_b10/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.275" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit lower="${radians(-180)}" upper="${radians(180)}" effort="368.48" velocity="${radians(130)}"/>
</joint>
<joint name="${prefix}joint_2_l" type="revolute">
<parent link="${prefix}link_1_s"/>
<child link="${prefix}link_2_l"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit lower="${radians(-180)}" upper="${radians(180)}" effort="414.54" velocity="${radians(130)}"/>
</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 0.700" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="${radians(-95)}" upper="${radians(265)}" effort="158.76" velocity="${radians(180)}"/>
</joint>
<joint name="${prefix}joint_4_r" type="revolute">
<parent link="${prefix}link_3_u"/>
<child link="${prefix}link_4_r"/>
<origin xyz="0.500 0 0" rpy="0 0 0" />
<axis xyz="-1 0 0" />
<limit lower="${radians(-180)}" upper="${radians(180)}" effort="41.16" velocity="${radians(180)}"/>
</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.162 0" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="${radians(-180)}" upper="${radians(180)}" effort="33.32" velocity="${radians(250)}"/>
</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(-180)}" upper="${radians(180)}" effort="31.36" velocity="${radians(250)}"/>
</joint>
<!-- end of joint list -->

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

<!-- 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.275" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>
</xacro:macro>
</robot>