19#include <rclcpp/rclcpp.hpp>
21#include <std_msgs/msg/string.hpp>
22#include <std_srvs/srv/empty.hpp>
24#include <carma_ros2_utils/carma_lifecycle_node.hpp>
26#include <tf2_ros/transform_listener.h>
27#include <tf2_ros/buffer.h>
29#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
30#include <tf2/LinearMath/Quaternion.h>
31#include <tf2/LinearMath/Matrix3x3.h>
37#include <boost/algorithm/string.hpp>
38#include <boost/optional.hpp>
46 class Node :
public carma_ros2_utils::CarmaLifecycleNode
66 explicit Node(
const rclcpp::NodeOptions &);
72 carma_ros2_utils::PubPtr<geometry_msgs::msg::PoseStamped>
map_pose_pub;
74 carma_ros2_utils::SubPtr<gps_msgs::msg::GPSFix>
fix_sub_;
76 carma_ros2_utils::SubPtr<std_msgs::msg::String>
geo_sub;
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< tf2_ros::TransformListener > tfListener_
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 > ¶meters)
carma_ros2_utils::PubPtr< geometry_msgs::msg::PoseStamped > map_pose_pub
std::shared_ptr< tf2_ros::Buffer > tfBuffer_
Stuct containing the algorithm configuration values for gnss_to_map_convertor.