+ <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
+
+ <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
+
+ <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
+ <param name="publish_frequency" value="20.0" />
+ </node>
+ <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen"/>
+
+ <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
+ <rosparam command="load" file="$(find wild_thumper)/config/analyzers.yaml"/>
+ </node>
+
+ <node pkg="wild_thumper" type="wt_node.py" name="wild_thumper" output="screen" respawn="false" required="true">
+ <param name="enable_odom_tf" value="true" unless="$(arg use_imu)"/>
+ <param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
+ </node>
+
+ <node pkg="wild_thumper" type="tinkerforge_imu2.py" name="tinkerforge_imu_brick2" output="screen" if="$(arg use_imu)">
+ <param name="uid" value="6DdNSn"/>
+ </node>
+
+ <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
+ <arg name="config_file" value="$(find wild_thumper)/config/cmd_vel_mux.yaml" />
+ <arg name="nodelet_manager_name" value="nodelet_manager" />
+ </include>
+
+ <node pkg="robot_localization" type="ekf_localization_node" name="ekf" clear_params="true" output="screen" if="$(arg use_imu)">
+ <rosparam command="load" file="$(find wild_thumper)/config/robot_localization.yaml"/>
+ <remap from="odometry/filtered" to="odom_combined"/>