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.
gnss_to_map_convertor_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2018-2022 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 */
17
19{
20 namespace std_ph = std::placeholders;
21
22 Node::Node(const rclcpp::NodeOptions &options): carma_ros2_utils::CarmaLifecycleNode(options), tfBuffer_(get_clock()), tfListener_(tfBuffer_)
23 {
24 // Create initial config
25 config_ = Config();
26
27 // Declare parameters
28 config_.base_link_frame = declare_parameter<std::string>("base_link_frame", config_.base_link_frame);
29 config_.map_frame = declare_parameter<std::string>("map_frame", config_.map_frame);
30 config_.heading_frame = declare_parameter<std::string>("heading_frame", config_.heading_frame);
31 }
32
33 rcl_interfaces::msg::SetParametersResult Node::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
34 {
35 auto error = update_params<std::string>({{"base_link_frame", config_.base_link_frame},{"map_frame", config_.map_frame},{"heading_frame", config_.heading_frame}}, parameters);
36
37 rcl_interfaces::msg::SetParametersResult result;
38
39 result.successful = !error;
40
41 return result;
42 }
43
44 carma_ros2_utils::CallbackReturn Node::handle_on_configure(const rclcpp_lifecycle::State &)
45 {
46 // Reset config
47 config_ = Config();
48
49 // Load parameters
50 get_parameter<std::string>("base_link_frame", config_.base_link_frame);
51 get_parameter<std::string>("map_frame", config_.map_frame);
52 get_parameter<std::string>("heading_frame", config_.heading_frame);
53
54 // Register runtime parameter update callback
55 add_on_set_parameters_callback(std::bind(&Node::parameter_update_callback, this, std_ph::_1));
56
57 // Map pose publisher
58 map_pose_pub = create_publisher<geometry_msgs::msg::PoseStamped>("gnss_pose", 10);
59
60 // Initialize primary worker object
61 convertor_worker_ = std::make_shared<GNSSToMapConvertor>(
62 [this](const auto& msg) { map_pose_pub->publish(msg); }, // Lambda representing publication
63
64 [this](const auto& target, const auto& source) -> boost::optional<geometry_msgs::msg::TransformStamped> { // Lambda representing transform lookup
65 geometry_msgs::msg::TransformStamped tf;
66 try
67 {
68 tf = tfBuffer_.lookupTransform(target, source, rclcpp::Time(1, 0));
69 }
70 catch (tf2::TransformException& ex)
71 {
72 RCLCPP_ERROR_STREAM(get_logger(),"Could not lookup transform with exception " << ex.what());
73 return boost::none;
74 }
75 return tf;
76 },
77
78 config_.map_frame, config_.base_link_frame, config_.heading_frame, this->get_node_logging_interface());
79
80 // Fix Subscriber
81
82 fix_sub_ = create_subscription<gps_msgs::msg::GPSFix>("gnss_fix_fused", 2,
83 std::bind(&GNSSToMapConvertor::gnssFixCb, convertor_worker_.get(), std_ph::_1));
84
85 // Georeference subsciber
86
87 geo_sub = create_subscription<std_msgs::msg::String>("georeference", 1,
88 std::bind(&GNSSToMapConvertor::geoReferenceCallback, convertor_worker_.get(), std_ph::_1));
89
90
91 // Return success if everthing initialized successfully
92 return CallbackReturn::SUCCESS;
93 }
94
95} // gnss_to_map_convertor
96
97#include "rclcpp_components/register_node_macro.hpp"
98
99// Register the component with class_loader
100RCLCPP_COMPONENTS_REGISTER_NODE(gnss_to_map_convertor::Node)
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...
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...
Node(const rclcpp::NodeOptions &)
Node constructor.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
carma_ros2_utils::SubPtr< gps_msgs::msg::GPSFix > fix_sub_
std::shared_ptr< GNSSToMapConvertor > convertor_worker_
carma_ros2_utils::SubPtr< std_msgs::msg::String > geo_sub
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
carma_ros2_utils::PubPtr< geometry_msgs::msg::PoseStamped > map_pose_pub
Stuct containing the algorithm configuration values for gnss_to_map_convertor.