--- /dev/null
+<?xml version="1.0"?>
+
+<!-- Launch file for ekf_localization_node -->
+<launch>
+
+ <!-- This node will take in measurements from odometry, IMU, stamped pose, and stamped twist messages. It tracks
+ the state of the robot, with the state vector being defined as X position, Y position, Z position,
+ roll, pitch, yaw, their respective velocites, and linear acceleration. Units for all measurements are assumed
+ to conform to the SI standard as specified in REP-103. -->
+ <node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true" output="screen">
+
+ <!-- ======== STANDARD PARAMETERS ======== -->
+
+ <!-- The frequency, in Hz, at which the filter will output a position estimate. Note that
+ the filter will not begin computation until it receives at least one message from
+ one of the inputs. It will then run continuously at the frequency specified here,
+ regardless of whether it receives more measurements. Defaults to 30 if unspecified. -->
+ <param name="frequency" value="20"/>
+
+ <!-- The period, in seconds, after which we consider a sensor to have timed out. In this event, we
+ 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"/>
+
+ <!-- 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
+ ground plane that might otherwise be detected by, for example, an IMU. Defaults to false if
+ unspecified. -->
+ <param name="two_d_mode" value="true"/>
+
+ <!-- REP-105 (http://www.ros.org/reps/rep-0105.html) specifies three principal coordinate frames: map,
+ odom, and base_link. base_link is the coordinate frame that is affixed to the robot. The robot's
+ position in the odom frame will drift over time, but is accurate in the short term and should be
+ continuous. The odom frame is therefore the best frame for executing local motion plans. The map
+ frame, like the odom frame, is a world-fixed coordinate frame, and while it contains the most
+ globally accurate position estimate for your robot, it is subject to discrete jumps, e.g., due to
+ the fusion of GPS data. Here is how to use the following settings:
+ 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.
+ * If your system does not have a map_frame, just remove it, and make sure "world_frame" is set
+ to the value of odom_frame.
+ 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data,
+ set "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state
+ estimation nodes.
+ 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position
+ updates from landmark observations) then:
+ 3a. Set your "world_frame" to your map_frame value
+ 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be
+ another instance of robot_localization! However, that instance should *not* fuse the global data. -->
+ <!-- Defaults to "map" if unspecified -->
+ <param name="map_frame" value="map"/>
+ <!-- Defaults to "odom" if unspecified -->
+ <param name="odom_frame" value="odom"/>
+ <!-- Defaults to "base_link" if unspecified -->
+ <param name="base_link_frame" value="base_footprint"/>
+ <!-- Defaults to the value of "odom_frame" if unspecified -->
+ <param name="world_frame" value="odom"/>
+
+ <!-- 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"/>
+
+ <!-- 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,
+ e.g., odom0, odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These
+ parameters obviously have no default values, and must be specified. -->
+ <param name="odom0" value="odom"/>
+ <param name="imu0" value="imu"/>
+ <param name="odom1" value="gps"/>
+
+ <!-- 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,
+ but only want to use its Z position value, then set the entire vector to false, except for the third entry.
+ The order of the values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some
+ message types lack certain variables. For example, a TwistWithCovarianceStamped message has no pose information, so
+ the first six values would be meaningless in that case. Each vector defaults to all false if unspecified, effectively
+ making this parameter required for each sensor. -->
+ <rosparam param="odom0_config">[true, true, false, false, false, true, true, true, false, false, false, true, true, true, false]</rosparam>
+ <rosparam param="imu0_config">[false, false, false, true, true, true, false, false, false, true, true, true, true, true, true]</rosparam>
+ <rosparam param="odom1_config">[true, true, true, false, false, false, true, true, true, false, false, false, true, true, true]</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
+ nodes support fusion of absolute measurements. If you have more than one sensor providing absolute measurements,
+ however, you may run into problems if your covariances are not large enough, as the sensors will inevitably
+ diverge from one another, causing the filter to jump back and forth rapidly. To combat this situation, you can
+ either increase the covariances for the variables in question, or you can simply set the sensor's differential
+ parameter to true. When differential mode is enabled, all absolute pose data is converted to velocity data by
+ differentiating the absolute pose measurements. These velocities are then integrated as usual. NOTE: this only
+ applies to sensors that provide absolute measurements, so setting differential to true for twit measurements has
+ no effect.
+
+ Users should take care when setting this to true for orientation variables: if you have only one source of
+ absolute orientation data, you should not set the differential parameter to true. This is due to the fact that
+ integration of velocities leads to slowly increasing error in the absolute (pose) variable. For position variables,
+ this is acceptable. For orientation variables, it can lead to trouble. Users should make sure that all orientation
+ variables have at least one source of absolute measurement. -->
+ <param name="odom0_differential" value="true"/>
+ <param name="imu0_differential" value="false"/>
+ <param name="odom1_differential" value="true"/>
+
+ <!-- When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" for all
+ future measurements. While you can achieve the same effect with the differential paremeter, the key difference is
+ that the relative parameter doesn't cause the measurement to be converted to a velocity before integrating it. If
+ you simply want your measurements to start at 0 for a given sensor, set this to true. -->
+ <param name="odom0_relative" value="false"/>
+ <param name="imu0_relative" value="false"/>
+ <param name="odom1_relative" value="false"/>
+
+ <!-- If we're including accelerations in our state estimate, then we'll probably want to remove any acceleration that
+ is due to gravity for each IMU. If you don't want to, then set this to false. Defaults to false if unspecified. -->
+ <param name="imu0_remove_gravitational_acceleration" value="true"/>
+
+ <!-- If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see
+ if the node is unhappy with any settings or data. -->
+ <param name="print_diagnostics" value="true"/>
+
+ <remap from="odometry/filtered" to="odom_combined"/>
+
+ </node>
+
+</launch>