Skip to content

Commit 3dbd48a

Browse files
ayrton04mabelzhangtogaen
authored
ROS1 recent feature port (#613)
* navsat_transform diagram to address #550 (#570) * add diagram for navsat_transform Signed-off-by: Mabel Zhang <[email protected]> * add diagram to tutorial Signed-off-by: Mabel Zhang <[email protected]> * Fix frame id of imu in differential mode, closes #482 * Added local Cartesian option to navsat_transform * Fix navsat_transform issue with starting on uneven terrain * Fix typo in navsat_transform_node.rst (#588) "prodives" -> "provides" * Fix sign error in dFY_dP in transfer function jacobian * Making repeated state publication optional (#595) * PR feedback * Fixing build issues * Fixing stamp issues * Linting and uncrustifying Co-authored-by: Mabel Zhang <[email protected]> Co-authored-by: Jeffrey Kane Johnson <[email protected]>
1 parent 3949cba commit 3dbd48a

15 files changed

+373
-172
lines changed

CMakeLists.txt

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

34+
# Geographiclib installs FindGeographicLib.cmake to this non-standard location
35+
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "/usr/share/cmake/geographiclib/")
36+
find_package(GeographicLib REQUIRED COMPONENTS STATIC)
37+
3438
find_package(PkgConfig REQUIRED)
3539
pkg_check_modules(YAML_CPP yaml-cpp)
3640

@@ -95,6 +99,7 @@ add_executable(
9599

96100
target_link_libraries(
97101
${library_name}
102+
${GeographicLib_LIBRARIES}
98103
${EIGEN3_LIBRARIES}
99104
${YAML_CPP_LIBRARIES}
100105
)
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: 14 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,14 @@ This is just a suggestion, however, and users are free to fuse the GPS data into
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

@@ -129,22 +137,22 @@ 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

144152
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

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

include/robot_localization/navsat_transform.hpp

Lines changed: 40 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,9 @@
3737
#include <robot_localization/srv/to_ll.hpp>
3838
#include <robot_localization/srv/from_ll.hpp>
3939

40+
#include <Eigen/Dense>
41+
#include <GeographicLib/Geocentric.hpp>
42+
#include <GeographicLib/LocalCartesian.hpp>
4043
#include <nav_msgs/msg/odometry.hpp>
4144
#include <rclcpp/rclcpp.hpp>
4245
#include <sensor_msgs/msg/imu.hpp>
@@ -46,7 +49,6 @@
4649
#include <tf2_ros/static_transform_broadcaster.h>
4750
#include <tf2_ros/transform_listener.h>
4851

49-
#include <Eigen/Dense>
5052
#include <memory>
5153
#include <string>
5254

@@ -73,7 +75,7 @@ class NavSatTransform : public rclcpp::Node
7375
void transformCallback();
7476

7577
/**
76-
* @brief Computes the transform from the UTM frame to the odom frame
78+
* @brief Computes the transform from the Cartesian frame to the odom frame
7779
*/
7880
void computeTransform();
7981

@@ -98,13 +100,13 @@ class NavSatTransform : public rclcpp::Node
98100
std::shared_ptr<robot_localization::srv::FromLL::Response> response);
99101

100102
/**
101-
* @brief Given the pose of the navsat sensor in the UTM frame, removes the
102-
* offset from the vehicle's centroid and returns the UTM-frame pose of said
103+
* @brief Given the pose of the navsat sensor in the Cartesian frame, removes the
104+
* offset from the vehicle's centroid and returns the Cartesian-frame pose of said
103105
* centroid.
104106
*/
105-
void getRobotOriginUtmPose(
106-
const tf2::Transform & gps_utm_pose,
107-
tf2::Transform & robot_utm_pose,
107+
void getRobotOriginCartesianPose(
108+
const tf2::Transform & gps_cartesian_pose,
109+
tf2::Transform & robot_cartesian_pose,
108110
const rclcpp::Time & transform_time);
109111

110112
/**
@@ -162,10 +164,10 @@ class NavSatTransform : public rclcpp::Node
162164
void setTransformOdometry(const nav_msgs::msg::Odometry::SharedPtr & msg);
163165

164166
/**
165-
* @brief Transforms the passed in pose from utm to map frame
166-
* @param[in] utm_pose the pose in utm frame to use to transform
167+
* @brief Transforms the passed in pose from Cartesian to map frame
168+
* @param[in] cartesian_pose the pose in Cartesian frame to use to transform
167169
*/
168-
nav_msgs::msg::Odometry utmToMap(const tf2::Transform & utm_pose) const;
170+
nav_msgs::msg::Odometry cartesianToMap(const tf2::Transform & cartesian_pose) const;
169171

170172
/**
171173
* @brief Transforms the passed in point from map frame to lat/long
@@ -184,15 +186,15 @@ class NavSatTransform : public rclcpp::Node
184186
std::string base_link_frame_id_;
185187

186188
/**
187-
* @brief Whether or not we broadcast the UTM transform
189+
* @brief Whether or not we broadcast the Cartesian transform
188190
*/
189-
bool broadcast_utm_transform_;
191+
bool broadcast_cartesian_transform_;
190192

191193
/**
192-
* @brief Whether to broadcast the UTM transform as parent frame, default as
194+
* @brief Whether to broadcast the Cartesian transform as parent frame, default as
193195
* child
194196
*/
195-
bool broadcast_utm_transform_as_parent_frame_;
197+
bool broadcast_cartesian_transform_as_parent_frame_;
196198

197199
/**
198200
* @brief TimerBase for publish callback
@@ -271,14 +273,14 @@ class NavSatTransform : public rclcpp::Node
271273
Eigen::MatrixXd latest_odom_covariance_;
272274

273275
/**
274-
* @brief Covariance for most recent GPS/UTM data
276+
* @brief Covariance for most recent GPS/UTM/LocalCartesian data
275277
*/
276-
Eigen::MatrixXd latest_utm_covariance_;
278+
Eigen::MatrixXd latest_cartesian_covariance_;
277279

278280
/**
279-
* @brief Latest GPS data, stored as UTM coords
281+
* @brief Latest GPS data, stored as Cartesian coords
280282
*/
281-
tf2::Transform latest_utm_pose_;
283+
tf2::Transform latest_cartesian_pose_;
282284

283285
/**
284286
* @brief Latest odometry pose data
@@ -349,15 +351,24 @@ class NavSatTransform : public rclcpp::Node
349351
tf2::Duration transform_timeout_;
350352

351353
/**
352-
* @brief Holds the UTM pose that is used to compute the transform
354+
* @brief Holds the Cartesian (UTM or local ENU) pose that is used to compute the transform
353355
*/
354-
tf2::Transform transform_utm_pose_;
356+
tf2::Transform transform_cartesian_pose_;
355357

356358
/**
357359
* @brief Latest IMU orientation
358360
*/
359361
tf2::Transform transform_world_pose_;
360362

363+
/**
364+
* @brief Whether we use a Local Cartesian (tangent plane ENU) or the UTM coordinates as our cartesian
365+
*/
366+
bool use_local_cartesian_;
367+
368+
//! @brief Local Cartesian projection around gps origin
369+
//!
370+
GeographicLib::LocalCartesian gps_local_cartesian_;
371+
361372
/**
362373
* @brief Whether we get our datum from the first GPS message or from the
363374
* set_datum service/parameter
@@ -370,32 +381,32 @@ class NavSatTransform : public rclcpp::Node
370381
bool use_odometry_yaw_;
371382

372383
/**
373-
* @brief Used for publishing the static world_frame->utm transform
384+
* @brief Used for publishing the static world_frame->cartesian transform
374385
*/
375-
tf2_ros::StaticTransformBroadcaster utm_broadcaster_;
386+
tf2_ros::StaticTransformBroadcaster cartesian_broadcaster_;
376387

377388
/**
378389
* @brief UTM's meridian convergence
379390
*
380-
* Angle between projected meridian (True North) and UTM's grid Y-axis.
381-
* For UTM projection (Ellipsoidal Transverse Mercator) it is zero on the
391+
* Angle between projected meridian (True North) and Cartesian's grid Y-axis.
392+
* For Cartesian projection (Ellipsoidal Transverse Mercator) it is zero on the
382393
* equator and non-zero everywhere else. It increases as the poles are
383394
* approached or as we're getting farther from central meridian.
384395
*/
385396
double utm_meridian_convergence_;
386397

387398
/**
388-
* @brief Holds the UTM->odom transform
399+
* @brief Holds the cartesian->odom transform
389400
*/
390-
tf2::Transform utm_world_transform_;
401+
tf2::Transform cartesian_world_transform_;
391402

392403
/**
393-
* @brief Holds the odom->UTM transform for filtered GPS broadcast
404+
* @brief Holds the odom->Cartesian transform for filtered GPS broadcast
394405
*/
395-
tf2::Transform utm_world_trans_inverse_;
406+
tf2::Transform cartesian_world_trans_inverse_;
396407

397408
/**
398-
* @brief UTM zone as determined after transforming GPS message
409+
* @brief Cartesian zone as determined after transforming GPS message
399410
*/
400411
std::string utm_zone_;
401412

include/robot_localization/ros_filter.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -525,6 +525,9 @@ class RosFilter : public rclcpp::Node
525525
//! @brief Whether the filter is enabled or not. See disabledAtStartup_.
526526
bool enabled_;
527527

528+
//! @brief Whether we'll allow old measurements to cause a re-publication of the updated state
529+
bool permit_corrected_publication_;
530+
528531
//! @brief The max (worst) dynamic diagnostic level.
529532
//!
530533
int dynamic_diag_error_level_;
@@ -595,6 +598,10 @@ class RosFilter : public rclcpp::Node
595598
//!
596599
rclcpp::Time last_diag_time_;
597600

601+
//! @brief The time of the most recent published state
602+
//!
603+
rclcpp::Time last_published_stamp_;
604+
598605
//! @brief We process measurements by queueing them up in
599606
//! callbacks and processing them all at once within each
600607
//! iteration

package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
<depend>geometry_msgs</depend>
2626
<depend>diagnostic_msgs</depend>
2727
<depend>diagnostic_updater</depend>
28+
<depend>geographiclib</depend>
2829
<depend>nav_msgs</depend>
2930
<build_depend>rclcpp</build_depend>
3031
<build_depend>rmw_implementation</build_depend>

0 commit comments

Comments
 (0)