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

Update GP8 support package (OPW params, missing links, collision mesh update) #493

Merged
merged 9 commits into from
Feb 13, 2025
Merged
Show file tree
Hide file tree
Changes from 8 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
2 changes: 1 addition & 1 deletion motoman_gp8_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_gp8.xml)
endif()

install(DIRECTORY config launch meshes urdf
Expand Down
20 changes: 20 additions & 0 deletions motoman_gp8_support/config/opw_parameters_gp8.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.345
c3: 0.340
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_gp8_support/meshes/collision/gp8_link_2_l.stl
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this a downsampled version of the visual mesh?

(just noticed the visual mesh is 1MB+. Not sure what happened during the review when that was initially contributed ..)

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That might have been from a 3D model that included a lot of internal elements which makes if harder reduce but still keep details. I should be able to generate new .dae model by converting MotoSim models that are already reduced.
@gavanderhoorn Do you want me to do it on this PR, or it's probably better to create a separate PR?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, no need.

It's already in the history of the repository, so adding a newer version will not reduce the total size.

Binary file not shown.
4 changes: 2 additions & 2 deletions motoman_gp8_support/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
</ul>
<p>
Joint limits and maximum joint velocities are based on the information
found in the online
https://www.motoman.com/hubfs/Robots/gp8.pdf
found in the online documentation files for the robot (CAD model GP8_3D.zip
and drawing datasheet <em>HW1384162</em> from <a href="https://www.yaskawa.eu.com/products/robots/handling-mounting/productdetail/product/gp8_694">here</a>).
All urdfs are based on the default motion and joint velocity limits,
unless noted otherwise.
</p>
Expand Down
59 changes: 0 additions & 59 deletions motoman_gp8_support/test/launch_test.xml

This file was deleted.

51 changes: 51 additions & 0 deletions motoman_gp8_support/test/launch_test_gp8.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
<!--
launch_test_gp8.xml - ROSlaunch tests
Usage Instructions:
1. Add the following to your CMakeLists.txt:
find_package(roslaunch)
roslaunch_add_file_check(test/launch_test_gp8.xml)
2. Create a test directory under your package
3. Add the "launch_text_gp8.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="controller" value="yrc1000" />

<group ns="load_gp8">
<include file="$(find motoman_gp8_support)/launch/load_gp8.launch" />
</group>

<group ns="test_gp8">
<include file="$(find motoman_gp8_support)/launch/test_gp8.launch" />
</group>

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

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

</launch>
Loading