From 255522203a214219cb406a0952a506472c09900b Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 19 Jun 2024 11:28:16 -0400 Subject: [PATCH] Revamp nav2_util CMakeLists.txt to use modern idioms. (#4393) This commit does a number of things: 1. Switches to using target_link_libraries everywhere. This gives us finer-grained control over what dependencies are exported to downstream as public, or private. In the particular case of nav2_util, this actually doesn't matter *too* much, but it will help for other packages. 2. Moves the include directory down one level to include/${PROJECT_NAME}, which is best practice in ROS 2 since Humble. 3. Makes sure to export nav2_util as a CMake target, so downstream users of it can use that target. 4. Moves the base_footprint_publisher.hpp header file into the src directory, as it isn't functionality that an external project could use. Signed-off-by: Chris Lalancette --- .../nav2_util/base_footprint_publisher.hpp | 129 ------------------ nav2_util/src/base_footprint_publisher.cpp | 2 +- .../test/test_base_footprint_publisher.cpp | 2 +- 3 files changed, 2 insertions(+), 131 deletions(-) delete mode 100644 nav2_util/include/nav2_util/base_footprint_publisher.hpp diff --git a/nav2_util/include/nav2_util/base_footprint_publisher.hpp b/nav2_util/include/nav2_util/base_footprint_publisher.hpp deleted file mode 100644 index 52bcdb53eb0..00000000000 --- a/nav2_util/include/nav2_util/base_footprint_publisher.hpp +++ /dev/null @@ -1,129 +0,0 @@ -// Copyright (c) 2023 Open Navigation LLC -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef NAV2_UTIL__BASE_FOOTPRINT_PUBLISHER_HPP_ -#define NAV2_UTIL__BASE_FOOTPRINT_PUBLISHER_HPP_ - -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "tf2_msgs/msg/tf_message.hpp" -#include "geometry_msgs/msg/transform_stamped.hpp" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/buffer.h" -#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" - -namespace nav2_util -{ - -/** - * @brief A TF2 listener that overrides the subscription callback - * to inject base footprint publisher removing Z, Pitch, and Roll for - * 3D state estimation but desiring a 2D frame for navigation, visualization, or other reasons - */ -class BaseFootprintPublisherListener : public tf2_ros::TransformListener -{ -public: - BaseFootprintPublisherListener(tf2::BufferCore & buffer, bool spin_thread, rclcpp::Node & node) - : tf2_ros::TransformListener(buffer, spin_thread) - { - node.declare_parameter( - "base_link_frame", rclcpp::ParameterValue(std::string("base_link"))); - node.declare_parameter( - "base_footprint_frame", rclcpp::ParameterValue(std::string("base_footprint"))); - base_link_frame_ = node.get_parameter("base_link_frame").as_string(); - base_footprint_frame_ = node.get_parameter("base_footprint_frame").as_string(); - tf_broadcaster_ = std::make_shared(node); - } - - /** - * @brief Overrides TF2 subscription callback to inject base footprint publisher - */ - void subscription_callback(tf2_msgs::msg::TFMessage::ConstSharedPtr msg, bool is_static) override - { - TransformListener::subscription_callback(msg, is_static); - - if (is_static) { - return; - } - - for (unsigned int i = 0; i != msg->transforms.size(); i++) { - auto & t = msg->transforms[i]; - if (t.child_frame_id == base_link_frame_) { - geometry_msgs::msg::TransformStamped transform; - transform.header.stamp = t.header.stamp; - transform.header.frame_id = base_link_frame_; - transform.child_frame_id = base_footprint_frame_; - - // Project to Z-zero - transform.transform.translation = t.transform.translation; - transform.transform.translation.z = 0.0; - - // Remove Roll and Pitch - tf2::Quaternion q; - q.setRPY(0, 0, tf2::getYaw(t.transform.rotation)); - q.normalize(); - transform.transform.rotation.x = q.x(); - transform.transform.rotation.y = q.y(); - transform.transform.rotation.z = q.z(); - transform.transform.rotation.w = q.w(); - - tf_broadcaster_->sendTransform(transform); - return; - } - } - } - -protected: - std::shared_ptr tf_broadcaster_; - std::string base_link_frame_, base_footprint_frame_; -}; - -/** - * @class nav2_util::BaseFootprintPublisher - * @brief Republishes the ``base_link`` frame as ``base_footprint`` - * stripping away the Z, Roll, and Pitch of the full 3D state to provide - * a 2D projection for navigation when state estimation is full 3D - */ -class BaseFootprintPublisher : public rclcpp::Node -{ -public: - /** - * @brief A constructor - */ - explicit BaseFootprintPublisher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()) - : Node("base_footprint_publisher", options) - { - RCLCPP_INFO(get_logger(), "Creating base footprint publisher"); - tf_buffer_ = std::make_shared(get_clock()); - auto timer_interface = std::make_shared( - get_node_base_interface(), - get_node_timers_interface()); - tf_buffer_->setCreateTimerInterface(timer_interface); - listener_publisher_ = std::make_shared( - *tf_buffer_, true, *this); - } - -protected: - std::shared_ptr tf_buffer_; - std::shared_ptr listener_publisher_; -}; - -} // end namespace nav2_util - -#endif // NAV2_UTIL__BASE_FOOTPRINT_PUBLISHER_HPP_ diff --git a/nav2_util/src/base_footprint_publisher.cpp b/nav2_util/src/base_footprint_publisher.cpp index f3b6791db44..144ba14ab66 100644 --- a/nav2_util/src/base_footprint_publisher.cpp +++ b/nav2_util/src/base_footprint_publisher.cpp @@ -14,7 +14,7 @@ #include -#include "nav2_util/base_footprint_publisher.hpp" +#include "base_footprint_publisher.hpp" int main(int argc, char ** argv) { diff --git a/nav2_util/test/test_base_footprint_publisher.cpp b/nav2_util/test/test_base_footprint_publisher.cpp index 47dc83c7f31..cd788831325 100644 --- a/nav2_util/test/test_base_footprint_publisher.cpp +++ b/nav2_util/test/test_base_footprint_publisher.cpp @@ -15,7 +15,7 @@ #include #include -#include "nav2_util/base_footprint_publisher.hpp" +#include "base_footprint_publisher.hpp" #include "gtest/gtest.h" #include "tf2/exceptions.h"