]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/robot_localization.launch
Set sonar angle to 5° degree
[ros_wild_thumper.git] / launch / robot_localization.launch
index d3da3176d126d101ecd6ba882f80d79413ce5d0a..0a7aa6d7032237cf1f4038cc133b470a426debf5 100644 (file)
@@ -21,7 +21,7 @@
                   carry out a predict cycle on the EKF without correcting it. This parameter can be thought of
                   as the minimum frequency with which the filter will generate new output. Defaults to 1 / frequency
                   if not specified. -->
-               <param name="sensor_timeout" value="2.0"/>
+               <!-- <param name="sensor_timeout" value="2.0"/> -->
 
                <!-- If this is set to true, no 3D information will be used in your state estimate. Use this if you
                   are operating in a planar environment and want to ignore the effect of small variations in the
@@ -59,7 +59,7 @@
                <!-- Use this parameter to provide an offset to the transform generated by ekf_localization_node. This
                   can be used for future dating the transform, which is required for interaction with some other
                   packages. Defaults to 0.0 if unspecified. -->
-               <param name="transform_time_offset" value="0.0"/>
+               <!-- <param name="transform_time_offset" value="0.0"/> -->
 
                <!-- The filter accepts an arbitrary number of inputs from each input message type (Odometry, PoseStamped,
                   TwistStamped, Imu). To add a new one, simply append the next number in the sequence to its base name,
@@ -67,6 +67,7 @@
                   parameters obviously have no default values, and must be specified. -->
                <param name="odom0" value="odom"/>
                <param name="imu0" value="imu"/>
+               <rosparam param="imu0_queue_size">10</rosparam>
 
                <!-- Each sensor reading updates some or all of the filter's state. These options give you greater control over
                   which values from each measurement are fed to the filter. For example, if you have an odometry message as input,
@@ -77,8 +78,8 @@
                   making this parameter required for each sensor. -->
                <!-- x/y not included because of redundancy with velocities -->
                <!-- vyaw not included in odom because too inaccurate -->
-               <rosparam param="odom0_config">[false, false, false, false, false, false, true, true, false, false, false, false, false, false, false]</rosparam>
-               <rosparam param="imu0_config">[false, false, false, false, false, true, false, false, false, false, false, true, false, false, false]</rosparam>
+               <rosparam param="odom0_config">[false, false, false, false, false, false, true, true, true, false, false, true, false, false, false]</rosparam>
+               <rosparam param="imu0_config">[false, false, false, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>
 
                <!-- The best practice for including new sensors in robot_localization's state estimation nodes is to pass in velocity
                   measurements and let the nodes integrate them. However, this isn't always feasible, and so the state estimation
                   if the node is unhappy with any settings or data. -->
                <param name="print_diagnostics" value="true"/>
 
+               <!-- If true, will dynamically scale the process_noise_covariance based on the robot?s velocity. This is useful, e.g., when you want your
+                    robot?s estimate error covariance to stop growing when the robot is stationary. Defaults to false. -->
+               <param name="dynamic_process_noise_covariance" value="true"/>
+
                <remap from="odometry/filtered" to="odom_combined"/>
        </node>
 </launch>