<launch>
+
+ <arg name="paused" default="false"/>
+
<!-- Start Gazebo -->
- <include file="$(find gazebo_worlds)/launch/empty_world.launch"/>
+ <include file="$(find gazebo_worlds)/launch/empty_world.launch">
+ <arg name="paused" value="$(arg paused)"/>
+ </include>
<include file="$(find twil_description)/launch/twil.launch"/>
</launch>
<?xml version="1.0"?>
<launch>
+
+ <arg name="paused" default="false"/>
+
<!-- Start Gazebo -->
- <include file="$(find gazebo_worlds)/launch/empty_world.launch"/>
+ <include file="$(find gazebo_worlds)/launch/empty_world.launch">
+ <arg name="paused" value="$(arg paused)"/>
+ </include>
<include file="$(find twil_description)/launch/twil_wam.launch"/>
</launch>
<include filename="$(find twil_description)/xacro/cpu.urdf.xacro" />
<include filename="$(find twil_description)/xacro/eurocard.urdf.xacro" />
- <link name="twil_origin"/>
+ <link name="twil_origin" />
<xacro:chassis name="chassis" parent="twil_origin">
<origin xyz="0 0 0.172" rpy="0 0 0"/>
</xacro:fixed_wheel_support>
<xacro:fixed_wheel name="right_wheel" parent="right_wheel_support">
- <origin xyz="0 0 -0.095" rpy="0 0 0" />
+ <origin xyz="0 0 -0.095" rpy="0 0 ${-M_PI}" />
</xacro:fixed_wheel>
<xacro:fixed_wheel_support name="left_wheel_support" parent="chassis">
<origin xyz="-0.04 0 0" rpy="0 0 0" />
</xacro:castor_wheel>
- <xacro:battery_bosch_12v name="battery" parent="chassis">
+ <xacro:castor_support name="front_castor_support" parent="chassis">
+ <origin xyz="0.2 0 -0.002" rpy="0 0 0" />
+ </xacro:castor_support>
+
+ <xacro:castor_base name="front_castor_base" parent="front_castor_support">
+ <origin xyz="0 0 -0.1325" rpy="0 0 0" />
+ </xacro:castor_base>
+
+ <xacro:castor_wheel name="front_castor_wheel" parent="front_castor_base">
+ <origin xyz="-0.04 0 0" rpy="0 0 0" />
+ </xacro:castor_wheel>
+
+ <!--xacro:battery_bosch_12v name="battery" parent="chassis">
<origin xyz="-0.15 0.0 ${0.0015+0.0875}" rpy="0.0 0.0 ${M_PI/2}" />
+ </xacro:battery_bosch_12v-->
+
+ <xacro:battery_bosch_12v name="battery" parent="chassis">
+ <origin xyz="0.0 0.0 ${0.0015+0.0875}" rpy="0.0 0.0 ${M_PI/2}" />
</xacro:battery_bosch_12v>
<xacro:eurocard name="fan" parent="chassis">