From 648e00f2722ad645a6880794f62f269b67a257dc Mon Sep 17 00:00:00 2001 From: Facundo Garcia Date: Mon, 28 Oct 2024 14:31:34 +0100 Subject: [PATCH] Changed geometry_msgs calls --- .../include/fixposition_driver_ros2/data_to_ros2.hpp | 2 +- fixposition_driver_ros2/src/data_to_ros2.cpp | 6 +++--- fixposition_driver_ros2/src/fixposition_driver_node.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp b/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp index 60ac5d9..31959e8 100644 --- a/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp +++ b/fixposition_driver_ros2/include/fixposition_driver_ros2/data_to_ros2.hpp @@ -130,7 +130,7 @@ void OdomToTf(const OdometryData& data, geometry_msgs::msg::TransformStamped& tf * @param[out] static_br_ * @param[out] br_ */ -void PublishNav2Tf(const std::map>& tf_map, std::shared_ptr static_br_, std::shared_ptr br_); +void PublishNav2Tf(const std::map>& tf_map, std::shared_ptr static_br_, std::shared_ptr br_); /** * @brief diff --git a/fixposition_driver_ros2/src/data_to_ros2.cpp b/fixposition_driver_ros2/src/data_to_ros2.cpp index 3786e99..f49dcb7 100644 --- a/fixposition_driver_ros2/src/data_to_ros2.cpp +++ b/fixposition_driver_ros2/src/data_to_ros2.cpp @@ -619,7 +619,7 @@ void OdomToTf(const OdometryData& data, geometry_msgs::msg::TransformStamped& tf tf2::toMsg(data.pose.position, tf.transform.translation); } -void PublishNav2Tf(const std::map>& tf_map, std::shared_ptr static_br_, std::shared_ptr br_) { +void PublishNav2Tf(const std::map>& tf_map, std::shared_ptr static_br_, std::shared_ptr br_) { if (tf_map.at("ECEFENU0") && tf_map.at("POIPOISH") && tf_map.at("ECEFPOISH") && tf_map.at("ENU0POI")) { // Publish FP_ECEF -> map tf_map.at("ECEFENU0")->child_frame_id = "map"; @@ -657,7 +657,7 @@ void PublishNav2Tf(const std::mapsendTransform(tf_map_odom); // Publish odom -> base_link - geometry_msgs::TransformStamped tf_odom_base; + geometry_msgs::msg::TransformStamped tf_odom_base; tf_odom_base.header.stamp = ros::Time::now(); tf_odom_base.header.frame_id = "odom"; tf_odom_base.child_frame_id = "base_link"; diff --git a/fixposition_driver_ros2/src/fixposition_driver_node.cpp b/fixposition_driver_ros2/src/fixposition_driver_node.cpp index ac878ce..ece6d8b 100644 --- a/fixposition_driver_ros2/src/fixposition_driver_node.cpp +++ b/fixposition_driver_ros2/src/fixposition_driver_node.cpp @@ -224,7 +224,7 @@ void FixpositionDriverNode::RegisterObservers() { // Append TF if Nav2 mode is selected if (params_.fp_output.nav2_mode) { // Get FP_POI -> FP_POISH - tf_map["POIPOISH"] = std::make_shared(tf); + tf_map["POIPOISH"] = std::make_shared(tf); } } else if (tf.child_frame_id == "FP_ENU0" && tf.header.frame_id == "FP_ECEF") { static_br_->sendTransform(tf); @@ -232,7 +232,7 @@ void FixpositionDriverNode::RegisterObservers() { // Append TF if Nav2 mode is selected if (params_.fp_output.nav2_mode) { // Get FP_ECEF -> FP_ENU0 - tf_map["ECEFENU0"] = std::make_shared(tf); + tf_map["ECEFENU0"] = std::make_shared(tf); } } else { static_br_->sendTransform(tf);