Skip to content

Commit 552877a

Browse files
mabelzhangayrton04striderathallerodgavanderhoorn
authored
Port to Dashing: melodic-devel 2.6.3 to current (#530)
* Fixing Euler body-to-world transformations (cherry picked from commit 58bef05) * fix RLE/RLL tests * Enabling the user to override the output child_frame_id (cherry picked from commit f642190) * Add const& to catch values to prevent the error: catching polymorphic type ‘class tf2::TransformException’ by value And ZoneNumber by 0x3fU to prevent error: directive output may be truncated writing between 1 and 11 bytes into a region of size 4 (cherry picked from commit c1963c3) * Rename odomBaseLinkTrans to baseLinkOdomTrans Adhere to the naming convention <fromFrame><toFrame>Trans used for worldBaseLinkTrans and mapOdomTrans. (cherry picked from commit 17d4f10) * Enable build optimisations if no build type configured. The selected build type can have a significant influence on processor usage (tenths of %). As setting a build type is often forgotten by users, from-source builds of robot_localization on resource constraint platforms can run into issues of low update rates, starvation and issues with stability. If a build type is configured (on the ROS buildfarm fi), the added stanzas respect it and do not overwrite it. If nothing is configured, a warning is printed and the CMake-standard `RelWithDebInfo` type is configured. (cherry picked from commit cc93cef) * fix differential init typo, compiler warning * Add broadcast_utm_transform_as_parent_frame (cherry picked from commit e8deb5d) * Fixing title underline (cherry picked from commit da80adf) * Change note about transform publishing (cherry picked from commit 0eecd5f) * Meridian convergence adjustment added to navsat_transform. (cherry picked from commit 2b57df6) * Add missing undocumented params (cherry picked from commit 2585e9f) * Fix bug with tf_prefix (cherry picked from commit 492c494) * Created service for converting to / from lat long (cherry picked from commit fbd3a72) * Fixed linting errors. (cherry picked from commit 46396c0) * Refactored common conversion methods out (cherry picked from commit 1efe3a3) * Remove unused variable utm_odom_tf_yaw_ for clang compatibility (cherry picked from commit 2f0289d) * Mask IMU update vector to ignore position and linear velocity * They are both not contained in sensor_msgs/Imu but so far were still introduced if the param in the config file was set to true (cherry picked from commit 0d32daf) * Warning log output if for invalid IMU config settings (cherry picked from commit e2f75c3) * Set the filtered gps frame_id to base_link This is actually the frame_id of the information, not the 'gps' frame which might not even exist (cherry picked from commit 791953a) * Log initial pose once and continue with debug streams (cherry picked from commit a59e1e5) * Skip the debug log (cherry picked from commit 0e6cf56) * linter * alphabetize cmake srv list Co-authored-by: Tom Moore <[email protected]> Co-authored-by: Matthew Jones <[email protected]> Co-authored-by: thallerod <[email protected]> Co-authored-by: G.A. vd. Hoorn <[email protected]> Co-authored-by: diasdm <[email protected]> Co-authored-by: Pavlo Kolomiiets <[email protected]> Co-authored-by: Charles Brian Quinn <[email protected]> Co-authored-by: oswinso <[email protected]> Co-authored-by: Timon Engelke <[email protected]> Co-authored-by: Jonathan Huber <[email protected]> Co-authored-by: Tim Clephas <[email protected]>
1 parent 3c93104 commit 552877a

15 files changed

+350
-117
lines changed

CMakeLists.txt

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,17 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
99
add_compile_options(-Wall -Wextra -Wpedantic)
1010
endif()
1111

12+
if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE)
13+
message("${PROJECT_NAME}: You did not request a specific build type: selecting 'RelWithDebInfo'.")
14+
set(CMAKE_BUILD_TYPE RelWithDebInfo)
15+
endif()
16+
1217
find_package(ament_cmake REQUIRED)
1318
find_package(rcl REQUIRED)
1419
find_package(rclcpp REQUIRED)
15-
find_package(geographic_msgs REQUIRED)
1620
find_package(diagnostic_msgs REQUIRED)
1721
find_package(diagnostic_updater REQUIRED)
22+
find_package(geographic_msgs REQUIRED)
1823
find_package(geometry_msgs REQUIRED)
1924
find_package(nav_msgs REQUIRED)
2025
find_package(rosidl_default_generators REQUIRED)
@@ -32,10 +37,12 @@ pkg_check_modules(YAML_CPP yaml-cpp)
3237
set(library_name rl_lib)
3338

3439
rosidl_generate_interfaces(${PROJECT_NAME}
40+
"srv/FromLL.srv"
3541
"srv/GetState.srv"
3642
"srv/SetDatum.srv"
3743
"srv/SetPose.srv"
3844
"srv/ToggleFilterProcessing.srv"
45+
"srv/ToLL.srv"
3946
DEPENDENCIES
4047
builtin_interfaces
4148
geometry_msgs

doc/navsat_transform_node.rst

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,15 @@ If *true*, ``navsat_transform_node`` will wait to get a datum from either:
4747
* The ``datum`` parameter
4848
* The ``set_datum`` service
4949

50+
~broadcast_utm_transform_as_parent_frame
51+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
52+
If *true*, ``navsat_transform_node`` will publish the utm->world_frame transform instead of the world_frame->utm transform.
53+
Note that for the transform to be published ``broadcast_utm_transform`` also has to be set to *true*.
54+
55+
~transform_timeout
56+
^^^^^^^^^^^^^^^^^^
57+
This parameter specifies how long we would like to wait if a transformation is not available yet. Defaults to 0 if not set. The value 0 means we just get us the latest available (see ``tf2`` implementation) transform.
58+
5059
Subscribed Topics
5160
=================
5261
* ``imu/data`` A `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message with orientation data
@@ -63,4 +72,4 @@ Published Topics
6372

6473
Published Transforms
6574
====================
66-
* ``world_frame->utm`` (optional) - If the ``broadcast_utm_transform`` parameter is set to *true*, ``navsat_transform_node`` calculates a transform from the *utm* frame to the ``frame_id`` of the input odometry data. By default, the *utm* frame is published as a child of the odometry frame by using the inverse transform. With use of the ``broadcast_utm_as_parent_frame`` parameter, the *utm* frame will be published as a parent of the odometry frame. This is useful if you have multiple robots within one TF tree.
75+
* ``world_frame->utm`` (optional) - If the ``broadcast_utm_transform`` parameter is set to *true*, ``navsat_transform_node`` calculates a transform from the *utm* frame to the ``frame_id`` of the input odometry data. By default, the *utm* frame is published as a child of the odometry frame by using the inverse transform. With use of the ``broadcast_utm_transform_as_parent_frame`` parameter, the *utm* frame will be published as a parent of the odometry frame. This is useful if you have multiple robots within one TF tree.

doc/state_estimation_nodes.rst

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,21 +43,23 @@ Specific parameters:
4343
* ``~map_frame``
4444
* ``~odom_frame``
4545
* ``~base_link_frame``
46+
* ``~base_link_output_frame``
4647
* ``~world_frame``
4748

4849
These parameters define the operating "mode" for ``robot_localization``. `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 *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 these parameters:
4950

5051
1. Set the ``map_frame``, ``odom_frame``, and ``base_link_frame`` parameters to the appropriate frame names for your system.
5152

5253
.. note:: 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``.
54+
.. note:: If you are running multiple EKF instances and would like to "override" the output transform and message to have this frame for its ``child_frame_id``, you may set this. The ``base_link_output_frame`` is optional and will default to the ``base_link_frame``. This helps to enable disconnected TF trees when multiple EKF instances are being run. When the final state is computed, we "override" the output transform and message to have this frame for its ``child_frame_id``.
5355

5456
2. If you are only 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 the state estimation nodes in ``robot_localization``, and the most common use for it.
5557
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:
5658

5759
i. Set your ``world_frame`` to your ``map_frame`` value
5860
ii. **Make sure** something else is generating the *odom->base_link* transform. This can even be another instance of a ``robot_localization`` state estimation node. However, that instance should *not* fuse the global data.
5961

60-
The default values for ``map_frame``, ``odom_frame``, and ``base_link_frame`` are *map*, *odom,* and *base_link,* respectively. The ``world_frame`` parameter defaults to the value of ``odom_frame``.
62+
The default values for ``map_frame``, ``odom_frame``, and ``base_link_frame`` are *map*, *odom,* and *base_link,* respectively. The ``base_link_output_frame`` parameter defaults to the value of ``base_link_frame``. The ``world_frame`` parameter defaults to the value of ``odom_frame``.
6163

6264
~transform_time_offset
6365
^^^^^^^^^^^^^^^^^^^^^^
@@ -286,6 +288,14 @@ The estimate covariance, commonly denoted *P*, defines the error in the current
286288
^^^^^^^^^^^^^^^^^^^
287289
If set to *true* and ``ros::Time::isSimTime()`` is *true*, the filter will reset to its uninitialized state when a jump back in time is detected on a topic. This is useful when working with bag data, in that the bag can be restarted without restarting the node.
288290

291+
~predict_to_current_time
292+
^^^^^^^^^^^^^^^^^^^^^^^^
293+
If set to *true*, the filter predicts and corrects up to the time of the latest measurement (by default) but will now also predict up to the current time step.
294+
295+
~disabled_at_startup
296+
^^^^^^^^^^^^^^^^^^^^
297+
If set to *true* will not run the filter on start.
298+
289299
Node-specific Parameters
290300
------------------------
291301
The standard and advanced parameters are common to all state estimation nodes in ``robot_localization``. This section details parameters that are unique to their respective state estimation nodes.
@@ -319,4 +329,4 @@ Published Transforms
319329
Services
320330
========
321331

322-
* ``set_pose`` - By issuing a `geometry_msgs/PoseWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html>`_ message to the ``set_pose`` topic, users can manually set the state of the filter. This is useful for resetting the filter during testing, and allows for interaction with ``rviz``. Alternatively, the state estimation nodes advertise a ``SetPose`` service, whose type is `robot_localization/SetPose <http://docs.ros.org/api/robot_localization/html/srv/SetPose.html>`_.rejection
332+
* ``set_pose`` - By issuing a `geometry_msgs/PoseWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html>`_ message to the ``set_pose`` topic, users can manually set the state of the filter. This is useful for resetting the filter during testing, and allows for interaction with ``rviz``. Alternatively, the state estimation nodes advertise a ``SetPose`` service, whose type is `robot_localization/SetPose <http://docs.ros.org/api/robot_localization/html/srv/SetPose.html>`_.

include/robot_localization/filter_common.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,7 @@ const int POSE_SIZE = 6;
9090
const int TWIST_SIZE = 6;
9191
const int POSITION_SIZE = 3;
9292
const int ORIENTATION_SIZE = 3;
93+
const int LINEAR_VELOCITY_SIZE = 3;
9394
const int ACCELERATION_SIZE = 3;
9495

9596
/**

include/robot_localization/navsat_conversions.hpp

Lines changed: 52 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -204,13 +204,17 @@ static inline char UTMLetterDesignator(double Lat)
204204
* East Longitudes are positive, West longitudes are negative.
205205
* North latitudes are positive, South latitudes are negative
206206
* Lat and Long are in fractional degrees
207+
* Meridian convergence is computed as for Spherical Transverse Mercator,
208+
* which gives quite good approximation.
209+
*
210+
* @param[out] gamma meridian convergence at point (degrees).
207211
*
208212
* Written by Chuck Gantz- [email protected]
209213
*/
210214
static inline void LLtoUTM(
211215
const double Lat, const double Long,
212216
double & UTMNorthing, double & UTMEasting,
213-
std::string & UTMZone)
217+
std::string & UTMZone, double & gamma)
214218
{
215219
double a = WGS84_A;
216220
double eccSquared = UTM_E2;
@@ -253,7 +257,9 @@ static inline void LLtoUTM(
253257

254258
// Compute the UTM Zone from the latitude and longitude
255259
char zone_buf[] = {0, 0, 0, 0};
256-
snprintf(zone_buf, sizeof(zone_buf), "%d%c", ZoneNumber,
260+
// We &0x3fU to let GCC know the size of ZoneNumber. In this case, it's under
261+
// 63 (6bits)
262+
snprintf(zone_buf, sizeof(zone_buf), "%d%c", ZoneNumber & 0x3fU,
257263
UTMLetterDesignator(Lat));
258264
UTMZone = std::string(zone_buf);
259265

@@ -290,25 +296,49 @@ static inline void LLtoUTM(
290296
(61 - 58 * T + T * T + 600 * C - 330 * eccPrimeSquared) * A *
291297
A * A * A * A * A / 720)));
292298

299+
gamma = atan(tan(LongRad - LongOriginRad) * sin(LatRad)) * DEGREES_PER_RADIAN;
300+
293301
if (Lat < 0) {
294302
// 10000000 meter offset for southern hemisphere
295303
UTMNorthing += 10000000.0;
296304
}
297305
}
298306

307+
/**
308+
* Convert lat/long to UTM coords. Equations from USGS Bulletin 1532
309+
*
310+
* East Longitudes are positive, West longitudes are negative.
311+
* North latitudes are positive, South latitudes are negative
312+
* Lat and Long are in fractional degrees
313+
*
314+
* Written by Chuck Gantz- [email protected]
315+
*/
316+
static inline void LLtoUTM(
317+
const double Lat, const double Long,
318+
double & UTMNorthing, double & UTMEasting,
319+
std::string & UTMZone)
320+
{
321+
double gamma;
322+
LLtoUTM(Lat, Long, UTMNorthing, UTMEasting, UTMZone, gamma);
323+
}
324+
299325
/**
300326
* Converts UTM coords to lat/long. Equations from USGS Bulletin 1532
301327
*
302328
* East Longitudes are positive, West longitudes are negative.
303329
* North latitudes are positive, South latitudes are negative
304330
* Lat and Long are in fractional degrees.
331+
* Meridian convergence is computed as for Spherical Transverse Mercator,
332+
* which gives quite good approximation.
333+
*
334+
* @param[out] gamma meridian convergence at point (degrees).
305335
*
306336
* Written by Chuck Gantz- [email protected]
307337
*/
308338
static inline void UTMtoLL(
309339
const double UTMNorthing, const double UTMEasting,
310340
const std::string & UTMZone, double & Lat,
311-
double & Long)
341+
double & Long, double & gamma)
312342
{
313343
double k0 = UTM_K0;
314344
double a = WGS84_A;
@@ -367,6 +397,25 @@ static inline void UTMtoLL(
367397
D * D * D * D * D / 120) /
368398
cos(phi1Rad));
369399
Long = LongOrigin + Long * DEGREES_PER_RADIAN;
400+
401+
gamma = atan(tanh(x / (k0 * a)) * tan(y / (k0 * a))) * DEGREES_PER_RADIAN;
402+
}
403+
404+
/**
405+
* Converts UTM coords to lat/long. Equations from USGS Bulletin 1532
406+
*
407+
* East Longitudes are positive, West longitudes are negative.
408+
* North latitudes are positive, South latitudes are negative
409+
* Lat and Long are in fractional degrees.
410+
*
411+
* Written by Chuck Gantz- [email protected]
412+
*/
413+
static inline void UTMtoLL(
414+
const double UTMNorthing, const double UTMEasting,
415+
const std::string & UTMZone, double & Lat, double & Long)
416+
{
417+
double gamma;
418+
UTMtoLL(UTMNorthing, UTMEasting, UTMZone, Lat, Long, gamma);
370419
}
371420

372421
} // namespace navsat_conversions

include/robot_localization/navsat_transform.hpp

Lines changed: 45 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@
3434
#define ROBOT_LOCALIZATION__NAVSAT_TRANSFORM_HPP_
3535

3636
#include <robot_localization/srv/set_datum.hpp>
37+
#include <robot_localization/srv/to_ll.hpp>
38+
#include <robot_localization/srv/from_ll.hpp>
3739

3840
#include <nav_msgs/msg/odometry.hpp>
3941
#include <rclcpp/rclcpp.hpp>
@@ -83,6 +85,18 @@ class NavSatTransform : public rclcpp::Node
8385
request,
8486
std::shared_ptr<robot_localization::srv::SetDatum::Response>);
8587

88+
//! @brief Callback for the to Lat Long service
89+
//!
90+
bool toLLCallback(
91+
const std::shared_ptr<robot_localization::srv::ToLL::Request> request,
92+
std::shared_ptr<robot_localization::srv::ToLL::Response> response);
93+
94+
//! @brief Callback for the from Lat Long service
95+
//!
96+
bool fromLLCallback(
97+
const std::shared_ptr<robot_localization::srv::FromLL::Request> request,
98+
std::shared_ptr<robot_localization::srv::FromLL::Response> response);
99+
86100
/**
87101
* @brief Given the pose of the navsat sensor in the UTM frame, removes the
88102
* offset from the vehicle's centroid and returns the UTM-frame pose of said
@@ -147,6 +161,20 @@ class NavSatTransform : public rclcpp::Node
147161
*/
148162
void setTransformOdometry(const nav_msgs::msg::Odometry::SharedPtr & msg);
149163

164+
/**
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+
*/
168+
nav_msgs::msg::Odometry utmToMap(const tf2::Transform & utm_pose) const;
169+
170+
/**
171+
* @brief Transforms the passed in point from map frame to lat/long
172+
* @param[in] point the point in map frame to use to transform
173+
*/
174+
void mapToLL(
175+
const tf2::Vector3 & point, double & latitude, double & longitude,
176+
double & altitude) const;
177+
150178
/**
151179
* @brief Frame ID of the robot's body frame
152180
*
@@ -171,6 +199,16 @@ class NavSatTransform : public rclcpp::Node
171199
*/
172200
rclcpp::Service<robot_localization::srv::SetDatum>::SharedPtr datum_srv_;
173201

202+
/**
203+
* @brief Service for to Lat Long
204+
*/
205+
rclcpp::Service<robot_localization::srv::ToLL>::SharedPtr to_ll_srv_;
206+
207+
/**
208+
* @brief Service for from Lat Long
209+
*/
210+
rclcpp::Service<robot_localization::srv::FromLL>::SharedPtr from_ll_srv_;
211+
174212
/**
175213
* @brief Navsatfix publisher
176214
*/
@@ -337,9 +375,14 @@ class NavSatTransform : public rclcpp::Node
337375
tf2_ros::StaticTransformBroadcaster utm_broadcaster_;
338376

339377
/**
340-
* @brief Stores the yaw we need to compute the transform
378+
* @brief UTM's meridian convergence
379+
*
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
382+
* equator and non-zero everywhere else. It increases as the poles are
383+
* approached or as we're getting farther from central meridian.
341384
*/
342-
double utm_odom_tf_yaw_;
385+
double utm_meridian_convergence_;
343386

344387
/**
345388
* @brief Holds the UTM->odom transform

include/robot_localization/ros_filter.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -554,6 +554,14 @@ class RosFilter : public rclcpp::Node
554554
//!
555555
std::string base_link_frame_id_;
556556

557+
//! @brief tf frame name for the robot's body frame
558+
//!
559+
//! When the final state is computed, we "override" the output transform and
560+
//! message to have this frame for its child_frame_id. This helps to enable
561+
//! disconnected TF trees when multiple EKF instances are being run.
562+
//!
563+
std::string base_link_output_frame_id_;
564+
557565
//! @brief tf frame name for the robot's map (world-fixed) frame
558566
//!
559567
std::string map_frame_id_;

0 commit comments

Comments
 (0)