]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
simulation: switch robot_pose_ekf to robot_localization
authorErik Andresen <erik@vontaene.de>
Wed, 18 Oct 2017 20:12:02 +0000 (22:12 +0200)
committerErik Andresen <erik@vontaene.de>
Wed, 18 Oct 2017 20:12:02 +0000 (22:12 +0200)
launch/gazebo.launch
launch/gmapping.launch
launch/wild_thumper.launch

index 7580d4e0c04fce6be27fbfca94c7505c218f0620..5be2fd6bc31e4583c135480f400013f7ee266e63 100644 (file)
                <remap from="/image" to="/camera/depth/image_raw"/>
         </node>
 
-       <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="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="false"/>
-               <param name="debug" value="true"/>
-               <param name="sensor_timeout" value="2.0"/>
+       <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>
 
        <include file="$(find yocs_cmd_vel_mux)/launch/cmd_vel_mux.launch">
index 8a053f5743fe7fbfe4cfaa5b7bcf91c3a44f258f..a8a75d41eb657d7de3dd484b18f54ebac0451252 100644 (file)
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <launch>
        <arg name="use_sim_time" default="false" />
-       <param name="/use_sim_time" value="$(arg use_sim_time)"/>
+       <param name="/use_sim_time" value="$(arg use_sim_time)" if="$(arg use_sim_time)"/>
 
        <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping">
                <param name="scan" value="scan" />
index 7c9eece0a416734d801eed7af272a39bbbc163cb..80dbf6fb14f65fb04167b239989d4b4964fa0f56 100644 (file)
@@ -31,7 +31,7 @@
                <arg name="nodelet_manager_name" value="nodelet_manager" />
        </include>
 
-       <node pkg="robot_localization" type="ekf_localization_node" name="ekf" clear_params="true" output="screen">
+       <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>