Autoware.Auto
|
|
In order to work with GNSS output in localization module there is a need for a node that would transform the GNSS input into a metric pose. This node does exactly that.
The node subscribes to the GNSS messages and publishes autoware_auto_msgs::msg::RelativePositionWithCovarianceStamped
converted messages setting the covariance from the user-provided values.
This node implements a conversion from WGS 84 (latitude, longitude, height) measurement into an ECEF (earth-centered, earth-fixed) metric pose \([x, y, z]^\top\) following the following equations (given [latitude, longitude, height]
= \([\phi,\lambda,h]^\top\)):
\begin{aligned} x =& (N(\phi) + h) \cos\phi \cos\lambda\\ y =& (N(\phi) + h) \cos\phi \sin\lambda\\ z =& ((1 - e^2) N(\phi) + h) \sin\phi, \end{aligned}
where \(N(\phi) = \frac{a}{\sqrt{1 - e^2 \sin^2 \phi}}\). Here, \(a = 6378137\), and \(e^2 = 6.69437999014 \times 10^{−3}\).