3 <arg name="use_imu" default="true"/>
5 <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
7 <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
9 <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
10 <param name="publish_frequency" value="20.0" />
12 <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen"/>
14 <node pkg="diagnostic_aggregator" type="aggregator_node" name="diagnostic_aggregator" output="screen">
15 <rosparam command="load" file="$(find wild_thumper)/config/analyzers.yaml"/>
18 <node pkg="wild_thumper" type="wt_node.py" name="wild_thumper" output="screen" respawn="false" required="true">
19 <param name="enable_odom_tf" value="true" unless="$(arg use_imu)"/>
20 <param name="enable_odom_tf" value="false" if="$(arg use_imu)"/>
23 <node pkg="wild_thumper" type="tinkerforge_imu2.py" name="tinkerforge_imu_brick2" output="screen">
24 <param name="uid" value="6DdNSn"/>
27 <node pkg="gpsd_client" type="gpsd_client" name="gpsd_client" output="screen">
28 <param name="use_gps_time" value="false"/>
31 <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
32 <arg name="config_file" value="$(find wild_thumper)/config/cmd_vel_mux.yaml" />
33 <arg name="nodelet_manager_name" value="nodelet_manager" />
36 <include file="$(find wild_thumper)/launch/robot_localization.launch" if="$(arg use_imu)"/>
37 <node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" output="screen">
38 <param name="magnetic_declination_radians" value="0.047"/>
39 <param name="yaw_offset" value="1.5708"/>
40 <param name="zero_altitude" value="true"/>
41 <param name="broadcast_utm_transform" value="true"/>
43 <remap from="/imu/data" to="imu"/>
44 <remap from="/gps/fix" to="fix" />
45 <remap from="/odometry/filtered" to="odom_combined"/>
46 <remap from="/odometry/gps" to="gps"/>