]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/wild_thumper.launch
Move gps nodes back to wild_thumper.launch
[ros_wild_thumper.git] / launch / wild_thumper.launch
index 5d90cadac9689396c2f0809f58fbf4bb77239e1a..1d304d83fa92c5b29eafa7b27e2848e3eb3c0b29 100644 (file)
@@ -1,5 +1,7 @@
 <?xml version="1.0"?>
 <launch>
+       <env name="ROSCONSOLE_CONFIG_FILE" value="$(find wild_thumper)/config/rosconsole.config"/>
+
        <arg name="use_imu" default="true"/>
 
        <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager"/>
                <param name="uid" value="6DdNSn"/>
        </node>
 
-       <node pkg="gpsd_client" type="gpsd_client"  name="gpsd_client" output="screen">
-               <param name="use_gps_time" value="false"/>
-       </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>
 
-       <include file="$(find wild_thumper)/launch/robot_localization.launch" if="$(arg use_imu)"/>
+       <node pkg="robot_localization" type="ekf_localization_node" name="ekf" clear_params="true" output="screen">
+               <rosparam command="load" file="$(find wild_thumper)/config/robot_localization.yaml"/>
+               <remap from="odometry/filtered" to="odom_combined"/>
+       </node>
+
+       <node pkg="gpsd_client" type="gpsd_client"  name="gpsd_client" output="screen">
+               <param name="use_gps_time" value="false"/>
+               <param name="frame_id" value="base_footprint"/>
+       </node>
+
        <node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" output="screen">
                <param name="magnetic_declination_radians" value="0.047"/>
-               <param name="yaw_offset" value="1.5708"/>
+               <param name="yaw_offset" value="0.0"/>
                <param name="zero_altitude" value="true"/>
                <param name="broadcast_utm_transform" value="true"/>