Skip to content

Commit

Permalink
Merge pull request #500 from isys-vision/add_gp7_opw
Browse files Browse the repository at this point in the history
Update GP7 support package (OPW params, missing links, collision mesh update)
  • Loading branch information
gavanderhoorn authored Feb 13, 2025
2 parents 8ff166f + 6202cef commit a1164fc
Show file tree
Hide file tree
Showing 6 changed files with 51 additions and 21 deletions.
2 changes: 1 addition & 1 deletion motoman_gp7_support/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ 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_gp7.xml)
endif()

install(DIRECTORY config launch meshes urdf
Expand Down
20 changes: 20 additions & 0 deletions motoman_gp7_support/config/opw_parameters_gp7.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#
# Parameters for use with IK solvers which support OPW (Ortho-Parallel Wrist)
# kinematic configurations, as described in the paper "An Analytical Solution
# of the Inverse Kinematics Problem of Industrial Serial Manipulators with an
# Ortho-parallel Basis and a Spherical Wrist" by Mathias Brandstötter, Arthur
# Angerer, and Michael Hofbaur (Proceedings of the Austrian Robotics Workshop
# 2014, 22-23 May, 2014, Linz, Austria).
#
# The moveit_opw_kinematics_plugin package provides such a solver.
#
opw_kinematics_geometric_parameters:
a1: 0.040
a2: -0.040
b: 0.000
c1: 0.330
c2: 0.445
c3: 0.440
c4: 0.080
opw_kinematics_joint_offsets: [0.0, 0.0, deg(-90.0), 0.0, 0.0, deg(180.0)]
opw_kinematics_joint_sign_corrections: [1, 1, -1, -1, -1, -1]
Binary file modified motoman_gp7_support/meshes/collision/gp7_link_2_l.stl
Binary file not shown.
8 changes: 4 additions & 4 deletions motoman_gp7_support/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@
<li>GP7 - Default</li>
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
found in the online
https://www.motoman.com/hubfs/Robots/gp7.pdf
All urdfs are based on the default motion and joint velocity limits,
Joint limits and maximum joint velocities are based on the information
found in <em>YASKAWA MOTOMAN-GP8,-GP7 INSTRUCTIONS (HW1486547)</em> version
<em>194559-1CD, rev 4</em>.
All urdfs are based on the default motion and joint velocity limits,
unless noted otherwise.
</p>
<p>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
-->
<launch>
<arg name="req_arg" value="default"/>
<arg name="yrc1000" value="yrc1000"/>
<arg name="controller" value="yrc1000"/>

<group ns="load_gp7">
<include file="$(find motoman_gp7_support)/launch/load_gp7.launch"/>
Expand All @@ -39,19 +39,19 @@
</group>

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

<group ns="robot_state_visualize_gp7">
<group ns="yrc1000" >
<group ns="$(arg controller)" >
<include file="$(find motoman_gp7_support)/launch/robot_state_visualize_gp7.launch">
<arg name="robot_ip" value="$(arg req_arg)" />
<arg name="controller" value="$(arg yrc1000)"/>
<arg name="controller" value="$(arg controller)"/>
</include>
</group>
</group>
Expand Down
32 changes: 21 additions & 11 deletions motoman_gp7_support/urdf/gp7_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="motoman_gp7" params="prefix">
<xacro:macro name="motoman_gp7" params="prefix">
<xacro:include filename="$(find motoman_resources)/urdf/common_materials.xacro"/>

<!-- link list -->
Expand Down Expand Up @@ -95,7 +95,6 @@
</geometry>
</collision>
</link>
<link name="${prefix}tool0"/>
<!-- end of link list -->

<!-- joint list -->
Expand All @@ -104,49 +103,60 @@
<child link="${prefix}link_1_s"/>
<origin xyz="0 0 0.330" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit lower="-2.9670" upper="2.9670" effort="212.66" velocity="6.5448"/>
<limit lower="${radians(-170)}" upper="${radians(170)}" effort="212.66" velocity="${radians(375)}"/>
</joint>
<joint name="${prefix}joint_2_l" type="revolute">
<parent link="${prefix}link_1_s"/>
<child link="${prefix}link_2_l"/>
<origin xyz="0.040 0 0" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit lower="-1.1344" upper="2.5307" effort="205.80" velocity="5.4977"/>
<limit lower="${radians(-65)}" upper="${radians(145)}" effort="205.80" velocity="${radians(315)}"/>
</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.445" rpy="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="-1.2217" upper="3.3161" effort="106.82" velocity="7.1558"/>
<limit lower="${radians(-70)}" upper="${radians(190)}" effort="106.82" velocity="${radians(410)}"/>
</joint>
<joint name="${prefix}joint_4_r" type="revolute">
<parent link="${prefix}link_3_u"/>
<child link="${prefix}link_4_r"/>
<origin xyz="0.440 0 0.040" rpy="0 0 0" />
<axis xyz="-1 0 0" />
<limit lower="-3.3161" upper="3.3161" effort="55.86" velocity="9.5993"/>
<limit lower="${radians(-190)}" upper="${radians(190)}" effort="55.86" velocity="${radians(550)}"/>
</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="0 0 0" />
<axis xyz="0 -1 0" />
<limit lower="-2.3561" upper="2.3561" effort="32.68" velocity="9.5993"/>
<limit lower="${radians(-135)}" upper="${radians(135)}" effort="32.68" velocity="${radians(550)}"/>
</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="-6.2944" upper="6.2944" effort="22.54" velocity="17.4845"/>
<limit lower="${radians(-360)}" upper="${radians(360)}" effort="22.54" velocity="${radians(1000)}"/>
</joint>
<joint name="${prefix}joint_6_t-tool0" type="fixed">
<origin xyz="0.080 0 0" rpy="3.1415926 -1.570796 0"/>
<!-- 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.080 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>
<!-- end of joint list -->

<!-- ROS base_link to Robot Manufacturer World Coordinates transform -->
<link name="${prefix}base" />
Expand Down

0 comments on commit a1164fc

Please sign in to comment.