]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
urdf: Added additional links for collision checks
authorErik Andresen <erik@vontaene.de>
Sat, 1 Jun 2019 09:42:52 +0000 (11:42 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 1 Jun 2019 09:42:52 +0000 (11:42 +0200)
launch/moveit.launch [new file with mode: 0644]
urdf/arm.urdf

diff --git a/launch/moveit.launch b/launch/moveit.launch
new file mode 100644 (file)
index 0000000..5b2488f
--- /dev/null
@@ -0,0 +1,8 @@
+<?xml version="1.0"?>
+<launch>
+       <include file="$(find arm_moveit_config)/launch/move_group.launch" />
+
+       <include file="$(find arm_moveit_config)/launch/moveit_rviz.launch">
+               <arg name="config" value="true"/>
+       </include>
+</launch>
index e59c6e2974aaad369aa656cc2e38c3a015e0d1b5..3b7c0b75c3b0bf16feb931cacbcfdbf57a93c1ed 100644 (file)
@@ -115,6 +115,30 @@ For IKFast:
                </visual>
        </link>
 
+       <link name="link2_motor_extension">
+               <visual>
+                       <geometry>
+                               <box size="0.015 0.015 0.10"/>
+                       </geometry>
+                       <origin xyz="0 0 0.05" rpy="0 0 0"/>
+                       <material name="grey">
+                               <color rgba="0.5 0.5 0.5 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="plate_box">
+               <visual>
+                       <geometry>
+                               <box size="0.185 0.185 0.035"/>
+                       </geometry>
+                       <origin xyz="0 0 0.0175" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
        <joint name="plate_joint" type="fixed">
                <parent link="base_link"/>
                <child link="plate"/>
@@ -193,4 +217,16 @@ For IKFast:
                <origin xyz="0 -0.015 0" rpy="3.1416 0 0"/>
                <limit effort="1.0" lower="0.0" upper="0.35" velocity="0.1"/>
        </joint>
+
+       <joint name="link2_motor_extension_joint" type="fixed">
+               <parent link="link2"/>
+               <child link="link2_motor_extension"/>
+               <origin xyz="0.165 -0.03 0" rpy="1.5708 0 0"/>
+       </joint>
+
+       <joint name="plate_box_joint" type="fixed">
+               <parent link="plate"/>
+               <child link="plate_box"/>
+               <origin xyz="0 -0.035 0" rpy="0 0 0"/>
+       </joint>
 </robot>