Skip to content

Commit

Permalink
add urdf folder based on elephantrobotics/mycobot_ros#48
Browse files Browse the repository at this point in the history
  • Loading branch information
kochigami committed Oct 13, 2022
1 parent fa99f09 commit a064297
Show file tree
Hide file tree
Showing 5 changed files with 75 additions and 46 deletions.
29 changes: 29 additions & 0 deletions urdf/common.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<?xml version="1.0"?>
<robot name="common" xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:property name="width" value=".2" />

<!-- PROPERTY LIST -->
<!-- All units in m-kg-s-radians unit system -->
<xacro:property name="M_PI" value="3.14159" />
<xacro:property name="SCALE_MM" value="0.001"/>
<xacro:property name="SCALE_CM" value="0.01"/>

<!-- Inertial macros. Units are kg*m^2 -->
<xacro:macro name="box_inertia" params="m x y z">
<inertia ixx="${m*(y*y+z*z)/12}" ixy = "0" ixz = "0"
iyy="${m*(z*z+x*x)/12}" iyz = "0"
izz="${m*(x*x+y*y)/12}" />
</xacro:macro>
<xacro:macro name="cylinder_inertia" params="m r h">
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy="0" ixz="0"
iyy="${m*(3*r*r+h*h)/12}" iyz="0"
izz="${m*r*r/2}" />
</xacro:macro>
<xacro:macro name="sphere_inertia" params="m r">
<inertia ixx="${m*r*r/5}" ixy="0" ixz="0"
iyy="${m*r*r/5}" iyz="0"
izz="${m*r*r/5}" />
</xacro:macro>

</robot>
2 changes: 1 addition & 1 deletion urdf/mycobot/mycobot.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<xacro:arg name="robot_namespace" default="" />

<xacro:include filename="$(find mycobot_description)/urdf/mycobot/mycobot.urdf.xacro" />
<xacro:include filename="$(find tork_moveit_tutorial)/urdf/mycobot/mycobot.urdf.xacro" />

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
Expand Down
30 changes: 15 additions & 15 deletions urdf/mycobot/mycobot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="mycobot" >

<xacro:include filename="$(find mycobot_description)/urdf/common.xacro" />
<xacro:include filename="$(find tork_moveit_tutorial)/urdf/common.xacro" />

<link name="link1">
<inertial>
Expand All @@ -11,13 +11,13 @@
</inertial>
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link1.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link1.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 -${pi/2}"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link1.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link1.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 -${pi/2}"/>
</collision>
Expand All @@ -31,13 +31,13 @@
</inertial>
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link2.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link2.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.06096 " rpy = " 0 0 -${pi/2}"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link2.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link2.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.06096 " rpy = " 0 0 -${pi/2}"/>
</collision>
Expand All @@ -51,13 +51,13 @@
</inertial>
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link3.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link3.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03256 " rpy = " 0 -${pi/2} 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link3.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link3.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03256 " rpy = " 0 -${pi/2} 0"/>
</collision>
Expand All @@ -72,14 +72,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link4.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link4.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03056 " rpy = " 0 -${pi/2} 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link4.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link4.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03056 " rpy = " 0 -${pi/2} 0"/>
</collision>
Expand All @@ -94,14 +94,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link5.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link5.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03356 " rpy = " -${pi/2} 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link5.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link5.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03356 " rpy = " -${pi/2} 0 0"/>
</collision>
Expand All @@ -116,14 +116,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link6.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link6.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.038 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link6.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link6.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.038 " rpy = " 0 0 0"/>
</collision>
Expand All @@ -138,14 +138,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link7.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link7.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/mesh/link7.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/mesh/link7.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</collision>
Expand Down
30 changes: 15 additions & 15 deletions urdf/mycobot/mycobot_with_vision.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mycobot/suit_env.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/suit_env.dae"/>
</geometry>
<origin xyz = "0 0 -0.02 " rpy = "1.5708 0 -1.5708"/>
</visual>
Expand All @@ -16,14 +16,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mycobot/joint1.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint1.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 -1.5708"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 1.5708 3.14159-->
<mesh filename="package://mycobot_description/urdf/mycobot/joint1.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint1.dae"/>
</geometry>
<origin xyz = "0.0 0 0 " rpy = " 0 0 -1.5708"/>
</collision>
Expand All @@ -32,13 +32,13 @@
<link name="joint2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/joint2.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint2.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.06096 " rpy = " 0 0 -1.5708"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/joint2.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint2.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.06096 " rpy = " 0 0 -1.5708"/>
</collision>
Expand All @@ -48,13 +48,13 @@
<link name="joint3">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/joint3.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint3.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03256 " rpy = " 0 -1.5708 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/mycobot/joint3.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint3.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03256 " rpy = " 0 -1.5708 0"/>
</collision>
Expand All @@ -65,14 +65,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint4.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint4.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03056 " rpy = " 0 -1.5708 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint4.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint4.dae"/>
</geometry>
<origin xyz = "0.0 0 0.03056 " rpy = " 0 -1.5708 0"/>
</collision>
Expand All @@ -83,14 +83,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint5.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint5.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03356 " rpy = "-1.5708 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint5.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint5.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.03356 " rpy = "-1.5708 0 0"/>
</collision>
Expand All @@ -101,14 +101,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint6.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint6.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.038 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint6.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint6.dae"/>
</geometry>
<origin xyz = "0 0.00 -0.038 " rpy = " 0 0 0"/>
</collision>
Expand All @@ -119,14 +119,14 @@
<visual>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint7.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint7.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<!--- 0.0 0 -0.04 -->
<mesh filename="package://mycobot_description/urdf/mycobot/joint7.dae"/>
<mesh filename="package://tork_moveit_tutorial/urdf/mycobot/joint7.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</collision>
Expand Down
Loading

0 comments on commit a064297

Please sign in to comment.