|
| 1 | +// Copyright (c) 2025, ros2_control development team |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +/* |
| 16 | + * Authors: Julia Jia |
| 17 | + */ |
| 18 | + |
| 19 | +#include "force_torque_sensor_broadcaster/wrench_transformer.hpp" |
| 20 | + |
| 21 | +#include <limits> |
| 22 | +#include <memory> |
| 23 | +#include <string> |
| 24 | + |
| 25 | +#include "tf2/utils.hpp" |
| 26 | + |
| 27 | +namespace force_torque_sensor_broadcaster |
| 28 | +{ |
| 29 | + |
| 30 | +WrenchTransformer::WrenchTransformer(const rclcpp::NodeOptions & options) |
| 31 | +: rclcpp::Node("fts_wrench_transformer", options) |
| 32 | +{ |
| 33 | + // Initialize TF2 |
| 34 | + tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock()); |
| 35 | + tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_); |
| 36 | +} |
| 37 | + |
| 38 | +void WrenchTransformer::init() |
| 39 | +{ |
| 40 | + try |
| 41 | + { |
| 42 | + param_listener_ = std::make_shared<force_torque_wrench_transformer::ParamListener>( |
| 43 | + shared_from_this()); |
| 44 | + params_ = param_listener_->get_params(); |
| 45 | + } |
| 46 | + catch (const std::exception & e) |
| 47 | + { |
| 48 | + RCLCPP_ERROR(this->get_logger(), "Exception thrown during initialization: %s", e.what()); |
| 49 | + return; |
| 50 | + } |
| 51 | + |
| 52 | + // Setup subscriber and publishers |
| 53 | + setup_subscriber(); |
| 54 | + setup_publishers(); |
| 55 | +} |
| 56 | + |
| 57 | +void WrenchTransformer::wrench_callback(const geometry_msgs::msg::WrenchStamped::SharedPtr msg) |
| 58 | +{ |
| 59 | + |
| 60 | + if (!msg || msg->header.frame_id.empty()) { |
| 61 | + RCLCPP_ERROR_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "Invalid wrench message or frame_id is empty"); |
| 62 | + return; |
| 63 | + } |
| 64 | + |
| 65 | + for (const auto & target_frame : params_.target_frames) { |
| 66 | + geometry_msgs::msg::WrenchStamped output_wrench; |
| 67 | + // preserve timestamp |
| 68 | + output_wrench.header.stamp = msg->header.stamp; |
| 69 | + output_wrench.header.frame_id = target_frame; |
| 70 | + if (transform_wrench(*msg, target_frame, output_wrench)) { |
| 71 | + auto publisher = transformed_wrench_publishers_[target_frame]; |
| 72 | + if (publisher) { |
| 73 | + publisher->publish(output_wrench); |
| 74 | + } |
| 75 | + } |
| 76 | + else { |
| 77 | + RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "Failed to transform wrench for frame %s, skipping publication", target_frame.c_str()); |
| 78 | + } |
| 79 | + } |
| 80 | +} |
| 81 | + |
| 82 | +bool WrenchTransformer::transform_wrench( |
| 83 | + const geometry_msgs::msg::WrenchStamped & input_wrench, const std::string & target_frame, |
| 84 | + geometry_msgs::msg::WrenchStamped & output_wrench) |
| 85 | +{ |
| 86 | + try { |
| 87 | + auto transform = tf_buffer_->lookupTransform(target_frame, input_wrench.header.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(params_.tf_timeout)); |
| 88 | + output_wrench.header.frame_id = target_frame; |
| 89 | + tf2::doTransform(input_wrench, output_wrench, transform); |
| 90 | + // Preserve original timestamp after transform (doTransform may modify it) |
| 91 | + output_wrench.header.stamp = input_wrench.header.stamp; |
| 92 | + return true; |
| 93 | + } |
| 94 | + catch (const tf2::TransformException & e) { |
| 95 | + RCLCPP_ERROR_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "Transform exception: %s", e.what()); |
| 96 | + return false; |
| 97 | + } |
| 98 | + return false; |
| 99 | +} |
| 100 | + |
| 101 | +void WrenchTransformer::setup_subscriber() |
| 102 | +{ |
| 103 | + input_topic_ = params_.broadcaster_namespace.empty() ? "~/wrench" : params_.broadcaster_namespace + "/wrench"; |
| 104 | + if (params_.use_filtered_input) { |
| 105 | + input_topic_ += "_filtered"; |
| 106 | + } |
| 107 | + wrench_subscriber_ = this->create_subscription<geometry_msgs::msg::WrenchStamped>( |
| 108 | + input_topic_, rclcpp::SystemDefaultsQoS(), std::bind(&WrenchTransformer::wrench_callback, this, std::placeholders::_1)); |
| 109 | + if (wrench_subscriber_ == nullptr) { |
| 110 | + RCLCPP_ERROR_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "Failed to create wrench subscriber"); |
| 111 | + return; |
| 112 | + } |
| 113 | +} |
| 114 | + |
| 115 | +void WrenchTransformer::setup_publishers() |
| 116 | +{ |
| 117 | + for (const auto & target_frame : params_.target_frames) { |
| 118 | + std::string topic_name = params_.output_topic_prefix + "_" + target_frame; |
| 119 | + transformed_wrench_publishers_[target_frame] = this->create_publisher<geometry_msgs::msg::WrenchStamped>( |
| 120 | + topic_name, rclcpp::SystemDefaultsQoS()); |
| 121 | + if (transformed_wrench_publishers_[target_frame] == nullptr) { |
| 122 | + RCLCPP_ERROR_THROTTLE(this->get_logger(), *this->get_clock(), 5000, "Failed to create publisher for target frame %s", target_frame.c_str()); |
| 123 | + return; |
| 124 | + } |
| 125 | + RCLCPP_INFO(this->get_logger(), "Created publisher for target frame %s", target_frame.c_str()); |
| 126 | + } |
| 127 | +} |
| 128 | + |
| 129 | +} // namespace force_torque_sensor_broadcaster |
| 130 | + |
0 commit comments