From 00432432eba76c41480a4efc85f2977336bd6573 Mon Sep 17 00:00:00 2001 From: Cindy Hua Date: Tue, 4 Mar 2025 21:05:10 -0500 Subject: [PATCH 1/2] Changed ekf_node to ekf_filter_node Changed in command, config file, and launch file. Signed-off-by: Cindy Hua --- setup_guides/odom/setup_robot_localization.rst | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/setup_guides/odom/setup_robot_localization.rst b/setup_guides/odom/setup_robot_localization.rst index 2c6c20923f..77945a9cb3 100644 --- a/setup_guides/odom/setup_robot_localization.rst +++ b/setup_guides/odom/setup_robot_localization.rst @@ -36,7 +36,7 @@ Next, we specify the parameters of the ``ekf_node`` using a YAML file. Create a .. code-block:: yaml ### ekf config file ### - ekf_node: + ekf_filter_node: ros__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 @@ -85,7 +85,7 @@ Next, we specify the parameters of the ``ekf_node`` using a YAML file. Create a In this configuration, we defined the parameter values of ``frequency``, ``two_d_mode``, ``publish_acceleration``, ``publish_tf``, ``map_frame``, ``odom_frame``, ``base_link_frame``, and ``world_frame``. For more information on the other parameters you can modify, see `Parameters of state estimation nodes `_, and a sample ``efk.yaml`` can be found `here `_. -To add a sensor input to the ``ekf_filter_node``, add the next number in the sequence to its base name (odom, imu, pose, twist). In our case, we have one ``nav_msgs/Odometry`` and one ``sensor_msgs/Imu`` as inputs to the filter, thus we use ``odom0`` and ``imu0``. We set the value of ``odom0`` to ``demo/odom``, which is the topic that publishes the ``nav_msgs/Odometry``. Similarly, we set the value of ``imu0`` to the topic that publishes ``sensor_msgs/Imu``, which is ``demo/imu``. +To add a sensor input to the ``ekf_node``, add the next number in the sequence to its base name (odom, imu, pose, twist). In our case, we have one ``nav_msgs/Odometry`` and one ``sensor_msgs/Imu`` as inputs to the filter, thus we use ``odom0`` and ``imu0``. We set the value of ``odom0`` to ``demo/odom``, which is the topic that publishes the ``nav_msgs/Odometry``. Similarly, we set the value of ``imu0`` to the topic that publishes ``sensor_msgs/Imu``, which is ``demo/imu``. To understand how ``robot_localization`` is configured and understand the reasoning behind the config have a look at `Configuring robot_localization `_. @@ -103,7 +103,7 @@ Now, let us add the ``ekf_node`` into the launch file. Open ``launch/display.lau robot_localization_node = Node( package='robot_localization', executable='ekf_node', - name='ekf_node', + name='ekf_filter_node', output='screen', parameters=[os.path.join(pkg_share, 'config/ekf.yaml'), {'use_sim_time': LaunchConfiguration('use_sim_time')}] ) From 437ea66ffb61793eecb3076adf20795479f18a32 Mon Sep 17 00:00:00 2001 From: Cindy Hua Date: Tue, 4 Mar 2025 21:20:13 -0500 Subject: [PATCH 2/2] Update setup_robot_localization.rst Signed-off-by: Cindy Hua --- setup_guides/odom/setup_robot_localization.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup_guides/odom/setup_robot_localization.rst b/setup_guides/odom/setup_robot_localization.rst index 77945a9cb3..22ed714268 100644 --- a/setup_guides/odom/setup_robot_localization.rst +++ b/setup_guides/odom/setup_robot_localization.rst @@ -85,7 +85,7 @@ Next, we specify the parameters of the ``ekf_node`` using a YAML file. Create a In this configuration, we defined the parameter values of ``frequency``, ``two_d_mode``, ``publish_acceleration``, ``publish_tf``, ``map_frame``, ``odom_frame``, ``base_link_frame``, and ``world_frame``. For more information on the other parameters you can modify, see `Parameters of state estimation nodes `_, and a sample ``efk.yaml`` can be found `here `_. -To add a sensor input to the ``ekf_node``, add the next number in the sequence to its base name (odom, imu, pose, twist). In our case, we have one ``nav_msgs/Odometry`` and one ``sensor_msgs/Imu`` as inputs to the filter, thus we use ``odom0`` and ``imu0``. We set the value of ``odom0`` to ``demo/odom``, which is the topic that publishes the ``nav_msgs/Odometry``. Similarly, we set the value of ``imu0`` to the topic that publishes ``sensor_msgs/Imu``, which is ``demo/imu``. +To add a sensor input to the ``ekf_filter_node``, add the next number in the sequence to its base name (odom, imu, pose, twist). In our case, we have one ``nav_msgs/Odometry`` and one ``sensor_msgs/Imu`` as inputs to the filter, thus we use ``odom0`` and ``imu0``. We set the value of ``odom0`` to ``demo/odom``, which is the topic that publishes the ``nav_msgs/Odometry``. Similarly, we set the value of ``imu0`` to the topic that publishes ``sensor_msgs/Imu``, which is ``demo/imu``. To understand how ``robot_localization`` is configured and understand the reasoning behind the config have a look at `Configuring robot_localization `_.