-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Generate thirdparty Hiwin RA620 1621 URDF file with Xacro
with the following commands: # in git repo root directory docker run --rm -it -v $(pwd):/workspace osrf/ros:noetic-desktop-full # in the docker container mkdir -p ~/catkin_ws/src cp -r /workspace/thirdparty/hiwin_ra620_1621_support ~/catkin_ws/src cd ~/catkin_ws/ catkin_make source devel/setup.sh cd /workspace/thirdparty/hiwin_ra620_1621_support/urdf xacro -o ra620_1621.urdf ra620_1621.xacro
- Loading branch information
Showing
1 changed file
with
191 additions
and
0 deletions.
There are no files selected for viewing
191 changes: 191 additions & 0 deletions
191
thirdparty/hiwin_ra620_1621_support/urdf/ra620_1621.urdf
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,191 @@ | ||
<?xml version="1.0" ?> | ||
<!-- =================================================================================== --> | ||
<!-- | This document was autogenerated by xacro from ra620_1621.xacro | --> | ||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> | ||
<!-- =================================================================================== --> | ||
<robot name="hiwin_ra620_1621"> | ||
<!-- links: main serial chain --> | ||
<link name="base_link"> | ||
<visual> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/visual/base_link.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="Black"> | ||
<color rgba="0.0 0.0 0.0 1.0"/> | ||
</material> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/collision/base_link.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<link name="link_1"> | ||
<visual> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/visual/link_1.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="LightGrey"> | ||
<color rgba="0.999 0.999 0.999 1.0"/> | ||
</material> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/collision/link_1.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<link name="link_2"> | ||
<visual> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/visual/link_2.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="LightGrey"> | ||
<color rgba="0.999 0.999 0.999 1.0"/> | ||
</material> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/collision/link_2.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<link name="link_3"> | ||
<visual> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/visual/link_3.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="LightGrey"> | ||
<color rgba="0.999 0.999 0.999 1.0"/> | ||
</material> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/collision/link_3.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<link name="link_4"> | ||
<visual> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/visual/link_4.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="LightGrey"> | ||
<color rgba="0.999 0.999 0.999 1.0"/> | ||
</material> | ||
</visual> | ||
<collision> | ||
<origin rpy="0 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/collision/link_4.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<link name="link_5"> | ||
<visual> | ||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/visual/link_5.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="LightGrey"> | ||
<color rgba="0.999 0.999 0.999 1.0"/> | ||
</material> | ||
</visual> | ||
<collision> | ||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/collision/link_5.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<link name="link_6"> | ||
<visual> | ||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/visual/link_6.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="LightGrey"> | ||
<color rgba="0.999 0.999 0.999 1.0"/> | ||
</material> | ||
</visual> | ||
<collision> | ||
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://hiwin_ra620_1621_support/meshes/collision/link_6.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<!-- joints: main serial chain --> | ||
<joint name="joint_1" type="revolute"> | ||
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.245"/> | ||
<parent link="base_link"/> | ||
<child link="link_1"/> | ||
<axis xyz="0 0 1"/> | ||
<limit effort="0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="2.018"/> | ||
</joint> | ||
<joint name="joint_2" type="revolute"> | ||
<origin rpy="0.0 0.0 0.0" xyz="0.106 0.150 0.280"/> | ||
<parent link="link_1"/> | ||
<child link="link_2"/> | ||
<axis xyz="1 0 0"/> | ||
<limit effort="0" lower="-2.356194490192345" upper="1.7453292519943295" velocity="2.018"/> | ||
</joint> | ||
<joint name="joint_3" type="revolute"> | ||
<origin rpy="0.0 0.0 0.0" xyz="0.0385 0.0 0.770"/> | ||
<parent link="link_2"/> | ||
<child link="link_3"/> | ||
<axis xyz="1 0 0"/> | ||
<limit effort="0" lower="-1.3962634015954636" upper="3.3161255787892263" velocity="2.018"/> | ||
</joint> | ||
<joint name="joint_4" type="revolute"> | ||
<origin rpy="0.0 0.0 0.0" xyz="-0.1445 0.231 0.150"/> | ||
<parent link="link_3"/> | ||
<child link="link_4"/> | ||
<axis xyz="0 1 0"/> | ||
<limit effort="0" lower="-3.490658503988659" upper="3.490658503988659" velocity="2.018"/> | ||
</joint> | ||
<joint name="joint_5" type="revolute"> | ||
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.454 0.0"/> | ||
<parent link="link_4"/> | ||
<child link="link_5"/> | ||
<axis xyz="1 0 0"/> | ||
<limit effort="0" lower="-2.2689280275926285" upper="2.2689280275926285" velocity="2.018"/> | ||
</joint> | ||
<joint name="joint_6" type="revolute"> | ||
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0885 0.0"/> | ||
<parent link="link_5"/> | ||
<child link="link_6"/> | ||
<axis xyz="0 1 0"/> | ||
<limit effort="0" lower="-3.141592653589793" upper="3.141592653589793" velocity="2.018"/> | ||
</joint> | ||
<!-- ROS-Industrial 'base' frame: base_link to HIWIN World Coordinates transform --> | ||
<link name="base"/> | ||
<joint name="base_link-base" type="fixed"> | ||
<origin rpy="0 0 0" xyz="0.0 0.0 0.525"/> | ||
<parent link="base_link"/> | ||
<child link="base"/> | ||
</joint> | ||
<!-- ROS-Industrial 'flange' frame: attachment point for EEF models --> | ||
<link name="flange"/> | ||
<joint name="joint_6-flange" type="fixed"> | ||
<origin rpy="0 0 0" xyz="0 0.0215 0"/> | ||
<parent link="link_6"/> | ||
<child link="flange"/> | ||
</joint> | ||
<!-- ROS-Industrial 'tool0' frame: all-zeros tool frame --> | ||
<link name="tool0"/> | ||
<joint name="link_6-tool0" type="fixed"> | ||
<origin rpy="0.0 -1.5707963267948966 -1.5707963267948966" xyz="0 0.1215 0.0"/> | ||
<parent link="link_6"/> | ||
<child link="tool0"/> | ||
</joint> | ||
</robot> |