<?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"/>
<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)/cfg/analyzers.yaml"/>
+ <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="true">
+ <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="razor_imu_9dof" type="imu_node.py" name="imu_node" output="screen" if="$(arg use_imu)">
- <rosparam file="$(find wild_thumper)/cfg/razor.yaml" command="load"/>
+ <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"/>
</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="gps_common" type="utm_odometry_node" name="gps_conv" output="screen">
- <remap from="odom" to="gps"/>
- <param name="frame_id" value="odom"/>
- <param name="child_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="0.0"/>
+ <param name="zero_altitude" value="true"/>
+ <param name="broadcast_utm_transform" value="true"/>
- <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen" if="$(arg use_imu)">
- <remap from="imu_data" to="imu"/>
- <remap from="vo" to="gps"/>
- <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
- <param name="output_frame" value="odom"/>
- <param name="freq" value="20.0"/>
- <param name="vo_used" value="true"/>
- <param name="debug" value="true"/>
- <param name="sensor_timeout" value="2.0"/>
+ <remap from="/imu/data" to="imu"/>
+ <remap from="/gps/fix" to="fix" />
+ <remap from="/odometry/filtered" to="odom_combined"/>
+ <remap from="/odometry/gps" to="gps"/>
</node>
- <!-- <include file="$(find wild_thumper)/launch/robot_localization.launch" if="$(arg use_imu)"/> -->
-
- <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
- <arg name="config_file" value="$(find wild_thumper)/cfg/cmd_vel_mux.yaml" />
- <arg name="nodelet_manager_name" value="nodelet_manager" />
- </include>
</launch>