<arg name="wam" default="false"/>
<arg name="d435" default="false"/>
- <param unless="$(arg wam)" name="robot_description" command="$(find xacro)/xacro '$(find twil_description)/xacro/twil.urdf.xacro' d435:=$(arg d435) add_plug:=true" />
- <param if="$(arg wam)" name="robot_description" command="$(find xacro)/xacro '$(find twil_description)/xacro/twil_wam.urdf.xacro' d435:=$(arg d435) add_plug:=true" />
+ <param name="robot_description" command="$(find xacro)/xacro '$(find twil_description)/xacro/twil.urdf.xacro' wam:=$(arg wam) d435:=$(arg d435) add_plug:=true" />
</launch>
<xacro:include filename="$(find twil_description)/xacro/step_motor.urdf.xacro" />
<xacro:include filename="$(find twil_description)/xacro/sonar.urdf.xacro" />
- <xacro:if value="$(arg d435)">
- <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
- </xacro:if>
-
<link name="twil_origin" />
<xacro:chassis name="chassis" parent="twil_origin">
<origin xyz="0.0 0.0 0.787" rpy="0.0 0.0 0.0" />
</joint>
+ <xacro:if value="$(arg wam)">
+ <xacro:include filename="$(find wam_description)/xacro/wam_bhand.urdf.xacro" />
+ <joint name="twil_wam" type="fixed">
+ <parent link="chassis_top"/>
+ <child link="wam_origin" />
+ <origin xyz="-0.220 -0.140 0.0" rpy="0.0 0.0 0.0" />
+ </joint>
+ </xacro:if>
+
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" >
<!-- <robotNamespace>/twil</robotNamespace> -->
</gazebo>
<xacro:if value="$(arg d435)">
+ <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
<xacro:sensor_d435 parent="tower">
<origin xyz="0 0 0.876" rpy="0.0 0.0 0.0" />
</xacro:sensor_d435>
<origin xyz="0.0 0.0 0.0" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" />
</joint>
-
<gazebo reference="camera_link">
<sensor name="camera" type="depth">
<update_rate>15</update_rate> <!--or 6 or 30 -->
+++ /dev/null
-<?xml version="1.0"?>
-<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="twil">
-
- <xacro:include filename="$(find twil_description)/xacro/twil.urdf.xacro" />
-
- <xacro:include filename="$(find wam_description)/xacro/wam_bhand.urdf.xacro" />
-
-
- <joint name="twil_wam" type="fixed">
- <parent link="chassis_top"/>
- <child link="wam_origin" />
- <origin xyz="-0.220 -0.140 0.0" rpy="0.0 0.0 0.0" />
- </joint>
-
-
- <xacro:include filename="$(find twil_description)/xacro/caster_support.urdf.xacro" />
-
- <xacro:caster_support name="caster_support_front" parent="chassis">
- <origin xyz="0.2 0 -0.002" rpy="0 0 0" />
- </xacro:caster_support>
-
- <xacro:caster_base name="caster_base_front" parent="caster_support_front">
- <origin xyz="0 0 -0.1325" rpy="0 0 0" />
- </xacro:caster_base>
-
- <xacro:caster_wheel name="caster_wheel_front" parent="caster_base_front">
- <origin xyz="-0.04 0 0" rpy="0 0 0" />
- </xacro:caster_wheel>
-
-
-</robot>