]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/wild_thumper.launch
renamed move_base.py to wt_node.py
[ros_wild_thumper.git] / launch / wild_thumper.launch
1 <?xml version="1.0"?>
2 <launch>
3         <arg name="use_imu" default="true" />
4
5         <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro" />
6
7         <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
8
9         <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" >
10                 <rosparam command="load" file="$(find wild_thumper)/cfg/analyzers.yaml" />
11         </node>
12
13         <node pkg="wild_thumper" type="wt_node.py" name="wild_thumper" output="screen" respawn="true">
14                 <param name="enable_odom_tf" value="true" unless="$(arg use_imu)" />
15                 <param name="enable_odom_tf" value="false" if="$(arg use_imu)" />
16         </node>
17
18         <node pkg="razor_imu_9dof" type="imu_node.py" name="imu_node" output="screen" if="$(arg use_imu)">
19                 <rosparam file="$(find wild_thumper)/cfg/razor.yaml" command="load"/>
20         </node>
21
22         <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen" if="$(arg use_imu)">
23                 <remap from="imu_data" to="imu"/>
24                 <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
25                 <param name="output_frame" value="odom"/>
26                 <param name="freq" value="20.0"/>
27                 <param name="vo_used" value="false"/>
28                 <param name="debug" value="true"/>
29         </node>
30 </launch>