You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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.
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*.
162
162
163
163
If you have any questions about this tutorial, please feel free to ask questions on `answers.ros.org <http://answers.ros.org>`_.
Copy file name to clipboardExpand all lines: doc/navsat_transform_node.rst
+34-8Lines changed: 34 additions & 8 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -28,13 +28,19 @@ Your IMU should read 0 for yaw when facing east. If it doesn't, enter the offset
28
28
^^^^^^^^^^^^^^
29
29
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.
30
30
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
+
31
35
~publish_filtered_gps
32
36
^^^^^^^^^^^^^^^^^^^^^
33
37
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.
34
38
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.
38
44
39
45
~use_odometry_yaw
40
46
^^^^^^^^^^^^^^^^^
@@ -47,15 +53,27 @@ If *true*, ``navsat_transform_node`` will wait to get a datum from either:
47
53
* The ``datum`` parameter
48
54
* The ``set_datum`` service
49
55
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.
54
62
55
63
~transform_timeout
56
64
^^^^^^^^^^^^^^^^^^
57
65
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
66
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
+
59
77
Subscribed Topics
60
78
=================
61
79
* ``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
72
90
73
91
Published Transforms
74
92
====================
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.
0 commit comments