Skip to content

Commit 532108f

Browse files
committed
Adding publishing of an REP-105 compliant ECEF transform
The navsat_transform_node can now publish an ecef earth frame. This is controlled using the parameters 'broadcast_earth_transform' and 'earth_frame_id'. Publishing the earth transform is only valid if use_local_cartesian is set to true.
1 parent b47541f commit 532108f

File tree

7 files changed

+415
-24
lines changed

7 files changed

+415
-24
lines changed

CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -268,6 +268,10 @@ if(BUILD_TESTING)
268268
target_include_directories(test_navsat_conversions PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src>")
269269
target_link_libraries(test_navsat_conversions ${library_name} ${GeographicLib_LIBRARIES})
270270

271+
#### EARTH CHAIN TESTS ####
272+
ament_add_gtest(test_earth_chain test/test_earth_chain.cpp)
273+
target_link_libraries(test_earth_chain ${library_name})
274+
271275
ament_add_gtest_executable(test_ros_robot_localization_listener
272276
test/test_ros_robot_localization_listener.cpp)
273277
target_link_libraries(test_ros_robot_localization_listener ${library_name})
@@ -303,6 +307,7 @@ if(BUILD_TESTING)
303307
#test_ekf_localization_node_bag3
304308
test_robot_localization_estimator
305309
test_navsat_conversions
310+
test_earth_chain
306311
test_ros_robot_localization_listener
307312
test_ros_robot_localization_listener_publisher
308313
#test_ukf_localization_node_bag1

doc/integrating_gps.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,6 @@ We now need to convert our latitude and longitude to UTM coordinates. The UTM gr
158158

159159
:math:`\theta = yaw_{imu} + \omega + offset_{yaw}`
160160

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*.
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_cartesian_transform`` parameter is set to *true*.
162162

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

doc/navsat_transform_node.rst

Lines changed: 34 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -28,13 +28,19 @@ Your IMU should read 0 for yaw when facing east. If it doesn't, enter the offset
2828
^^^^^^^^^^^^^^
2929
If this is *true*, the `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message produced by this node has its pose Z value set to 0.
3030

31+
~use_local_cartesian
32+
^^^^^^^^^^^^^^^^^^^^
33+
If this is *true*, the node uses a local East-North-Up (ENU) cartesian coordinate system centered at the GPS datum. If *false*, the node uses UTM coordinates. Defaults to *false* (UTM mode). Local cartesian mode is required for earth frame transform support.
34+
3135
~publish_filtered_gps
3236
^^^^^^^^^^^^^^^^^^^^^
3337
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.
3438

35-
~broadcast_utm_transform
36-
^^^^^^^^^^^^^^^^^^^^^^^^
37-
If this is *true*, ``navsat_transform_node`` will broadcast the transform between the UTM grid and the frame of the input odometry data. See Published Transforms below for more information.
39+
~broadcast_cartesian_transform
40+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
41+
If this is *true*, ``navsat_transform_node`` will broadcast the transform between the cartesian frame (UTM or local_enu) and the world frame. See Published Transforms below for more information.
42+
43+
.. note:: The legacy parameter name ``broadcast_utm_transform`` is deprecated but still supported for backward compatibility.
3844

3945
~use_odometry_yaw
4046
^^^^^^^^^^^^^^^^^
@@ -47,15 +53,27 @@ If *true*, ``navsat_transform_node`` will wait to get a datum from either:
4753
* The ``datum`` parameter
4854
* The ``set_datum`` service
4955

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*.
56+
~broadcast_cartesian_transform_as_parent_frame
57+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
58+
If *true*, ``navsat_transform_node`` will publish the cartesian->world_frame transform instead of the world_frame->cartesian transform.
59+
Note that for the transform to be published ``broadcast_cartesian_transform`` also has to be set to *true*.
60+
61+
.. note:: The legacy parameter name ``broadcast_utm_transform_as_parent_frame`` is deprecated but still supported for backward compatibility.
5462

5563
~transform_timeout
5664
^^^^^^^^^^^^^^^^^^
5765
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.
5866

67+
~earth_frame_id
68+
^^^^^^^^^^^^^^^
69+
The name of the ECEF earth frame for REP-105 compliant coordinate systems. Defaults to ``earth``. This frame represents the WGS-84 Earth-Centered Earth-Fixed coordinate system using ellipsoidal heights only (no geoid corrections).
70+
71+
~broadcast_earth_transform
72+
^^^^^^^^^^^^^^^^^^^^^^^^^^
73+
If *true*, ``navsat_transform_node`` will broadcast transforms that link the earth frame to the existing cartesian/world frames, enabling REP-105 compliant ECEF coordinate system support. The specific transform chain published depends on the ``broadcast_cartesian_transform`` and ``broadcast_cartesian_transform_as_parent_frame`` settings. Defaults to *false*.
74+
75+
.. note:: This parameter is only valid when ``use_local_cartesian`` is *true*. Earth frame transforms are not supported with UTM coordinates. If you attempt to set both ``broadcast_earth_transform: true`` and ``use_local_cartesian: false``, the node will log an error and disable the earth transform functionality.
76+
5977
Subscribed Topics
6078
=================
6179
* ``imu/data`` A `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message with orientation data
@@ -72,4 +90,12 @@ Published Topics
7290

7391
Published Transforms
7492
====================
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.
93+
* ``world_frame->cartesian`` (optional) - If the ``broadcast_cartesian_transform`` parameter is set to *true*, ``navsat_transform_node`` calculates a transform from the cartesian frame (UTM or local_enu) to the ``frame_id`` of the input odometry data. By default, the cartesian frame is published as a child of the world frame by using the inverse transform. With use of the ``broadcast_cartesian_transform_as_parent_frame`` parameter, the cartesian frame will be published as a parent of the world frame. This is useful if you have multiple robots within one TF tree.
94+
95+
* ``earth->world_frame/local_enu`` (optional) - If the ``broadcast_earth_transform`` parameter is set to *true*, and ``use_local_cartesian`` is set to *true*, ``navsat_transform_node`` publishes transforms that link the REP-105 compliant earth frame (ECEF WGS-84) to the existing coordinate frames. The child frame can be either the world_frame of local_enu dependent on other configurations. If ``broadcast_cartesian_transform`` is *false* or ``broadcast_cartesian_transform_as_parent_frame`` is *false*, then the child frame is set as the world_frame. Otherwise, the child frame is set to local_enu.
96+
97+
98+
Heights
99+
=======
100+
101+
All ECEF conversions use WGS-84 **ellipsoidal** heights. No geoid corrections are applied.

include/robot_localization/navsat_transform.hpp

Lines changed: 35 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -211,6 +211,13 @@ class NavSatTransform : public rclcpp::Node {
211211
*/
212212
void setManualDatum();
213213

214+
/**
215+
* @brief Computes earth to cartesian transform
216+
* @note Only valid when use_local_cartesian_ is true
217+
*/
218+
void computeEarthToCartesian(double lat0_deg, double lon0_deg, double h0_m);
219+
220+
214221
/**
215222
* @brief Frame ID of the robot's body frame
216223
*
@@ -439,9 +446,9 @@ class NavSatTransform : public rclcpp::Node {
439446
bool use_odometry_yaw_;
440447

441448
/**
442-
* @brief Used for publishing the static world_frame->cartesian transform
449+
* @brief Used for publishing static transforms
443450
*/
444-
tf2_ros::StaticTransformBroadcaster cartesian_broadcaster_;
451+
tf2_ros::StaticTransformBroadcaster tf_broadcaster_;
445452

446453
/**
447454
* @brief UTM's meridian convergence
@@ -505,6 +512,32 @@ class NavSatTransform : public rclcpp::Node {
505512
* can be set.
506513
*/
507514
geographic_msgs::msg::GeoPose manual_datum_geopose_;
515+
516+
/**
517+
* @brief Earth frame ID for ECEF coordinates
518+
*/
519+
std::string earth_frame_id_;
520+
521+
/**
522+
* @brief Whether or not we broadcast the earth transform
523+
* @note Only valid when use_local_cartesian_ is true.
524+
* Earth transforms are not supported with UTM coordinates.
525+
*/
526+
bool broadcast_earth_transform_;
527+
528+
529+
/**
530+
* @brief Transform from earth to cartesian (ECEF to local/UTM)
531+
* Note: This is the mathematical transform E2C, inverted when published to TF
532+
*/
533+
tf2::Transform earth_cartesian_transform_;
534+
535+
/**
536+
* @brief Origin GPS coordinates for earth frame computation
537+
*/
538+
double origin_latitude_;
539+
double origin_longitude_;
540+
double origin_altitude_;
508541
};
509542

510543
} // namespace robot_localization

params/navsat_transform.yaml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,3 +48,10 @@ navsat_transform_node:
4848
# and heading in radians. As navsat_transform_node assumes an ENU standard, a 0 heading corresponds to east.
4949
datum: [55.944904, -3.186693, 0.0]
5050

51+
# Earth frame ID for ECEF coordinates (REP-105 compliant). Defaults to "earth".
52+
earth_frame_id: "earth"
53+
54+
# If this is true, the transform earth->cartesian or earth->world transform is broadcast for use by other nodes.
55+
# This enables REP-105 compliant ECEF coordinate system support. Defaults to false.
56+
broadcast_earth_transform: false
57+

src/navsat_transform.cpp

Lines changed: 111 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -85,13 +85,18 @@ NavSatTransform::NavSatTransform(const rclcpp::NodeOptions & options)
8585
force_user_utm_(false),
8686
use_manual_datum_(false),
8787
use_odometry_yaw_(false),
88-
cartesian_broadcaster_(*this),
88+
tf_broadcaster_(*this),
8989
utm_meridian_convergence_(0.0),
9090
utm_zone_(0),
9191
northp_(true),
9292
world_frame_id_("odom"),
9393
yaw_offset_(0.0),
94-
zero_altitude_(false)
94+
zero_altitude_(false),
95+
earth_frame_id_("earth"),
96+
broadcast_earth_transform_(false),
97+
origin_latitude_(0.0),
98+
origin_longitude_(0.0),
99+
origin_altitude_(0.0)
95100
{
96101
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
97102
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf_buffer_);
@@ -145,6 +150,21 @@ NavSatTransform::NavSatTransform(const rclcpp::NodeOptions & options)
145150
broadcast_cartesian_transform_as_parent_frame_);
146151
}
147152

153+
earth_frame_id_ = this->declare_parameter("earth_frame_id", earth_frame_id_);
154+
broadcast_earth_transform_ = this->declare_parameter("broadcast_earth_transform",
155+
broadcast_earth_transform_);
156+
157+
// Validate parameter combinations
158+
if (broadcast_earth_transform_ && !use_local_cartesian_) {
159+
RCLCPP_ERROR(
160+
this->get_logger(),
161+
"Invalid parameter combination: broadcast_earth_transform=true requires "
162+
"use_local_cartesian=true. Earth frame transforms are only supported with local cartesian "
163+
"coordinates, not UTM. This setting will be ignored!");
164+
broadcast_earth_transform_ = false;
165+
}
166+
167+
148168
if (!this->get_clock()->started()) {
149169
RCLCPP_INFO(this->get_logger(), "Waiting for clock to start...");
150170
this->get_clock()->wait_until_started();
@@ -353,22 +373,61 @@ void NavSatTransform::computeTransform()
353373

354374
transform_good_ = true;
355375

356-
// Send out the (static) UTM transform in case anyone else would like to use
357-
// it.
376+
// Prepare vector of transforms to publish
377+
std::vector<geometry_msgs::msg::TransformStamped> transforms_to_publish;
378+
379+
// Add cartesian transform if requested
358380
if (broadcast_cartesian_transform_) {
359381
geometry_msgs::msg::TransformStamped cartesian_transform_stamped;
360382
cartesian_transform_stamped.header.stamp = this->now();
361-
std::string cartesian_frame_id = (use_local_cartesian_ ? "local_enu" : "utm");
362-
cartesian_transform_stamped.header.frame_id =
363-
(broadcast_cartesian_transform_as_parent_frame_ ? cartesian_frame_id : world_frame_id_);
364-
cartesian_transform_stamped.child_frame_id =
365-
(broadcast_cartesian_transform_as_parent_frame_ ? world_frame_id_ : cartesian_frame_id);
366-
cartesian_transform_stamped.transform =
367-
(broadcast_cartesian_transform_as_parent_frame_ ?
368-
tf2::toMsg(cartesian_world_trans_inverse_) : tf2::toMsg(cartesian_world_transform_));
383+
std::string const cartesian_frame_id =
384+
(use_local_cartesian_ ? "local_enu" : "utm");
385+
if (broadcast_cartesian_transform_as_parent_frame_) {
386+
cartesian_transform_stamped.header.frame_id = cartesian_frame_id;
387+
cartesian_transform_stamped.child_frame_id = world_frame_id_;
388+
cartesian_transform_stamped.transform = tf2::toMsg(cartesian_world_trans_inverse_);
389+
} else {
390+
cartesian_transform_stamped.header.frame_id = world_frame_id_;
391+
cartesian_transform_stamped.child_frame_id = cartesian_frame_id;
392+
cartesian_transform_stamped.transform = tf2::toMsg(cartesian_world_transform_);
393+
}
369394
cartesian_transform_stamped.transform.translation.z =
370395
(zero_altitude_ ? 0.0 : cartesian_transform_stamped.transform.translation.z);
371-
cartesian_broadcaster_.sendTransform(cartesian_transform_stamped);
396+
transforms_to_publish.push_back(cartesian_transform_stamped);
397+
}
398+
399+
// Add earth frame transforms if requested
400+
// Note: Only valid when use_local_cartesian_ is true (validated in constructor)
401+
if (broadcast_earth_transform_) {
402+
computeEarthToCartesian(origin_latitude_, origin_longitude_, origin_altitude_);
403+
404+
geometry_msgs::msg::TransformStamped earth_transform_stamped;
405+
406+
earth_transform_stamped.header.stamp = this->now();
407+
earth_transform_stamped.header.frame_id = earth_frame_id_;
408+
409+
// If cartesian -> world is published, then we public earth -> cartesian
410+
// Otherwise, we publish earth -> world
411+
if (broadcast_cartesian_transform_ &&
412+
broadcast_cartesian_transform_as_parent_frame_)
413+
{
414+
415+
earth_transform_stamped.child_frame_id = "local_enu";
416+
earth_transform_stamped.transform = tf2::toMsg(earth_cartesian_transform_.inverse());
417+
418+
} else {
419+
tf2::Transform const C2W = cartesian_world_transform_;
420+
tf2::Transform const E2W = C2W * earth_cartesian_transform_;
421+
422+
earth_transform_stamped.child_frame_id = world_frame_id_;
423+
earth_transform_stamped.transform = tf2::toMsg(E2W.inverse());
424+
}
425+
transforms_to_publish.push_back(earth_transform_stamped);
426+
}
427+
428+
// Publish all transforms in a single call
429+
if (!transforms_to_publish.empty()) {
430+
tf_broadcaster_.sendTransform(transforms_to_publish);
372431
}
373432
}
374433
}
@@ -948,6 +1007,11 @@ bool NavSatTransform::prepareGpsOdometry(nav_msgs::msg::Odometry * gps_odom)
9481007
void NavSatTransform::setTransformGps(
9491008
const sensor_msgs::msg::NavSatFix::SharedPtr & msg)
9501009
{
1010+
// Store origin coordinates for earth frame computation
1011+
origin_latitude_ = msg->latitude;
1012+
origin_longitude_ = msg->longitude;
1013+
origin_altitude_ = msg->altitude;
1014+
9511015
double cartesian_x {};
9521016
double cartesian_y {};
9531017
double cartesian_z {};
@@ -1038,4 +1102,38 @@ rcl_interfaces::msg::SetParametersResult NavSatTransform::parametersCallback(
10381102
return result;
10391103
}
10401104

1105+
void NavSatTransform::computeEarthToCartesian(double lat0_deg, double lon0_deg, double h0_m)
1106+
{
1107+
// This function should only be called when use_local_cartesian_ is true
1108+
// (validated in constructor)
1109+
1110+
GeographicLib::Geocentric geo(GeographicLib::Constants::WGS84_a(),
1111+
GeographicLib::Constants::WGS84_f());
1112+
double X0, Y0, Z0;
1113+
geo.Forward(lat0_deg, lon0_deg, h0_m, X0, Y0, Z0);
1114+
1115+
double sphi, cphi, slam, clam;
1116+
GeographicLib::Math::sincosd(lat0_deg, sphi, cphi);
1117+
GeographicLib::Math::sincosd(lon0_deg, slam, clam);
1118+
1119+
// ECEF -> ENU at datum (using GeographicLib's exact matrix layout)
1120+
tf2::Matrix3x3 R_ecef_to_enu(
1121+
-slam, clam, 0, // East axis
1122+
-clam * sphi, -slam * sphi, cphi, // North axis
1123+
clam * cphi, slam * cphi, sphi // Up axis
1124+
);
1125+
1126+
// Create transform to match LocalCartesian behavior
1127+
// LocalCartesian does: R * (input - origin)
1128+
// TF2 does: R * input + translation
1129+
// Therefore: translation = -R * origin
1130+
tf2::Vector3 origin_ecef(X0, Y0, Z0);
1131+
tf2::Vector3 translated_origin = -(R_ecef_to_enu * origin_ecef);
1132+
tf2::Transform E2C(R_ecef_to_enu, translated_origin);
1133+
1134+
// Store the transform (earth -> local_enu)
1135+
earth_cartesian_transform_ = E2C;
1136+
}
1137+
1138+
10411139
} // namespace robot_localization

0 commit comments

Comments
 (0)