From 428d01a93f5686da7a4dbd4073e99555d85c01db Mon Sep 17 00:00:00 2001 From: Vaios Papaspyros Date: Thu, 5 Dec 2024 13:28:12 +0100 Subject: [PATCH 1/3] feat(controllers): add TF listener and lookup TF helpers in BaseControllerInterface (#169) --- CHANGELOG.md | 1 + .../src/ComponentInterface.cpp | 2 +- .../BaseControllerInterface.hpp | 58 +++++++++++++++++ .../src/BaseControllerInterface.cpp | 65 +++++++++++++++++++ 4 files changed, 125 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 7945b27d..8d0290ac 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -22,6 +22,7 @@ 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) ## 5.0.2 diff --git a/source/modulo_components/src/ComponentInterface.cpp b/source/modulo_components/src/ComponentInterface.cpp index bbf2c811..30beb678 100644 --- a/source/modulo_components/src/ComponentInterface.cpp +++ b/source/modulo_components/src/ComponentInterface.cpp @@ -537,7 +537,7 @@ geometry_msgs::msg::TransformStamped ComponentInterface::lookup_ros_transform( const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point, const tf2::Duration& duration) { if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) { - throw exceptions::LookupTransformException("Failed to lookup transform: To TF buffer / listener configured."); + throw exceptions::LookupTransformException("Failed to lookup transform: No TF buffer / listener configured."); } try { return this->tf_buffer_->lookupTransform(reference_frame, frame, time_point, duration); diff --git a/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp b/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp index bde57816..7eae0168 100644 --- a/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp +++ b/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp @@ -7,6 +7,8 @@ #include #include #include +#include +#include #include @@ -310,6 +312,39 @@ class BaseControllerInterface : public controller_interface::ControllerInterface const std::string& service_name, const std::function& callback); + /** + * @brief Configure a transform buffer and listener. + */ + void add_tf_listener(); + + /** + * @brief Look up a transform from TF. + * @param frame The desired frame of the transform + * @param reference_frame The desired reference frame of the transform + * @param time_point The time at which the value of the transform is desired + * @param duration How long to block the lookup call before failing + * @throws modulo_core::exceptions::LookupTransformException if TF buffer/listener are unconfigured or + * if the lookupTransform call failed + * @return If it exists, the requested transform + */ + [[nodiscard]] state_representation::CartesianPose lookup_transform( + const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point, + const tf2::Duration& duration); + + /** + * @brief Look up a transform from TF. + * @param frame The desired frame of the transform + * @param reference_frame The desired reference frame of the transform + * @param validity_period The validity period of the latest transform from the time of lookup in seconds + * @param duration How long to block the lookup call before failing + * @throws modulo_core::exceptions::LookupTransformException if TF buffer/listener are unconfigured, + * if the lookupTransform call failed, or if the transform is too old + * @return If it exists and is still valid, the requested transform + */ + [[nodiscard]] state_representation::CartesianPose lookup_transform( + 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 Getter of the Quality of Service attribute. * @return The Quality of Service attribute @@ -334,6 +369,12 @@ class BaseControllerInterface : public controller_interface::ControllerInterface */ std::timed_mutex& get_command_mutex(); + /** + * @brief Check if the node has been initialized or not. + * @return True if the node is initialized, false otherwise + */ + bool is_node_initialized() const; + private: /** * @brief Parameter validation function @@ -447,6 +488,20 @@ class BaseControllerInterface : public controller_interface::ControllerInterface */ std::string validate_service_name(const std::string& service_name, const std::string& type) const; + /** + * @brief Helper method to look up a transform from TF. + * @param frame The desired frame of the transform + * @param reference_frame The desired reference frame of the transform + * @param time_point The time at which the value of the transform is desired + * @param duration How long to block the lookup call before failing + * @throws modulo_core::exceptions::LookupTransformException if TF buffer/listener are unconfigured or + * if the lookupTransform call failed + * @return If it exists, the requested transform + */ + [[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); + state_representation::ParameterMap parameter_map_;///< ParameterMap for handling parameters std::unordered_map read_only_parameters_; std::shared_ptr @@ -482,6 +537,9 @@ class BaseControllerInterface : public controller_interface::ControllerInterface custom_output_configuration_callables_; std::map> custom_input_configuration_callables_; + + std::shared_ptr tf_buffer_; ///< TF buffer + std::shared_ptr tf_listener_;///< TF listener }; template diff --git a/source/modulo_controllers/src/BaseControllerInterface.cpp b/source/modulo_controllers/src/BaseControllerInterface.cpp index b3aaa754..2233ecca 100644 --- a/source/modulo_controllers/src/BaseControllerInterface.cpp +++ b/source/modulo_controllers/src/BaseControllerInterface.cpp @@ -2,9 +2,13 @@ #include +#include + #include +#include #include +#include template struct overloaded : Ts... { @@ -539,6 +543,58 @@ void BaseControllerInterface::add_service( } } +void BaseControllerInterface::add_tf_listener() { + if (!is_node_initialized()) { + throw modulo_core::exceptions::CoreException("Failed to add TF buffer and listener: Node is not initialized yet."); + } + if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) { + RCLCPP_DEBUG(this->get_node()->get_logger(), "Adding TF buffer and listener."); + console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE); + this->tf_buffer_ = std::make_shared(this->get_node()->get_clock()); + this->tf_listener_ = std::make_shared(*this->tf_buffer_); + } else { + RCLCPP_DEBUG(this->get_node()->get_logger(), "TF buffer and listener already exist."); + } +} + +state_representation::CartesianPose BaseControllerInterface::lookup_transform( + const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point, + const tf2::Duration& duration) { + auto transform = this->lookup_ros_transform(frame, reference_frame, time_point, duration); + state_representation::CartesianPose result(frame, reference_frame); + translators::read_message(result, transform); + return result; +} + +state_representation::CartesianPose BaseControllerInterface::lookup_transform( + const std::string& frame, const std::string& reference_frame, double validity_period, + const tf2::Duration& duration) { + auto transform = + this->lookup_ros_transform(frame, reference_frame, tf2::TimePoint(std::chrono::microseconds(0)), duration); + if (validity_period > 0.0 + && (this->get_node()->get_clock()->now() - transform.header.stamp).seconds() > validity_period) { + throw modulo_core::exceptions::LookupTransformException("Failed to lookup transform: Latest transform is too old!"); + } + state_representation::CartesianPose result(frame, reference_frame); + translators::read_message(result, transform); + return result; +} + +geometry_msgs::msg::TransformStamped BaseControllerInterface::lookup_ros_transform( + const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point, + const tf2::Duration& duration) { + if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) { + throw modulo_core::exceptions::LookupTransformException( + "Failed to lookup transform: No TF buffer / listener configured."); + } + try { + return this->tf_buffer_->lookupTransform(reference_frame, frame, time_point, duration); + } catch (const tf2::TransformException& ex) { + throw modulo_core::exceptions::LookupTransformException( + std::string("Failed to lookup transform: ").append(ex.what())); + } +} + rclcpp::QoS BaseControllerInterface::get_qos() const { return qos_; } @@ -555,4 +611,13 @@ std::timed_mutex& BaseControllerInterface::get_command_mutex() { return command_mutex_; } +bool BaseControllerInterface::is_node_initialized() const { + try { + get_node(); + return true; + } catch (const std::runtime_error&) { + return false; + } +} + }// namespace modulo_controllers From 987252fd486b5a4b207ea5ac857fb39bb17ef4b9 Mon Sep 17 00:00:00 2001 From: Vaios Papaspyros Date: Thu, 5 Dec 2024 14:42:54 +0100 Subject: [PATCH 2/3] 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_; } From 76313a4bc715ecb59444a044e6b76e6c5c7f6e06 Mon Sep 17 00:00:00 2001 From: Vaios Papaspyros Date: Thu, 5 Dec 2024 16:32:44 +0100 Subject: [PATCH 3/3] test(controllers): add TF listener and broadcaster tests (#172) --- CHANGELOG.md | 1 + .../BaseControllerInterface.hpp | 1 + .../test/test_controller_interface.cpp | 74 ++++++++++++++++++- 3 files changed, 75 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 285ae46f..dffdade6 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -24,6 +24,7 @@ Release Versions: - fix(controllers): move predicate publishing rate parameter to BaseControllerInterface (#168) - feat(controllers): add TF listener in BaseControllerInterface (#169) - feat(controllers): add TF broadcaster in BaseControllerInterface (#170) + - test(controllers): add TF listener and broadcaster tests (#172) ## 5.0.2 diff --git a/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp b/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp index b26c19aa..0c7e7a45 100644 --- a/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp +++ b/source/modulo_controllers/include/modulo_controllers/BaseControllerInterface.hpp @@ -537,6 +537,7 @@ 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) diff --git a/source/modulo_controllers/test/test_controller_interface.cpp b/source/modulo_controllers/test/test_controller_interface.cpp index 67cf4f05..adb4d1cb 100644 --- a/source/modulo_controllers/test/test_controller_interface.cpp +++ b/source/modulo_controllers/test/test_controller_interface.cpp @@ -18,7 +18,15 @@ class FriendControllerInterface : public ControllerInterface { public: using ControllerInterface::add_input; using ControllerInterface::add_output; + using ControllerInterface::add_static_tf_broadcaster; + using ControllerInterface::add_tf_broadcaster; + using ControllerInterface::add_tf_listener; + using ControllerInterface::lookup_transform; using ControllerInterface::read_input; + using ControllerInterface::send_static_transform; + using ControllerInterface::send_static_transforms; + using ControllerInterface::send_transform; + using ControllerInterface::send_transforms; using ControllerInterface::write_output; private: @@ -211,7 +219,71 @@ TYPED_TEST_P(ControllerInterfaceTest, OutputTest) { } } -REGISTER_TYPED_TEST_CASE_P(ControllerInterfaceTest, ConfigureErrorTest, InputTest, OutputTest); +TYPED_TEST_P(ControllerInterfaceTest, TF) { + EXPECT_THROW(this->interface_->add_tf_broadcaster(), modulo_core::exceptions::CoreException); + EXPECT_THROW(this->interface_->add_static_tf_broadcaster(), modulo_core::exceptions::CoreException); + EXPECT_THROW(this->interface_->add_tf_listener(), modulo_core::exceptions::CoreException); + auto send_early_tf = state_representation::CartesianPose::Random("controller_test", "world"); + EXPECT_THROW(this->interface_->send_transform(send_early_tf), modulo_core::exceptions::CoreException); + this->init(); + this->interface_->add_tf_broadcaster(); + this->interface_->add_static_tf_broadcaster(); + this->interface_->add_tf_listener(); + auto send_tf = state_representation::CartesianPose::Random("controller_test", "world"); + EXPECT_NO_THROW(this->interface_->send_transform(send_tf)); + sleep(1); + state_representation::CartesianPose lookup_tf; + EXPECT_NO_THROW(lookup_tf = this->interface_->lookup_transform("controller_test", "world")); + auto identity = send_tf * lookup_tf.inverse(); + EXPECT_FLOAT_EQ(identity.data().norm(), 1.); + EXPECT_FLOAT_EQ(abs(identity.get_orientation().w()), 1.); + + sleep(1); + EXPECT_THROW( + lookup_tf = this->interface_->lookup_transform("controller_test", "world", 0.1), + modulo_core::exceptions::LookupTransformException); + + auto send_static_tf = state_representation::CartesianPose::Random("controller_static_test", "world"); + EXPECT_NO_THROW(this->interface_->send_static_transform(send_static_tf)); + EXPECT_THROW( + auto throw_tf = this->interface_->lookup_transform("dummy", "world"), + modulo_core::exceptions::LookupTransformException); + + EXPECT_NO_THROW(lookup_tf = this->interface_->lookup_transform("controller_static_test", "world")); + identity = send_static_tf * lookup_tf.inverse(); + EXPECT_FLOAT_EQ(identity.data().norm(), 1.); + EXPECT_FLOAT_EQ(abs(identity.get_orientation().w()), 1.); + + std::vector send_tfs; + send_tfs.reserve(3); + for (std::size_t idx = 0; idx < 3; ++idx) { + send_tfs.emplace_back( + state_representation::CartesianPose::Random("controller_test_" + std::to_string(idx), "world")); + } + EXPECT_NO_THROW(this->interface_->send_transforms(send_tfs)); + for (const auto& tf : send_tfs) { + lookup_tf = this->interface_->lookup_transform(tf.get_name(), tf.get_reference_frame()); + identity = tf * lookup_tf.inverse(); + EXPECT_FLOAT_EQ(identity.data().norm(), 1.); + EXPECT_FLOAT_EQ(abs(identity.get_orientation().w()), 1.); + } + + std::vector send_static_tfs; + send_static_tfs.reserve(3); + for (std::size_t idx = 0; idx < 3; ++idx) { + send_static_tfs.emplace_back( + state_representation::CartesianPose::Random("controller_test_static_" + std::to_string(idx), "world")); + } + EXPECT_NO_THROW(this->interface_->send_static_transforms(send_static_tfs)); + for (const auto& tf : send_static_tfs) { + lookup_tf = this->interface_->lookup_transform(tf.get_name(), tf.get_reference_frame()); + identity = tf * lookup_tf.inverse(); + EXPECT_FLOAT_EQ(identity.data().norm(), 1.); + EXPECT_FLOAT_EQ(abs(identity.get_orientation().w()), 1.); + } +} + +REGISTER_TYPED_TEST_CASE_P(ControllerInterfaceTest, ConfigureErrorTest, InputTest, OutputTest, TF); typedef ::testing::Types SignalTypes; INSTANTIATE_TYPED_TEST_CASE_P(TestPrefix, ControllerInterfaceTest, SignalTypes);