]> defiant.homedns.org Git - ros_wild_thumper.git/blob - wild_thumper.launch
a21a14c51a9d9ebebb047ad95c04fda2c882aeef
[ros_wild_thumper.git] / wild_thumper.launch
1 <?xml version="1.0"?>
2 <launch>
3         <arg name="use_imu" default="true"/>
4
5         <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
6
7         <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
8
9         <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
10                 <param name="publish_frequency" value="20.0" />
11         </node>
12         <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen"/>
13
14         <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
15                 <rosparam command="load" file="$(find wild_thumper)/config/analyzers.yaml"/>
16         </node>
17
18         <node pkg="wild_thumper" type="wt_node.py" name="wild_thumper" output="screen" respawn="false" required="false">
19                 <param name="enable_odom_tf" value="true" unless="$(arg use_imu)"/>
20                 <param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
21         </node>
22
23         <node pkg="razor_imu_9dof" type="imu_node.py" name="imu_node" output="screen" if="$(arg use_imu)">
24                 <rosparam file="$(find wild_thumper)/config/razor.yaml" command="load"/>
25         </node>
26
27         <node pkg="gpsd_client" type="gpsd_client"  name="gpsd_client" output="screen">
28                 <param name="use_gps_time" value="false"/>
29         </node>
30
31         <node pkg="gps_common" type="utm_odometry_node" name="gps_conv" output="screen">
32                 <remap from="odom" to="gps"/>
33                 <param name="frame_id" value="odom"/>
34                 <param name="child_frame_id" value="base_footprint"/>
35         </node>
36
37         <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen" if="$(arg use_imu)">
38                 <remap from="imu_data" to="imu"/>
39                 <remap from="vo" to="gps"/>
40                 <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
41                 <param name="output_frame" value="odom"/>
42                 <param name="freq" value="20.0"/>
43                 <param name="vo_used" value="true"/>
44                 <param name="debug" value="false"/>
45                 <param name="sensor_timeout" value="2.0"/>
46         </node>
47
48         <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
49                 <arg name="config_file" value="$(find wild_thumper)/config/cmd_vel_mux.yaml" />
50                 <arg name="nodelet_manager_name" value="nodelet_manager" />
51         </include>
52 </launch>