]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
urdf modifications
authorErik Andresen <erik@vontaene.de>
Sun, 12 Oct 2014 14:12:33 +0000 (16:12 +0200)
committerErik Andresen <erik@vontaene.de>
Sun, 12 Oct 2014 14:12:33 +0000 (16:12 +0200)
arm.launch
config/base_local_planner_params.yaml
urdf/arm.urdf [deleted file]
urdf/arm.urdf.xacro [new file with mode: 0644]

index 2ea8f39eca32be4c605c79287f3092fccb32bb3b..03255e2f51e0dd2fbd57b113d5904ed77f143017 100644 (file)
@@ -8,7 +8,6 @@
                <param name="output_frame_id" value="/scan" />
        </node>
 
-       <param name="robot_description" textfile="$(find arm)/urdf/arm.urdf" />
-
+       <param name="robot_description" command="$(find xacro)/xacro.py $(find arm)/urdf/arm.urdf.xacro" />
        <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
 </launch>
index d046846262e769172edc947a81ce8d3d48404bd3..ae715827b8bc7027aa8ec6eb1197e1902f2e63c5 100644 (file)
@@ -1,12 +1,12 @@
 TrajectoryPlannerROS:
-  max_vel_x: 0.20
-  min_vel_x: 0.20
-  max_vel_theta: 1.5
-  min_vel_theta: 0.8
-  min_in_place_vel_theta: 0.8
+  max_vel_x: 0.50
+  min_vel_x: 0.10
+  max_vel_theta: 1.0
+  min_vel_theta: -1.0
+  min_in_place_vel_theta: 0.4
 
-  acc_lim_x: 180
-  acc_lim_y: 0.0
-  acc_lim_th: 620
+  acc_lim_x: 2.5
+  acc_lim_y: 2.5
+  acc_lim_theta: 3.2
 
   holonomic_robot: false
diff --git a/urdf/arm.urdf b/urdf/arm.urdf
deleted file mode 100644 (file)
index 99e6dac..0000000
+++ /dev/null
@@ -1,68 +0,0 @@
-<?xml version="1.0"?>
-<robot name="arm">
-       <link name="base_link">
-               <visual>
-                       <geometry>
-                               <box size="0.30 0.22 0.015"/>
-                       </geometry>
-                       <origin xyz="0.08 0 0.095" rpy="0 0 0"/>
-                       <material name="black">
-                               <color rgba="0.0 0.0 0.0 1"/>
-                       </material>
-               </visual>
-       </link>
-
-       <link name="front_wheel">
-               <visual>
-                       <geometry>
-                               <cylinder radius="0.025" length="0.002"/>
-                       </geometry>
-                       <origin xyz="0 0 0" rpy="1.57 0 0"/>
-                       <material name="black">
-                               <color rgba="0 0 0 1"/>
-                       </material>
-               </visual>
-       </link>
-
-       <link name="aft_left_wheel">
-               <visual>
-                       <geometry>
-                               <cylinder radius="0.025" length="0.002"/>
-                       </geometry>
-                       <origin xyz="0 0 0" rpy="1.57 0 0"/>
-                       <material name="black">
-                               <color rgba="0 0 0 1"/>
-                       </material>
-               </visual>
-       </link>
-
-       <link name="aft_right_wheel">
-               <visual>
-                       <geometry>
-                               <cylinder radius="0.025" length="0.002"/>
-                       </geometry>
-                       <origin xyz="0 0 0" rpy="1.57 0 0"/>
-                       <material name="black">
-                               <color rgba="0 0 0 1"/>
-                       </material>
-               </visual>
-       </link>
-
-       <joint name="front_wheel_joint" type="fixed">
-               <parent link="base_link"/>
-               <child link="front_wheel"/>
-               <origin xyz="0.17 0.0 0.025" rpy="0 0 0"/>
-       </joint>
-
-       <joint name="aft_left_wheel_joint" type="fixed">
-               <parent link="base_link"/>
-               <child link="aft_left_wheel"/>
-               <origin xyz="0.0 0.05 0.025" rpy="0 0 0"/>
-       </joint>
-
-       <joint name="aft_right_wheel_joint" type="fixed">
-               <parent link="base_link"/>
-               <child link="aft_right_wheel"/>
-               <origin xyz="0.0 -0.05 0.025" rpy="0 0 0"/>
-       </joint>
-</robot>
diff --git a/urdf/arm.urdf.xacro b/urdf/arm.urdf.xacro
new file mode 100644 (file)
index 0000000..8e7b3d5
--- /dev/null
@@ -0,0 +1,83 @@
+<?xml version="1.0"?>
+<robot name="arm" xmlns:xacro="http://ros.org/wiki/xacro">
+       <xacro:include filename="$(find hector_sensors_description)/urdf/asus_camera.urdf.xacro" />
+
+       <link name="base_link">
+               <visual>
+                       <geometry>
+                               <box size="0.30 0.22 0.015"/>
+                       </geometry>
+                       <origin xyz="0.08 0 0.095" rpy="0 0 0"/>
+                       <material name="black">
+                               <color rgba="0.0 0.0 0.0 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="front_wheel">
+               <visual>
+                       <geometry>
+                               <cylinder radius="0.025" length="0.002"/>
+                       </geometry>
+                       <origin xyz="0 0 0" rpy="1.57 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="aft_left_wheel">
+               <visual>
+                       <geometry>
+                               <cylinder radius="0.025" length="0.002"/>
+                       </geometry>
+                       <origin xyz="0 0 0" rpy="1.57 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <link name="aft_right_wheel">
+               <visual>
+                       <geometry>
+                               <cylinder radius="0.025" length="0.002"/>
+                       </geometry>
+                       <origin xyz="0 0 0" rpy="1.57 0 0"/>
+                       <material name="black">
+                               <color rgba="0 0 0 1"/>
+                       </material>
+               </visual>
+       </link>
+
+       <xacro:asus_camera name="camera" parent="base_link">
+               <origin xyz="0.195 0.0 0.165" rpy="0 0 0"/>
+       </xacro:asus_camera>
+
+       <link name="scan">
+       </link>
+
+       <joint name="scan_joint" type="fixed">
+               <parent link="camera_depth_frame"/>
+               <child link="scan"/>
+               <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="front_wheel_joint" type="fixed">
+               <parent link="base_link"/>
+               <child link="front_wheel"/>
+               <origin xyz="0.17 0.0 0.025" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="aft_left_wheel_joint" type="fixed">
+               <parent link="base_link"/>
+               <child link="aft_left_wheel"/>
+               <origin xyz="0.0 0.05 0.025" rpy="0 0 0"/>
+       </joint>
+
+       <joint name="aft_right_wheel_joint" type="fixed">
+               <parent link="base_link"/>
+               <child link="aft_right_wheel"/>
+               <origin xyz="0.0 -0.05 0.025" rpy="0 0 0"/>
+       </joint>
+</robot>