Fixação do protótipo no gazebo com o link world e correções no código.
authorGabriel Schmitz <gschmitz@ece.ufrgs.br>
Thu, 10 Jan 2019 16:03:37 +0000 (14:03 -0200)
committerGabriel Schmitz <gschmitz@ece.ufrgs.br>
Thu, 10 Jan 2019 16:03:37 +0000 (14:03 -0200)
miitzhand_description/urdf/miitzhand.urdf

index 7edd25b..c9a7b63 100644 (file)
@@ -1,7 +1,13 @@
 <robot\r
   name="miitzhand">\r
- <link\r
+<link \r
+  name="world"/> \r
+  <link\r
     name="origin_link"/>\r
+   <joint name="world" type="fixed" >\r
+               <parent link="world"/>\r
+               <child link="origin_link"/>\r
+       </joint>\r
   <link\r
     name="base_link">\r
     <inertial>\r
@@ -42,7 +48,7 @@
       </geometry>\r
     </collision>\r
   </link>\r
-<joint name="origin_joint" type="fixed" static="true">\r
+<joint name="origin_joint" type="fixed" >\r
                <parent link="origin_link"/>\r
                <child link="base_link"/>\r
        </joint>\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="0 0 1" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r
     <axis\r
       xyz="-1 0 0" />\r
     <limit\r
-      lower="-1.57"\r
+      lower="0"\r
       upper="1.57"\r
       effort="30"\r
       velocity="2" />\r