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.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 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 */
16
17#pragma once
18
19#include <rclcpp/rclcpp.hpp>
20#include <functional>
21#include <std_msgs/msg/string.hpp>
22#include <std_srvs/srv/empty.hpp>
23
24#include <carma_ros2_utils/carma_lifecycle_node.hpp>
25
26#include <tf2_ros/transform_listener.h>
27#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
28#include <tf2/LinearMath/Quaternion.h>
29#include <tf2/LinearMath/Matrix3x3.h>
30
31#include <vector>
32#include <string>
33#include <algorithm>
34
35#include <boost/algorithm/string.hpp>
36#include <boost/optional.hpp>
37
40
42{
43
44 class Node : public carma_ros2_utils::CarmaLifecycleNode
45 {
46 private:
47
48 // Node configuration
50
51 // Buffer which holds the tree of transforms
52
53 tf2_ros::Buffer tfBuffer_;
54
55 // tf2 listeners. Subscribes to the /tf and /tf_static topics
56 tf2_ros::TransformListener tfListener_ {tfBuffer_};
57
58 //worker for GNSSToMapConvertor
59 std::shared_ptr <GNSSToMapConvertor> convertor_worker_;
60
61 public:
65 explicit Node(const rclcpp::NodeOptions &);
66
67 rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
68
69 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
70
71 carma_ros2_utils::PubPtr<geometry_msgs::msg::PoseStamped> map_pose_pub;
72
73 carma_ros2_utils::SubPtr<gps_msgs::msg::GPSFix> fix_sub_;
74
75 carma_ros2_utils::SubPtr<std_msgs::msg::String> geo_sub;
76
77 };
78
79} // gnss_to_map_convertor
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_
tf2_ros::TransformListener tfListener_
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.