Skip to content

Commit 9cde94f

Browse files
authored
ROS1 recent feature port (#613) (#648)
1 parent 2816e92 commit 9cde94f

15 files changed

+385
-186
lines changed

CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,10 @@ find_package(Eigen3 REQUIRED)
3232
find_package(Boost REQUIRED)
3333
find_package(yaml_cpp_vendor REQUIRED)
3434

35+
# Geographiclib installs FindGeographicLib.cmake to this non-standard location
36+
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "/usr/share/cmake/geographiclib/")
37+
find_package(GeographicLib REQUIRED COMPONENTS STATIC)
38+
3539
set(library_name rl_lib)
3640

3741
rosidl_generate_interfaces(${PROJECT_NAME}
@@ -93,6 +97,7 @@ add_executable(
9397

9498
target_link_libraries(
9599
${library_name}
100+
${GeographicLib_LIBRARIES}
96101
${EIGEN3_LIBRARIES}
97102
)
98103

File renamed without changes.
49.9 KB
Loading
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
\documentclass{standalone}
2+
\usepackage{tikz}
3+
\usetikzlibrary{positioning}
4+
5+
\begin{document}
6+
7+
\sffamily
8+
9+
\begin{tikzpicture}[>=stealth,
10+
node distance = 3cm,
11+
box/.style={shape=rectangle,draw,rounded corners},]
12+
% Nodes
13+
\node (wheel) [box] {Wheel Odometry};
14+
\node (imu) [box, right =of wheel]{IMU};
15+
\node (ekfLocal) [box, below =of wheel]{EKF Local};
16+
\node (ekfGlobal) [box, below =of imu]{EKF Global};
17+
\node (navsat) [box, right =7cm of ekfGlobal]{navsat\_transform};
18+
\node (gps) [box, above =of navsat]{GPS};
19+
% Coordinates for edges pointing to empty space
20+
\node (gpsF) [right =of navsat]{};
21+
\node (tfLocal) [below =of ekfLocal]{};
22+
\node (odomLocal) [left =of ekfLocal]{};
23+
\node (tfGlobal) [below =of ekfGlobal]{};
24+
% Edges
25+
\draw[->] (wheel.270) -- (ekfLocal.90);
26+
\draw[->] (wheel.315) -- (ekfGlobal.135)
27+
node [fill=white, pos=0.2, align=center] {\ttfamily"/wheel/odometry"\\nav\_msgs/Odometry};
28+
\draw[->] (imu.225) -- (ekfLocal.45);
29+
\draw[->] (imu.315) -- (navsat.135);
30+
\draw[->] (imu.270) -- (ekfGlobal.90)
31+
node [fill=white, pos=0.2, align=center] {\ttfamily"/imu/data"\\sensor\_msgs/Imu};
32+
\draw[->] (gps.270) -- (navsat.90)
33+
node [fill=white, pos=0.2, align=center] {\ttfamily"/gps/fix"\\sensor\_msgs/NavSatFix};
34+
\draw[->, transform canvas={yshift=1mm}] (ekfGlobal) -- (navsat)
35+
node [fill=white, above=1mm, pos=0.5, align=center] {\ttfamily"/odometry/filtered/global"\\nav\_msgs/Odometry};
36+
\draw[->, transform canvas={yshift=-1mm}] (navsat) -- (ekfGlobal)
37+
node [fill=white, below=1mm, pos=0.5, align=center] {\ttfamily"/odometry/gps"\\nav\_msgs/Odometry};
38+
% Outputs not cycled back into the graph
39+
\draw[->, dashed] (navsat) -- (gpsF)
40+
node [fill=white, above=1mm, pos=1.0, align=center] {\ttfamily"/gps/filtered"\\sensor\_msgs/NavSatFix};
41+
\draw[->, dashed] (ekfLocal) -- (tfLocal)
42+
node [fill=white, pos=0.7, align=center] {\ttfamily"/tf" odom -> base\\tf2\_msgs/TFMessage};
43+
\draw[->, dashed] (ekfLocal) -- (odomLocal)
44+
node [fill=white, above=1mm, pos=1.0, align=center] {\ttfamily"/odometry/filtered/local"\\nav\_msgs/Odometry};
45+
\draw[->, dashed] (ekfGlobal) -- (tfGlobal)
46+
node [fill=white, pos=0.7, align=center] {\ttfamily"/tf" map -> odom\\tf2\_msgs/TFMessage};
47+
\end{tikzpicture}
48+
49+
\end{document}

doc/integrating_gps.rst

Lines changed: 26 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -11,17 +11,25 @@ Notes on Fusing GPS Data
1111
Before beginning this tutorial, users should be sure to familiarize themselves with `REP-105 <http://www.ros.org/reps/rep-0105.html>`_. It is important for users to realize that using a position estimate that includes GPS data will likely be unfit for use by navigation modules, owing to the fact that GPS data is subject to discrete discontinuities ("jumps"). If you want to fuse data from a GPS into your position estimate, one potential solution is to do the following:
1212

1313
1. Run one instance of a ``robot_localization`` state estimation node that fuses only continuous data, such as odometry and IMU data. Set the ``world_frame`` parameter for this instance to the same value as the ``odom_frame`` parameter. Execute local path plans and motions in this frame.
14-
2. Run another instance of a ``robot_localization`` state estimation node that fuses all sources of data, including the GPS. Set the ``world_frame`` parameter for this instance to the same value as the ``map_frame`` parameter.
14+
2. Run another instance of a ``robot_localization`` state estimation node that fuses all sources of data, including the GPS. Set the ``world_frame`` parameter for this instance to the same value as the ``map_frame`` parameter.
1515

16-
This is just a suggestion, however, and users are free to fuse the GPS data into a single instance of a ``robot_localization`` state estimation node.
16+
This is just a suggestion, however, and users are free to fuse the GPS data into a single instance of a ``robot_localization`` state estimation node.
1717

1818
Using navsat_transform_node
1919
***************************
2020

21+
The diagram below illustrates an example setup:
22+
23+
.. image:: images/navsat_transform_workflow.png
24+
:width: 800px
25+
:align: center
26+
:alt: navsat_transform workflow
27+
28+
2129
Required Inputs
2230
===============
2331

24-
``navsat_transform_node`` requires three sources of information: the robot's current pose estimate in its world frame, an earth-referenced heading, and a geographic coordinate expressed as a latitude/longitude pair (with optional altitude).
32+
``navsat_transform_node`` requires three sources of information: the robot's current pose estimate in its world frame, an earth-referenced heading, and a geographic coordinate expressed as a latitude/longitude pair (with optional altitude).
2533

2634
These data can be obtained in three different ways:
2735

@@ -31,7 +39,7 @@ These data can be obtained in three different ways:
3139
* A `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message with an absolute (earth-referenced) heading.
3240
* A `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message that contains the robot's current position estimate in the frame specified by its start location (typically the output of a ``robot_localization`` state estimation node).
3341

34-
2. The datum (global frame origin) can be specified via the ``datum`` parameter.
42+
2. The datum (global frame origin) can be specified via the ``datum`` parameter.
3543

3644
.. note:: In order to use this mode, the ``wait_for_datum`` parameter must be set to *true*.
3745

@@ -41,15 +49,15 @@ These data can be obtained in three different ways:
4149
4250
<rosparam param="datum">[55.944904, -3.186693, 0.0, map, base_link]</rosparam>
4351
44-
The parameter order is ``latitude`` in decimal degrees, ``longitude`` in decimal degrees, ``heading`` in radians) the ``frame_id`` of your robot's world frame (i.e., the value of the ``world_frame`` parameter in a ``robot_localization`` state estimation node), and the ``frame_id`` of your robot's body frame (i.e., the value of the ``base_link_frame`` parameter in a ``robot_localization`` state estimation node). When this mode is used, the robot assumes that your robot's world frame origin is at the specified latitude and longitude and with a heading of :math:`0` (east).
52+
The parameter order is ``latitude`` in decimal degrees, ``longitude`` in decimal degrees, ``heading`` in radians) the ``frame_id`` of your robot's world frame (i.e., the value of the ``world_frame`` parameter in a ``robot_localization`` state estimation node), and the ``frame_id`` of your robot's body frame (i.e., the value of the ``base_link_frame`` parameter in a ``robot_localization`` state estimation node). When this mode is used, the robot assumes that your robot's world frame origin is at the specified latitude and longitude and with a heading of :math:`0` (east).
4553

46-
3. The datum can be set manually via the ``set_datum`` service and using the `robot_localization/SetDatum <http://docs.ros.org/api/robot_localization/html/srv/SetDatum.html>`_ service message.
54+
3. The datum can be set manually via the ``set_datum`` service and using the `robot_localization/SetDatum <http://docs.ros.org/api/robot_localization/html/srv/SetDatum.html>`_ service message.
4755

4856

4957
GPS Data
5058
^^^^^^^^
5159

52-
Please note that all development of ``navsat_transform_node`` was done using a Garmin 18x GPS unit, so there may be intricacies of the data generated by other units that need to be handled.
60+
Please note that all development of ``navsat_transform_node`` was done using a Garmin 18x GPS unit, so there may be intricacies of the data generated by other units that need to be handled.
5361

5462
The excellent `nmea_navsat_driver <http://wiki.ros.org/nmea_navsat_driver>`_ package provides the required `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message. Here is the ``nmea_navsat_driver`` launch file we'll use for this tutorial:
5563

@@ -110,9 +118,9 @@ Integration with ``robot_localization`` is straightforward at this point. Simply
110118
111119
<param name="odomN" value="/your_state_estimation_node_topic">
112120
113-
<rosparam param="odomN_config">[true, true, false,
114-
false, false, false,
115-
false, false, false,
121+
<rosparam param="odomN_config">[true, true, false,
122+
false, false, false,
123+
false, false, false,
116124
false, false, false,
117125
false, false, false]</rosparam>
118126
<param name="odomN_differential" value="false"/>
@@ -129,29 +137,27 @@ You should have no need to modify the ``_differential`` setting within the state
129137
Details
130138
=======
131139

132-
We'll start with a picture. Consider a robot that starts at some latitude and longitude and with some heading. We assume in this tutorial that the heading comes from an IMU that reads 0 when facing east, and increases according to the ROS spec (i.e., counter-clockwise). The remainder of this tutorial will refer to Figure 1:
140+
We'll start with a picture. Consider a robot that starts at some latitude and longitude and with some heading. We assume in this tutorial that the heading comes from an IMU that reads 0 when facing east, and increases according to the ROS spec (i.e., counter-clockwise). The remainder of this tutorial will refer to Figure 2:
133141

134-
.. image:: images/figure1.png
142+
.. image:: images/figure2.png
135143
:width: 800px
136144
:align: center
137-
:alt: Figure 1
145+
:alt: Figure 2
138146

139147

140-
`REP-105 <http://www.ros.org/reps/rep-0105.html>`_ suggests four coordinate frames: *base_link*, *odom*, *map*, and *earth*. *base_link* is the coordinate frame that is rigidly attached to the vehicle. The *odom* and *map* frames are world-fixed frames and generally have their origins at the vehicle's start position and orientation. The *earth* frame is used as a common reference frame for multiple map frames, and is not yet supported by ``navsat_transform_node``. Note that in Figure 1, the robot has just started (``t = 0``), and so its *base_link*, *odom*, and *map* frames are aligned. We can also define a coordinate frame for the UTM grid, which we will call *utm*. For the purposes of this tutorial, we will refer to the UTM grid coordinate frame as *utm*. Therefore, what we want to do is create a *utm*->*map* transform.
148+
`REP-105 <http://www.ros.org/reps/rep-0105.html>`_ suggests four coordinate frames: *base_link*, *odom*, *map*, and *earth*. *base_link* is the coordinate frame that is rigidly attached to the vehicle. The *odom* and *map* frames are world-fixed frames and generally have their origins at the vehicle's start position and orientation. The *earth* frame is used as a common reference frame for multiple map frames, and is not yet supported by ``navsat_transform_node``. Note that in Figure 2, the robot has just started (``t = 0``), and so its *base_link*, *odom*, and *map* frames are aligned. We can also define a coordinate frame for the UTM grid, which we will call *utm*. For the purposes of this tutorial, we will refer to the UTM grid coordinate frame as *utm*. Therefore, what we want to do is create a *utm*->*map* transform.
141149

142-
Referring to Figure 1, these ideas are (hopefully) made clear. The UTM origin is the :math:`(0_{UTM}, 0_{UTM})` point of the UTM zone that is associated with the robot's GPS location. The robot begins somewhere within the UTM zone at location :math:`(x_{UTM}, y_{UTM})`. The robot's initial orientation is some angle :math:`\theta` above the UTM grid's :math:`X`-axis. Our transform will therefore require that we know :math:`x_{UTM}, y_{UTM}` and :math:`\theta`.
150+
Referring to Figure 2, these ideas are (hopefully) made clear. The UTM origin is the :math:`(0_{UTM}, 0_{UTM})` point of the UTM zone that is associated with the robot's GPS location. The robot begins somewhere within the UTM zone at location :math:`(x_{UTM}, y_{UTM})`. The robot's initial orientation is some angle :math:`\theta` above the UTM grid's :math:`X`-axis. Our transform will therefore require that we know :math:`x_{UTM}, y_{UTM}` and :math:`\theta`.
143151

144-
We now need to convert our latitude and longitude to UTM coordinates. The UTM grid assumes that the :math:`X`-axis faces east, the :math:`Y`-axis faces (true) north, and the :math:`Z`-axis points up out of the ground. This complies with the right-handed coordinate frame as dictated by `REP-105 <http://www.ros.org/reps/rep-0105.html>`_. The REP also states that a yaw angle of :math:`0` means that we are facing straight down the :math:`X`-axis, and that the yaw increases counter-clockwise. ``navsat_transform_node`` assumes your heading data conforms to this standard. However, there are two factors that need to be considered:
152+
We now need to convert our latitude and longitude to UTM coordinates. The UTM grid assumes that the :math:`X`-axis faces east, the :math:`Y`-axis faces (true) north, and the :math:`Z`-axis points up out of the ground. This complies with the right-handed coordinate frame as dictated by `REP-105 <http://www.ros.org/reps/rep-0105.html>`_. The REP also states that a yaw angle of :math:`0` means that we are facing straight down the :math:`X`-axis, and that the yaw increases counter-clockwise. ``navsat_transform_node`` assumes your heading data conforms to this standard. However, there are two factors that need to be considered:
145153

146154
1. The IMU driver may not allow the user to apply the magnetic declination correction factor
147-
2. The IMU driver may incorrectly report :math:`0` when facing north, and not when facing east (even though its headings increase and decrease correctly). Fortunately, ``navsat_transform_node`` exposes two parameters to adddress these possible shortcomings in IMU data: ``magnetic_declination_radians`` and ``yaw_offset``. Referring to Figure 1, for an IMU that is currently measuring a yaw value of ``imu_yaw``,
155+
2. The IMU driver may incorrectly report :math:`0` when facing north, and not when facing east (even though its headings increase and decrease correctly). Fortunately, ``navsat_transform_node`` exposes two parameters to adddress these possible shortcomings in IMU data: ``magnetic_declination_radians`` and ``yaw_offset``. Referring to Figure 2, for an IMU that is currently measuring a yaw value of ``imu_yaw``,
148156

149157
:math:`yaw_{imu} = -\omega - offset_{yaw} + \theta`
150158

151159
:math:`\theta = yaw_{imu} + \omega + offset_{yaw}`
152160

153-
We now have a translation :math:`(x_{UTM}, y_{UTM})` and rotation :math:`\theta`, which we can use to create the required *utm* -> *map* transform. We use the transform to convert all future GPS positions into the robot's local coordinate frame. ``navsat_transform_node`` will also broadcast this transform if the ``broadcast_utm_transform`` parameter is set to *true*.
161+
We now have a translation :math:`(x_{UTM}, y_{UTM})` and rotation :math:`\theta`, which we can use to create the required *utm* -> *map* transform. We use the transform to convert all future GPS positions into the robot's local coordinate frame. ``navsat_transform_node`` will also broadcast this transform if the ``broadcast_utm_transform`` parameter is set to *true*.
154162

155163
If you have any questions about this tutorial, please feel free to ask questions on `answers.ros.org <http://answers.ros.org>`_.
156-
157-

doc/navsat_transform_node.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ The time, in seconds, to wait before calculating the transform from GPS coordina
1818

1919
~magnetic_declination_radians
2020
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
21-
Enter the magnetic declination for your location. If you don't know it, see `http://www.ngdc.noaa.gov/geomag-web <http://www.ngdc.noaa.gov/geomag-web>`_ (make sure to convert the value to radians). This parameter is needed if your IMU prodives its orientation with respect to the magnetic north.
21+
Enter the magnetic declination for your location. If you don't know it, see `http://www.ngdc.noaa.gov/geomag-web <http://www.ngdc.noaa.gov/geomag-web>`_ (make sure to convert the value to radians). This parameter is needed if your IMU provides its orientation with respect to the magnetic north.
2222

2323
~yaw_offset
2424
^^^^^^^^^^^

doc/state_estimation_nodes.rst

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -166,6 +166,14 @@ Starts the filter with the specified state. The state is given as a 15-D vector
166166
0.0, 0.0, 0.0,
167167
0.0, 0.0, 0.0]</rosparam>
168168
169+
~permit_corrected_publication
170+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
171+
When the state estimation nodes publish the state at time `t`, but then receive a measurement with a timestamp < `t`, they re-publish the corrected state, with the same time stamp as the previous publication. Setting this parameter to *false* disables that behavior. Defaults to *false*.
172+
173+
~print_diagnostics
174+
^^^^^^^^^^^^^^^^^^
175+
If true, the state estimation node will publish diagnostic messages to the ``/diagnostics`` topic. This is useful for debugging your configuration and sensor data.
176+
169177
~publish_tf
170178
^^^^^^^^^^^
171179
If *true*, the state estimation node will publish the transform from the frame specified by the ``world_frame`` parameter to the frame specified by the ``base_link_frame`` parameter. Defaults to *true*.
@@ -174,10 +182,6 @@ If *true*, the state estimation node will publish the transform from the frame s
174182
^^^^^^^^^^^^^^^^^^^^^
175183
If *true*, the state estimation node will publish the linear acceleration state. Defaults to *false*.
176184

177-
~print_diagnostics
178-
^^^^^^^^^^^^^^^^^^
179-
If true, the state estimation node will publish diagnostic messages to the ``/diagnostics`` topic. This is useful for debugging your configuration and sensor data.
180-
181185
Advanced Parameters
182186
-------------------
183187

0 commit comments

Comments
 (0)