Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
GNSSToMapConvertor.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2018-2021 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
18#include <wgs84_utils/proj_tools.h>
19#include <lanelet2_core/geometry/Point.h>
20#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
21
23{
25 std::string map_frame_id, std::string base_link_frame_id,
26 std::string heading_frame_id,rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger)
27 : pose_pub_(pose_pub)
28 , tf_lookup_(tf_lookup)
29 , map_frame_id_(map_frame_id)
30 , base_link_frame_id_(base_link_frame_id)
31 , heading_frame_id_(heading_frame_id)
32 , logger_(logger)
33{
34}
35
36void GNSSToMapConvertor::gnssFixCb(gps_msgs::msg::GPSFix::UniquePtr fix_msg)
37{
38 if (!baselink_in_sensor_) // Extract the assumed static transform between baselink and the sensor if it was not
39 // already optained
40 {
41 auto tf_msg = tf_lookup_(fix_msg->header.frame_id, base_link_frame_id_);
42 if (!tf_msg) // Failed to get transform
43 {
44 RCLCPP_WARN_STREAM(logger_->get_logger(),"Ignoring fix message: Could not locate static transform between "
45 << fix_msg->header.frame_id << " and " << base_link_frame_id_);
46 return;
47 }
48
49 tf2::Transform tf;
50 tf2::convert(tf_msg.get().transform, tf);
51
53 }
54
55 if (!sensor_in_ned_heading_rotation_) // Extract the assumed static transform between heading frame and the position
56 // sensor frame if it was not already optained
57 {
58 auto tf_msg = tf_lookup_(fix_msg->header.frame_id, heading_frame_id_);
59 if (!tf_msg) // Failed to get transform
60 {
61 RCLCPP_WARN_STREAM(logger_->get_logger(), "Ignoring fix message: Could not locate static transform between " << heading_frame_id_ << " and "
62 << fix_msg->header.frame_id);
63 return;
64 }
65
66 tf2::Transform tf;
67 tf2::convert(tf_msg.get().transform, tf);
68
69 if (tf.getOrigin().x() != 0.0 || tf.getOrigin().y() != 0.0 || tf.getOrigin().z() != 0.0)
70 {
71 RCLCPP_WARN_STREAM(logger_->get_logger(), "Heading frame does not have rotation only transform with sensor frame. The translation will not "
72 "be handled by the GNSS convertor");
73 }
74
75 sensor_in_ned_heading_rotation_ = tf.getRotation();
76 }
77
78 if (!map_projector_ || !ned_in_map_rotation_) // Check if map projection is available
79 {
80 RCLCPP_WARN_STREAM(logger_->get_logger(), "Ignoring fix message as no map projection has been recieved.");
81 return;
82 }
83
84 geometry_msgs::msg::PoseWithCovarianceStamped pose_msg =
86
87 geometry_msgs::msg::PoseStamped msg; // TODO until covariance is added drop it from the output
88 msg.header = pose_msg.header;
89 msg.header.frame_id = map_frame_id_;
90 msg.pose = pose_msg.pose.pose;
91
92 pose_pub_(msg);
93}
94
95void GNSSToMapConvertor::geoReferenceCallback(std_msgs::msg::String::UniquePtr geo_ref)
96{
97 if (georeference_ != geo_ref->data)
98 {
99 georeference_ = geo_ref->data;
100 map_projector_ = std::make_shared<lanelet::projection::LocalFrameProjector>(
101 geo_ref->data.c_str()); // Build projector from proj string
102
103 RCLCPP_INFO_STREAM(logger_->get_logger(), "Received map georeference: " << geo_ref->data);
104
105 std::string axis = wgs84_utils::proj_tools::getAxisFromProjString(geo_ref->data); // Extract axis for orientation calc
106
107 RCLCPP_INFO_STREAM(logger_->get_logger(), "Extracted Axis: " << axis);
108
109 ned_in_map_rotation_ = wgs84_utils::proj_tools::getRotationOfNEDFromProjAxis(axis); // Extract map rotation from axis
110
111 RCLCPP_INFO_STREAM(logger_->get_logger(), "Extracted NED in Map Rotation (x,y,z,w) : ( "
112 << ned_in_map_rotation_.get().x() << ", " << ned_in_map_rotation_.get().y() << ", "
113 << ned_in_map_rotation_.get().z() << ", " << ned_in_map_rotation_.get().w());
114 }
115}
116
117boost::optional<tf2::Quaternion> GNSSToMapConvertor::getNedInMapRotation()
118{
120}
121
122std::shared_ptr<lanelet::projection::LocalFrameProjector> GNSSToMapConvertor::getMapProjector()
123{
124 return map_projector_;
125}
126
127
128geometry_msgs::msg::PoseWithCovarianceStamped GNSSToMapConvertor::poseFromGnss(
129 const tf2::Transform& baselink_in_sensor,
130 const tf2::Quaternion& sensor_in_ned_heading_rotation,
131 const lanelet::projection::LocalFrameProjector& projector,
132 const tf2::Quaternion& ned_in_map_rotation,
133 gps_msgs::msg::GPSFix fix_msg)
134{
136 const double lat = fix_msg.latitude;
137 const double lon = fix_msg.longitude;
138 const double alt = fix_msg.altitude;
139
140 lanelet::BasicPoint3d map_point = projector.forward({ lat, lon, alt });
141 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "map_point: " << map_point.x() << ", " << map_point.y() << ", " << map_point.z());
142
143 if (fabs(map_point.x()) > 10000.0 || fabs(map_point.y()) > 10000.0)
144 { // Above 10km from map origin earth curvature will start to have a negative impact on system performance
145
146 RCLCPP_WARN_STREAM(logger_->get_logger(), "Distance from map origin is larger than supported by system assumptions. Strongly advise "
147 "alternative map origin be used. ");
148 }
149
151 // This logic assumes that the orientation difference between an NED frame located at the map origin and an NED frame
152 // located at the GNSS point are sufficiently small that they can be ignored. Therefore it is assumed the heading
153 // report of the GNSS system reguardless of its poition in the map without change in its orientation will give the
154 // same result (as far as we are concered).
155
156 tf2::Quaternion R_m_n(ned_in_map_rotation); // Rotation of NED frame in map frame
157 tf2::Quaternion R_n_h; // Rotation of sensor heading report in NED frame
158 R_n_h.setRPY(0, 0, fix_msg.track * wgs84_utils::DEG2RAD);
159
160 tf2::Quaternion R_h_s = sensor_in_ned_heading_rotation; // Rotation of heading report in sensor frame
161
162 tf2::Quaternion R_m_s =
163 R_m_n * R_n_h * R_h_s; // Rotation of sensor in map frame under assumption that distance from map origin is
164 // sufficiently small so as to ignore local changes in NED orientation
165
166 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "R_m_n (x,y,z,w) : ( "
167 << R_m_n.x() << ", " << R_m_n.y() << ", "
168 << R_m_n.z() << ", " << R_m_n.w());
169
170 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "R_n_h (x,y,z,w) : ( "
171 << R_n_h.x() << ", " << R_n_h.y() << ", "
172 << R_n_h.z() << ", " << R_n_h.w());
173
174 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "R_h_s (x,y,z,w) : ( "
175 << R_h_s.x() << ", " << R_h_s.y() << ", "
176 << R_h_s.z() << ", " << R_h_s.w());
177
178 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "R_m_s (x,y,z,w) : ( "
179 << R_m_s.x() << ", " << R_m_s.y() << ", "
180 << R_m_s.z() << ", " << R_m_s.w());
181
182 tf2::Transform T_m_s(R_m_s,
183 tf2::Vector3(map_point.x(), map_point.y(), map_point.z())); // Reported position and orientation
184 // of sensor frame in map frame
185 tf2::Transform T_s_b(baselink_in_sensor); // Transform between sensor and baselink frame
186 tf2::Transform T_m_b = T_m_s * T_s_b; // Transform between map and baselink frame
187
188 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "T_m_s (x,y,z,w) : ( "
189 << T_m_s.getRotation().x() << ", " << T_m_s.getRotation().y() << ", "
190 << T_m_s.getRotation().z() << ", " << T_m_s.getRotation().w());
191 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "T_s_b (x,y,z,w) : ( "
192 << T_s_b.getRotation().x() << ", " << T_s_b.getRotation().y() << ", "
193 << T_s_b.getRotation().z() << ", " << T_s_b.getRotation().w());
194 RCLCPP_DEBUG_STREAM(logger_->get_logger(), "T_m_b (x,y,z,w) : ( "
195 << T_m_b.getRotation().x() << ", " << T_m_b.getRotation().y() << ", "
196 << T_m_b.getRotation().z() << ", " << T_m_b.getRotation().w());
197
198 // TODO handle covariance
199
200 // Populate message
201 geometry_msgs::msg::PoseWithCovarianceStamped pose;
202 pose.header = fix_msg.header;
203
204 pose.pose.pose.position.x = T_m_b.getOrigin().getX();
205 pose.pose.pose.position.y = T_m_b.getOrigin().getY();
206 pose.pose.pose.position.z = T_m_b.getOrigin().getZ();
207
208 pose.pose.pose.orientation.x = T_m_b.getRotation().getX();
209 pose.pose.pose.orientation.y = T_m_b.getRotation().getY();
210 pose.pose.pose.orientation.z = T_m_b.getRotation().getZ();
211 pose.pose.pose.orientation.w = T_m_b.getRotation().getW();
212
213 return pose;
214}
215} // namespace gnss_to_map_convertor
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_
std::function< void(geometry_msgs::msg::PoseStamped)> PosePubCallback
void geoReferenceCallback(std_msgs::msg::String::UniquePtr geo_ref)
Map georeference callback The geodetic description of the map frame should be provided to this callba...
std::function< boost::optional< geometry_msgs::msg::TransformStamped >(const std::string &, const std::string &)> TransformLookupCallback
boost::optional< tf2::Quaternion > sensor_in_ned_heading_rotation_
void gnssFixCb(gps_msgs::msg::GPSFix::UniquePtr fix_msg)
GNSS Fix callback which will publish a pose representing that fix in the map frame if the required tr...
std::shared_ptr< lanelet::projection::LocalFrameProjector > getMapProjector()
Get the projector built from the provided georeference via the callback.
GNSSToMapConvertor(PosePubCallback pose_pub, TransformLookupCallback tf_lookup, std::string map_frame_id, std::string base_link_frame_id, std::string heading_frame_id, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger)
Constructor.
boost::optional< tf2::Transform > baselink_in_sensor_
boost::optional< tf2::Quaternion > ned_in_map_rotation_
geometry_msgs::msg::PoseWithCovarianceStamped poseFromGnss(const tf2::Transform &baselink_in_sensor, const tf2::Quaternion &sensor_in_ned_heading_rotation, const lanelet::projection::LocalFrameProjector &projector, const tf2::Quaternion &ned_in_map_rotation, gps_msgs::msg::GPSFix fix_msg)
Converts a provided GNSS fix message into a pose message for the map frame describibed by the provide...
boost::optional< tf2::Quaternion > getNedInMapRotation()
Get the rotation computed from the recieved georeference or boost::none if unset.
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_
void convert(const carma_v2x_msgs::msg::PSM &in_msg, carma_perception_msgs::msg::ExternalObject &out_msg, const std::string &map_frame_id, double pred_period, double pred_step_size, const lanelet::projection::LocalFrameProjector &map_projector, const tf2::Quaternion &ned_in_map_rotation, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock)