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 Class Reference

#include <gnss_to_map_convertor_node.hpp>

Inheritance diagram for gnss_to_map_convertor::Node:
Inheritance graph
Collaboration diagram for gnss_to_map_convertor::Node:
Collaboration graph

Public Member Functions

 Node (const rclcpp::NodeOptions &)
 Node constructor. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 

Public Attributes

carma_ros2_utils::PubPtr< geometry_msgs::msg::PoseStamped > map_pose_pub
 
carma_ros2_utils::SubPtr< gps_msgs::msg::GPSFix > fix_sub_
 
carma_ros2_utils::SubPtr< std_msgs::msg::String > geo_sub
 

Private Attributes

Config config_
 
tf2_ros::Buffer tfBuffer_
 
tf2_ros::TransformListener tfListener_ {tfBuffer_}
 
std::shared_ptr< GNSSToMapConvertorconvertor_worker_
 

Detailed Description

Definition at line 44 of file gnss_to_map_convertor_node.hpp.

Constructor & Destructor Documentation

◆ Node()

gnss_to_map_convertor::Node::Node ( const rclcpp::NodeOptions &  options)
explicit

Node constructor.

Definition at line 22 of file gnss_to_map_convertor_node.cpp.

22 : 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 }
tf2_ros::TransformListener tfListener_

References gnss_to_map_convertor::Config::base_link_frame, config_, gnss_to_map_convertor::Config::heading_frame, and gnss_to_map_convertor::Config::map_frame.

Member Function Documentation

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn gnss_to_map_convertor::Node::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 44 of file gnss_to_map_convertor_node.cpp.

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 }
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...
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

References gnss_to_map_convertor::Config::base_link_frame, config_, convertor_worker_, fix_sub_, geo_sub, gnss_to_map_convertor::GNSSToMapConvertor::geoReferenceCallback(), gnss_to_map_convertor::GNSSToMapConvertor::gnssFixCb(), gnss_to_map_convertor::Config::heading_frame, gnss_to_map_convertor::Config::map_frame, map_pose_pub, parameter_update_callback(), and tfBuffer_.

Here is the call graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult gnss_to_map_convertor::Node::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Definition at line 33 of file gnss_to_map_convertor_node.cpp.

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 }

References gnss_to_map_convertor::Config::base_link_frame, config_, gnss_to_map_convertor::Config::heading_frame, and gnss_to_map_convertor::Config::map_frame.

Referenced by handle_on_configure().

Here is the caller graph for this function:

Member Data Documentation

◆ config_

Config gnss_to_map_convertor::Node::config_
private

◆ convertor_worker_

std::shared_ptr<GNSSToMapConvertor> gnss_to_map_convertor::Node::convertor_worker_
private

Definition at line 59 of file gnss_to_map_convertor_node.hpp.

Referenced by handle_on_configure().

◆ fix_sub_

carma_ros2_utils::SubPtr<gps_msgs::msg::GPSFix> gnss_to_map_convertor::Node::fix_sub_

Definition at line 73 of file gnss_to_map_convertor_node.hpp.

Referenced by handle_on_configure().

◆ geo_sub

carma_ros2_utils::SubPtr<std_msgs::msg::String> gnss_to_map_convertor::Node::geo_sub

Definition at line 75 of file gnss_to_map_convertor_node.hpp.

Referenced by handle_on_configure().

◆ map_pose_pub

carma_ros2_utils::PubPtr<geometry_msgs::msg::PoseStamped> gnss_to_map_convertor::Node::map_pose_pub

Definition at line 71 of file gnss_to_map_convertor_node.hpp.

Referenced by handle_on_configure().

◆ tfBuffer_

tf2_ros::Buffer gnss_to_map_convertor::Node::tfBuffer_
private

Definition at line 53 of file gnss_to_map_convertor_node.hpp.

Referenced by handle_on_configure().

◆ tfListener_

tf2_ros::TransformListener gnss_to_map_convertor::Node::tfListener_ {tfBuffer_}
private

Definition at line 56 of file gnss_to_map_convertor_node.hpp.


The documentation for this class was generated from the following files: