]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
added meshes
authorErik Andresen <erik@vontaene.de>
Fri, 23 Oct 2015 16:49:24 +0000 (18:49 +0200)
committerErik Andresen <erik@vontaene.de>
Fri, 23 Oct 2015 16:49:24 +0000 (18:49 +0200)
meshes/31019.stl [new file with mode: 0644]
meshes/32985.stl [new file with mode: 0644]
meshes/35978.stl
scripts/arm_ros_conn.py
urdf/arm.urdf

diff --git a/meshes/31019.stl b/meshes/31019.stl
new file mode 100644 (file)
index 0000000..7468893
Binary files /dev/null and b/meshes/31019.stl differ
diff --git a/meshes/32985.stl b/meshes/32985.stl
new file mode 100644 (file)
index 0000000..5307211
Binary files /dev/null and b/meshes/32985.stl differ
index fd256fdfebfb88f444155c69f5ebfed636abbb53..0b0020a07224afc2a55fb32edc112e5ae31f8120 100644 (file)
Binary files a/meshes/35978.stl and b/meshes/35978.stl differ
index 1d27cd500bf263ba6333fa87d0481e031e92dcb6..0865b890bba1bffd0a4940ef7dc400d7bf76de33 100755 (executable)
@@ -11,7 +11,7 @@ from actionlib_msgs.msg import GoalStatus
 from time import sleep
 from math import *
 
-lJointNames = ["base_to_link1", "link_1_2_joint", "link_2_3_joint", "gripper_joint_1", "gripper_joint_2", "left_gripper_joint", "right_gripper_joint"]
+lJointNames = ["base_to_link1", "link_1_2_joint", "link_2_3_joint", "link_3_4_joint", "link_4_5_joint", "left_gripper_joint", "right_gripper_joint"]
 
 
 class ARMRosConn():
index f20e03e5fd88d25ba310528d23c476f9121ac0fd..0c24531deda1e25aee0eccbbb24c227dca677452 100644 (file)
@@ -1,12 +1,20 @@
 <?xml version="1.0"?>
 <robot name="arm">
        <link name="base_link">
+               <visual>
+                       <geometry>
+                               <mesh filename="package://arm_ros_conn/meshes/32985.stl" scale="1 1 1"/>
+                       </geometry>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
        </link>
 
        <link name="link1">
                <visual>
                        <geometry>
-                               <box size="0.06 0.03 0.135"/>
+                               <box size="0.06 0.03 0.123"/>
                        </geometry>
                        <origin xyz="0 0 0.0675"/>
                        <material name="grey">
@@ -39,7 +47,7 @@
                </visual>
        </link>
 
-       <link name="gripper_pole1">
+       <link name="link4">
                <visual>
                        <geometry>
                                <cylinder radius="0.045" length="0.03"/>
                </visual>
        </link>
 
-       <link name="gripper_pole2">
+       <link name="link5">
                <visual>
                        <geometry>
-                               <cylinder radius="0.03" length="0.015"/>
+                               <mesh filename="package://arm_ros_conn/meshes/31019.stl" scale="1 1 1"/>
                        </geometry>
                        <origin xyz="0.0 0 0" rpy="1.57075 0 0"/>
                        <material name="red">
                </visual>
        </link>
 
+       <link name="gripper_pole">
+       </link>
+
        <link name="left_gripper">
                <visual>
                        <origin xyz="0.025 0 0" rpy="-1.57075 3.1415 0"/>
                        <geometry>
                                <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
                        </geometry>
+                       <material name="red">
+                               <color rgba="1 0 0 1"/>
+                       </material>
                </visual>
        </link>
 
@@ -78,6 +92,9 @@
                        <geometry>
                                <mesh filename="package://arm_ros_conn/meshes/35978.stl" scale="0.001 0.001 0.001"/>
                        </geometry>
+                       <material name="red">
+                               <color rgba="1 0 0 1"/>
+                       </material>
                </visual>
        </link>
 
                <parent link="base_link"/>
                <child link="link1"/>
                <axis xyz="0 0 1"/>
+               <origin xyz="0 0.099 0"/>
                <limit effort="1000.0" lower="-5.672320068981571" upper="0.0" velocity="1.0"/>
        </joint>
 
                <limit effort="1000.0" lower="-3.141592653589793" upper="0.0" velocity="1.0"/>
        </joint>
 
-       <joint name="gripper_joint_1" type="continuous">
+       <joint name="link_3_4_joint" type="continuous">
                <parent link="link3"/>
-               <child link="gripper_pole1"/>
+               <child link="link4"/>
                <axis xyz="1 0 0"/>
                <origin xyz="0 0.135 0.0" rpy="1.57075 0 1.57075"/>
                <limit effort="1000.0" lower="-7.679448708775051" upper="0.6981317007977319" velocity="1.0"/>
        </joint>
 
-       <joint name="gripper_joint_2" type="continuous">
-               <parent link="gripper_pole1"/>
-               <child link="gripper_pole2"/>
+       <joint name="link_4_5_joint" type="continuous">
+               <parent link="link4"/>
+               <child link="link5"/>
                <axis xyz="0 1 0"/>
                <origin xyz="0.06 0.0 0.0" rpy="0 0 0"/>
                <limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
        </joint>
 
+       <joint name="gripper_pole_joint" type="fixed">
+               <parent link="link5"/>
+               <child link="gripper_pole"/>
+       </joint>
+
        <joint name="left_gripper_joint" type="revolute">
-               <parent link="gripper_pole2"/>
+               <parent link="gripper_pole"/>
                <child link="left_gripper"/>
                <axis xyz="0 0 1"/>
                <origin xyz="0.02 0.01 0" rpy="0 0 0" />
        </joint>
 
        <joint name="right_gripper_joint" type="revolute">
-               <parent link="gripper_pole2"/>
+               <parent link="gripper_pole"/>
                <child link="right_gripper"/>
                <axis xyz="0 0 -1"/>
                <origin xyz="0.02 -0.01 0" rpy="0 0 0"/>