From 987252fd486b5a4b207ea5ac857fb39bb17ef4b9 Mon Sep 17 00:00:00 2001 From: Vaios Papaspyros Date: Thu, 5 Dec 2024 14:42:54 +0100 Subject: [PATCH] feat(controllers): add TF broadcaster in BaseControllerInterface (#170) --- CHANGELOG.md | 3 +- .../BaseControllerInterface.hpp | 82 ++++++++++++++++++- .../src/BaseControllerInterface.cpp | 43 ++++++++++ 3 files changed, 125 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 8d0290ac..285ae46f 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -22,7 +22,8 @@ Release Versions: - fix(components): remove incorrect log line (#166) - fix(controllers): move predicate publishing rate parameter to BaseControllerInterface (#168) - - feat(controllers): add TF listener interface in BaseControllerInterface (#169) + - feat(controllers): add TF listener in BaseControllerInterface (#169) + - feat(controllers): add TF broadcaster in BaseControllerInterface (#170) ## 5.0.2 diff --git a/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp b/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp index 7eae0168..b26c19aa 100644 --- a/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp +++ b/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp @@ -8,6 +8,8 @@ #include #include #include +#include +#include #include #include @@ -345,6 +347,40 @@ class BaseControllerInterface : public controller_interface::ControllerInterface const std::string& frame, const std::string& reference_frame = "world", double validity_period = -1.0, const tf2::Duration& duration = tf2::Duration(std::chrono::microseconds(10))); + /** + *@brief Configure a transform broadcaster. + */ + void add_tf_broadcaster(); + + /** + * @brief Configure a static transform broadcaster. + */ + void add_static_tf_broadcaster(); + + /** + * @brief Send a transform to TF. + * @param transform The transform to send + */ + void send_transform(const state_representation::CartesianPose& transform); + + /** + * @brief Send a vector of transforms to TF. + * @param transforms The vector of transforms to send + */ + void send_transforms(const std::vector& transforms); + + /** + * @brief Send a static transform to TF. + * @param transform The transform to send + */ + void send_static_transform(const state_representation::CartesianPose& transform); + + /** + * @brief Send a vector of static transforms to TF. + * @param transforms The vector of transforms to send + */ + void send_static_transforms(const std::vector& transforms); + /** * @brief Getter of the Quality of Service attribute. * @return The Quality of Service attribute @@ -501,6 +537,17 @@ class BaseControllerInterface : public controller_interface::ControllerInterface [[nodiscard]] geometry_msgs::msg::TransformStamped lookup_ros_transform( const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point, const tf2::Duration& duration); + /** + * @brief Helper function to send a vector of transforms through a transform broadcaster + * @tparam T The type of the broadcaster (tf2_ros::TransformBroadcaster or tf2_ros::StaticTransformBroadcaster) + * @param transforms The transforms to send + * @param tf_broadcaster A pointer to a configured transform broadcaster object + * @param is_static If true, treat the broadcaster as a static frame broadcaster for the sake of log messages + */ + template + void publish_transforms( + const std::vector& transforms, const std::shared_ptr& tf_broadcaster, + bool is_static = false); state_representation::ParameterMap parameter_map_;///< ParameterMap for handling parameters std::unordered_map read_only_parameters_; @@ -538,8 +585,10 @@ class BaseControllerInterface : public controller_interface::ControllerInterface std::map> custom_input_configuration_callables_; - std::shared_ptr tf_buffer_; ///< TF buffer - std::shared_ptr tf_listener_;///< TF listener + std::shared_ptr tf_buffer_; ///< TF buffer + std::shared_ptr tf_listener_; ///< TF listener + std::shared_ptr tf_broadcaster_; ///< TF broadcaster + std::shared_ptr static_tf_broadcaster_;///< TF static broadcaster }; template @@ -925,4 +974,33 @@ inline void BaseControllerInterface::write_output(const std::string& name, const write_std_output(name, data); } +template +inline void BaseControllerInterface::publish_transforms( + const std::vector& transforms, const std::shared_ptr& tf_broadcaster, + bool is_static) { + if (!is_node_initialized()) { + throw modulo_core::exceptions::CoreException("Failed send transform(s): Node is not initialized yet."); + } + std::string modifier = is_static ? "static " : ""; + if (tf_broadcaster == nullptr) { + RCLCPP_ERROR_STREAM_THROTTLE( + this->get_node()->get_logger(), *this->get_node()->get_clock(), 1000, + "Failed to send " << modifier << "transform: No " << modifier << "TF broadcaster configured."); + return; + } + try { + std::vector transform_messages; + transform_messages.reserve(transforms.size()); + for (const auto& tf : transforms) { + geometry_msgs::msg::TransformStamped transform_message; + modulo_core::translators::write_message(transform_message, tf, this->get_node()->get_clock()->now()); + transform_messages.emplace_back(transform_message); + } + tf_broadcaster->sendTransform(transform_messages); + } catch (const std::exception& ex) { + RCLCPP_ERROR_STREAM_THROTTLE( + this->get_node()->get_logger(), *this->get_node()->get_clock(), 1000, + "Failed to send " << modifier << "transform: " << ex.what()); + } +} }// namespace modulo_controllers diff --git a/source/modulo_controllers/src/BaseControllerInterface.cpp b/source/modulo_controllers/src/BaseControllerInterface.cpp index 2233ecca..562d3cfc 100644 --- a/source/modulo_controllers/src/BaseControllerInterface.cpp +++ b/source/modulo_controllers/src/BaseControllerInterface.cpp @@ -595,6 +595,49 @@ geometry_msgs::msg::TransformStamped BaseControllerInterface::lookup_ros_transfo } } +void BaseControllerInterface::add_tf_broadcaster() { + if (!is_node_initialized()) { + throw modulo_core::exceptions::CoreException("Failed to add TF broadcaster: Node is not initialized yet."); + } + if (this->tf_broadcaster_ == nullptr) { + RCLCPP_DEBUG(this->get_node()->get_logger(), "Adding TF broadcaster."); + console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE); + this->tf_broadcaster_ = std::make_shared(get_node()); + } else { + RCLCPP_DEBUG(this->get_node()->get_logger(), "TF broadcaster already exists."); + } +} + +void BaseControllerInterface::add_static_tf_broadcaster() { + if (!is_node_initialized()) { + throw modulo_core::exceptions::CoreException("Failed to add static TF broadcaster: Node is not initialized yet."); + } + if (this->static_tf_broadcaster_ == nullptr) { + RCLCPP_DEBUG(this->get_node()->get_logger(), "Adding static TF broadcaster."); + console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE); + this->static_tf_broadcaster_ = std::make_shared(get_node()); + } else { + RCLCPP_DEBUG(this->get_node()->get_logger(), "Static TF broadcaster already exists."); + } +} + +void BaseControllerInterface::send_transform(const state_representation::CartesianPose& transform) { + this->send_transforms(std::vector{transform}); +} + +void BaseControllerInterface::send_transforms(const std::vector& transforms) { + this->publish_transforms(transforms, this->tf_broadcaster_); +} + +void BaseControllerInterface::send_static_transform(const state_representation::CartesianPose& transform) { + this->send_static_transforms(std::vector{transform}); +} + +void BaseControllerInterface::send_static_transforms( + const std::vector& transforms) { + this->publish_transforms(transforms, this->static_tf_broadcaster_, true); +} + rclcpp::QoS BaseControllerInterface::get_qos() const { return qos_; }