Skip to content

Commit 534a719

Browse files
Merge pull request #521 from mabelzhang/dashing-cherry-pick-melodic
Port to Dashing: robot_localization_estimator and ros_robot_localization_listener
2 parents 889c0cb + 37ae642 commit 534a719

19 files changed

+1983
-42
lines changed

CMakeLists.txt

Lines changed: 46 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,14 +19,18 @@ find_package(geometry_msgs REQUIRED)
1919
find_package(nav_msgs REQUIRED)
2020
find_package(rosidl_default_generators REQUIRED)
2121
find_package(sensor_msgs REQUIRED)
22+
find_package(std_srvs REQUIRED)
2223
find_package(tf2 REQUIRED)
24+
find_package(tf2_eigen REQUIRED)
2325
find_package(tf2_geometry_msgs REQUIRED)
2426
find_package(tf2_ros REQUIRED)
2527
find_package(Eigen3 REQUIRED)
28+
find_package(yaml-cpp REQUIRED)
2629

2730
set(library_name rl_lib)
2831

2932
rosidl_generate_interfaces(${PROJECT_NAME}
33+
"srv/GetState.srv"
3034
"srv/SetDatum.srv"
3135
"srv/SetPose.srv"
3236
DEPENDENCIES
@@ -50,8 +54,10 @@ add_library(
5054
src/filter_base.cpp
5155
src/filter_utilities.cpp
5256
src/navsat_transform.cpp
57+
src/robot_localization_estimator.cpp
5358
src/ros_filter.cpp
54-
src/ros_filter_utilities.cpp)
59+
src/ros_filter_utilities.cpp
60+
src/ros_robot_localization_listener.cpp)
5561

5662
rosidl_target_interfaces(${library_name}
5763
${PROJECT_NAME} "rosidl_typesupport_cpp")
@@ -71,21 +77,32 @@ add_executable(
7177
src/navsat_transform_node.cpp
7278
)
7379

80+
add_executable(
81+
robot_localization_listener_node
82+
src/robot_localization_listener_node.cpp
83+
)
84+
7485
target_link_libraries(
7586
${library_name}
7687
${EIGEN3_LIBRARIES}
88+
yaml-cpp
7789
)
7890

7991
ament_target_dependencies(
8092
${library_name}
8193
diagnostic_msgs
8294
diagnostic_updater
95+
eigen_conversions
96+
geographic_msgs
8397
geometry_msgs
8498
nav_msgs
8599
rcl
86100
rclcpp
87101
sensor_msgs
102+
std_msgs
103+
std_srvs
88104
tf2
105+
tf2_eigen
89106
tf2_geometry_msgs
90107
tf2_ros
91108
)
@@ -120,13 +137,23 @@ ament_target_dependencies(
120137
rclcpp
121138
)
122139

140+
target_link_libraries(
141+
robot_localization_listener_node
142+
${library_name}
143+
)
144+
145+
ament_target_dependencies(
146+
robot_localization_listener_node
147+
rclcpp
148+
)
149+
123150
if(BUILD_TESTING)
124151
find_package(ament_cmake_gtest REQUIRED)
125152
find_package(ament_cmake_cppcheck REQUIRED)
126153
find_package(ament_cmake_cpplint REQUIRED)
127154
find_package(ament_cmake_lint_cmake REQUIRED)
128155
find_package(ament_cmake_uncrustify REQUIRED)
129-
156+
find_package(launch_testing_ament_cmake)
130157

131158
#### FILTER BASE TESTS ####
132159
ament_add_gtest(filter_base-test test/test_filter_base.cpp)
@@ -194,6 +221,19 @@ if(BUILD_TESTING)
194221
# ament_add_gtest(test_ukf_localization_node_bag3 test/test_localization_node_bag_pose_tester.cpp)
195222
# target_link_libraries(test_ukf_localization_node_bag3 ${library_name})
196223

224+
#### RLE/RLL TESTS #####
225+
ament_add_gtest(test_robot_localization_estimator
226+
test/test_robot_localization_estimator.cpp)
227+
target_link_libraries(test_robot_localization_estimator ${library_name})
228+
229+
ament_add_gtest(test_ros_robot_localization_listener
230+
test/test_ros_robot_localization_listener.cpp)
231+
target_link_libraries(test_ros_robot_localization_listener ${library_name})
232+
233+
ament_add_gtest(test_ros_robot_localization_listener_publisher
234+
test/test_ros_robot_localization_listener_publisher.cpp)
235+
target_link_libraries(test_ros_robot_localization_listener_publisher ${library_name})
236+
197237
ament_cppcheck(LANGUAGE "c++")
198238
ament_cpplint()
199239
ament_lint_cmake()
@@ -210,6 +250,9 @@ if(BUILD_TESTING)
210250
#test_ekf_localization_node_bag1
211251
#test_ekf_localization_node_bag2
212252
#test_ekf_localization_node_bag3
253+
test_robot_localization_estimator
254+
test_ros_robot_localization_listener
255+
test_ros_robot_localization_listener_publisher
213256
#test_ukf_localization_node_bag1
214257
#test_ukf_localization_node_bag2
215258
#test_ukf_localization_node_bag3
@@ -229,6 +272,7 @@ install(
229272
navsat_transform_node
230273
ekf_node
231274
ukf_node
275+
robot_localization_listener_node
232276
${library_name}
233277
DESTINATION lib/${PROJECT_NAME}
234278
)

doc/configuring_robot_localization.rst

Lines changed: 30 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@ Note that the configuration vector is given in the ``frame_id`` of the input mes
1717

1818
.. code-block:: xml
1919
20-
<rosparam param="twist0_config">[false, false, false,
21-
false, false, false,
22-
true, false, false,
20+
<rosparam param="twist0_config">[false, false, false,
21+
false, false, false,
22+
true, false, false,
2323
false, false, false,
2424
false, false, false]</rosparam>
2525
@@ -33,19 +33,19 @@ The first decision to make when configuring your sensors is whether or not your
3333
Fusing Unmeasured Variables
3434
***************************
3535

36-
Let's start with an example. Let's say you have a wheeled, nonholonomic robot that works in a planar environment. Your robot has some wheel encoders that are used to estimate instantaneous X velocity as well as absolute pose information. This information is reported in an `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message. Additionally, your robot has an IMU that measures rotational velocity, vehicle attitude, and linear acceleration. Its data is reported in a `sensor_msgs/Imu.html <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message. As we are operating in a planar environment, we set the ``two_d_mode`` parameter to *true*. This will automatically zero out all 3D variables, such as :math:`Z`, :math:`roll`, :math:`pitch`, their respective velocities, and :math:`Z` acceleration. We start with this configuration:
36+
Let's start with an example. Let's say you have a wheeled, nonholonomic robot that works in a planar environment. Your robot has some wheel encoders that are used to estimate instantaneous X velocity as well as absolute pose information. This information is reported in an `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message. Additionally, your robot has an IMU that measures rotational velocity, vehicle attitude, and linear acceleration. Its data is reported in a `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message. As we are operating in a planar environment, we set the ``two_d_mode`` parameter to *true*. This will automatically zero out all 3D variables, such as :math:`Z`, :math:`roll`, :math:`pitch`, their respective velocities, and :math:`Z` acceleration. We start with this configuration:
3737

3838
.. code-block:: xml
3939
40-
<rosparam param="odom0_config">[true, true, false,
41-
false, false, true,
42-
true, false, false,
40+
<rosparam param="odom0_config">[true, true, false,
41+
false, false, true,
42+
true, false, false,
4343
false, false, true,
4444
false, false, false]</rosparam>
4545
46-
<rosparam param="imu0_config">[false, false, false,
47-
false, false, true,
48-
false, false, false,
46+
<rosparam param="imu0_config">[false, false, false,
47+
false, false, true,
48+
false, false, false,
4949
false, false, true,
5050
true, false, false]</rosparam>
5151
@@ -55,35 +55,35 @@ As a first pass, this makes sense, as a planar robot only needs to concern itsel
5555

5656
.. code-block:: xml
5757
58-
<rosparam param="odom0_config">[false, false, false,
59-
false, false, false,
60-
true, false, false,
58+
<rosparam param="odom0_config">[false, false, false,
59+
false, false, false,
60+
true, false, false,
6161
false, false, true,
6262
false, false, false]</rosparam>
6363
64-
<rosparam param="imu0_config">[false, false, false,
65-
false, false, true,
66-
false, false, false,
64+
<rosparam param="imu0_config">[false, false, false,
65+
false, false, true,
66+
false, false, false,
6767
false, false, true,
6868
true, false, false]</rosparam>
6969
7070
2. Next, we note that we are not fusing :math:`\dot{Y}`. At first glance, this is the right choice, as our robot cannot move instantaneously sideways. However, if the `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message reports a :math:`0` value for :math:`\dot{Y}` (and the :math:`\dot{Y}` covariance is NOT inflated to a large value), it's best to feed that value to the filter. As a :math:`0` measurement in this case indicates that the robot cannot ever move in that direction, it serves as a perfectly valid measurement:
7171

7272
.. code-block:: xml
7373
74-
<rosparam param="odom0_config">[false, false, false,
75-
false, false, false,
76-
true, true, false,
74+
<rosparam param="odom0_config">[false, false, false,
75+
false, false, false,
76+
true, true, false,
7777
false, false, true,
7878
false, false, false]</rosparam>
7979
80-
<rosparam param="imu0_config">[false, false, false,
81-
false, false, true,
82-
false, false, false,
80+
<rosparam param="imu0_config">[false, false, false,
81+
false, false, true,
82+
false, false, false,
8383
false, false, true,
8484
true, false, false]</rosparam>
8585
86-
You may wonder why did we not fuse :math:`\dot{Z}` velocity for the same reason. The answer is that we did when we set ``two_d_mode`` to *false*. If we hadn't, we could, in fact, fuse the :math:`0` measurement for :math:`\dot{Z}` velocity into the filter.
86+
You may wonder why did we not fuse :math:`\dot{Z}` velocity for the same reason. The answer is that we did when we set ``two_d_mode`` to *false*. If we hadn't, we could, in fact, fuse the :math:`0` measurement for :math:`\dot{Z}` velocity into the filter.
8787

8888
3. Last, we come to the IMU. You may notice that we have set the :math:`\ddot{Y}` to *false*. This is due to the fact that many systems, including the hypothetical one we are discussing here, will not undergo instantaneous :math:`Y` acceleration. However, the IMU will likely report non-zero, noisy values for Y acceleration, which can cause your estimate to drift rapidly.
8989

@@ -96,21 +96,21 @@ The state estimation nodes in ''robot_localization'' allow users to fuse as many
9696

9797
.. code-block:: xml
9898
99-
<rosparam param="imu0_config">[false, false, false,
100-
true, true, true,
101-
false, false, false,
99+
<rosparam param="imu0_config">[false, false, false,
100+
true, true, true,
101+
false, false, false,
102102
false, false, false,
103103
false, false, false]</rosparam>
104104
105-
<rosparam param="imu1_config">[false, false, false,
106-
true, true, true,
107-
false, false, false,
105+
<rosparam param="imu1_config">[false, false, false,
106+
true, true, true,
107+
false, false, false,
108108
false, false, false,
109109
false, false, false]</rosparam>
110110
111111
In this case, users should be **very** careful and ensure that the covariances on each measured orientation variable are set correctly. If each IMU advertises a yaw variance of, for example, :math:`0.1`, yet the delta between the IMUs' yaw measurements is :math:`> 0.1`, then the output of the filter will oscillate back and forth between the values provided by each sensor. Users should make sure that the noise distributions around each measurement overlap.
112112
113-
2. Alternatively, users can make use of the ``_differential`` parameter. By setting this to *true* for a given sensor, all pose (position and orientation) data is converted to a velocity by calculating the change in the measurement value between two consecutive time steps. The data is then fused as a velocity. Again, though, users should take care: when measurements are fused absolutely (especially IMUs), if the measurement has a static or non-increasing variance for a given variable, then the variance in the estimate's covariance matrix will be bounded. If that information is converted to a velocity, then at each time step, the estimate will gain some small amount of error, and the variance for the variable in question will grow without bound. For position :math:`(X, Y, Z)` information, this isn't an issue, but for orientation data, it is a problem. For example, it is acceptable for a robot to move around its environment and accumulate :math:`1.5` meters of error in the :math:`X` direction after some time. If that same robot moves around and accumulates :math:`1.5` radians of error in yaw, then when the robot next drives forward, its position error will explode.
113+
2. Alternatively, users can make use of the ``_differential`` parameter. By setting this to *true* for a given sensor, all pose (position and orientation) data is converted to a velocity by calculating the change in the measurement value between two consecutive time steps. The data is then fused as a velocity. Again, though, users should take care: when measurements are fused absolutely (especially IMUs), if the measurement has a static or non-increasing variance for a given variable, then the variance in the estimate's covariance matrix will be bounded. If that information is converted to a velocity, then at each time step, the estimate will gain some small amount of error, and the variance for the variable in question will grow without bound. For position :math:`(X, Y, Z)` information, this isn't an issue, but for orientation data, it is a problem. For example, it is acceptable for a robot to move around its environment and accumulate :math:`1.5` meters of error in the :math:`X` direction after some time. If that same robot moves around and accumulates :math:`1.5` radians of error in yaw, then when the robot next drives forward, its position error will explode.
114114
115115
The general rule of thumb for the ``_differential`` parameter is that if a give robot has only one source of orientation data, then the differential parameter should be set to *false*. If there are :math:`N` sources, users can set the ``_differential`` parameter to *true* for :math:`N-1` of them, or simply ensure that the covariance values are large enough to eliminate oscillations.
116116

doc/navsat_transform_node.rst

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
navsat_transform_node
22
*********************
33

4-
``navsat_transform_node`` takes as input a `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message (usually the output of ``ekf_localization_node`` or ``ukf_localization_node``), a `sensor_msgs/Imu.html <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ containing an accurate estimate of your robot's heading, and a `sensor_msgs/NavSatFix.html <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing GPS data. It produces an odometry message in coordinates that are consistent with your robot's world frame. This value can be directly fused into your state estimate.
4+
``navsat_transform_node`` takes as input a `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message (usually the output of ``ekf_localization_node`` or ``ukf_localization_node``), a `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ containing an accurate estimate of your robot's heading, and a `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing GPS data. It produces an odometry message in coordinates that are consistent with your robot's world frame. This value can be directly fused into your state estimate.
55

66
.. note:: If you fuse the output of this node with any of the state estimation nodes in ``robot_localization``, you should make sure that the ``odomN_differential`` setting is *false* for that input.
77

@@ -10,7 +10,7 @@ Parameters
1010

1111
~frequency
1212
^^^^^^^^^^
13-
The real-valued frequency, in Hz, at which ``navsat_transform_node`` checks for new `sensor_msgs/NavSatFix.html <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ messages, and publishes filtered `sensor_msgs/NavSatFix.html <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ when ``publish_filtered_gps`` is set to *true*.
13+
The real-valued frequency, in Hz, at which ``navsat_transform_node`` checks for new `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ messages, and publishes filtered `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ when ``publish_filtered_gps`` is set to *true*.
1414

1515
~delay
1616
^^^^^^
@@ -30,7 +30,7 @@ If this is *true*, the `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html
3030

3131
~publish_filtered_gps
3232
^^^^^^^^^^^^^^^^^^^^^
33-
If *true*, ``navsat_transform_node`` will also transform your robot's world frame (e.g., *map*) position back to GPS coordinates, and publish a `sensor_msgs/NavSatFix.html <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message on the ``/gps/filtered`` topic.
33+
If *true*, ``navsat_transform_node`` will also transform your robot's world frame (e.g., *map*) position back to GPS coordinates, and publish a `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message on the ``/gps/filtered`` topic.
3434

3535
~broadcast_utm_transform
3636
^^^^^^^^^^^^^^^^^^^^^^^^
@@ -49,17 +49,17 @@ If *true*, ``navsat_transform_node`` will wait to get a datum from either:
4949

5050
Subscribed Topics
5151
=================
52-
* ``imu/data`` A `sensor_msgs/Imu.html <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message with orientation data
52+
* ``imu/data`` A `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message with orientation data
5353

5454
* ``odometry/filtered`` A `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message of your robot's current position. This is needed in the event that your first GPS reading comes after your robot has attained some non-zero pose.
5555

56-
* ``gps/fix`` A `sensor_msgs/NavSatFix.html <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing your robot's GPS coordinates
56+
* ``gps/fix`` A `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing your robot's GPS coordinates
5757

5858
Published Topics
5959
================
6060
* ``odometry/gps`` A `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message containing the GPS coordinates of your robot, transformed into its world coordinate frame. This message can be directly fused into ``robot_localization``'s state estimation nodes.
6161

62-
* ``gps/filtered`` (optional) A `sensor_msgs/NavSatFix.html <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing your robot's world frame position, transformed into GPS coordinates
62+
* ``gps/filtered`` (optional) A `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing your robot's world frame position, transformed into GPS coordinates
6363

6464
Published Transforms
6565
====================

0 commit comments

Comments
 (0)