|
| 1 | +// Copyright 2025, Universal Robots A/S |
| 2 | +// |
| 3 | +// Redistribution and use in source and binary forms, with or without |
| 4 | +// modification, are permitted provided that the following conditions are met: |
| 5 | +// |
| 6 | +// * Redistributions of source code must retain the above copyright |
| 7 | +// notice, this list of conditions and the following disclaimer. |
| 8 | +// |
| 9 | +// * Redistributions in binary form must reproduce the above copyright |
| 10 | +// notice, this list of conditions and the following disclaimer in the |
| 11 | +// documentation and/or other materials provided with the distribution. |
| 12 | +// |
| 13 | +// * Neither the name of the {copyright_holder} nor the names of its |
| 14 | +// contributors may be used to endorse or promote products derived from |
| 15 | +// this software without specific prior written permission. |
| 16 | +// |
| 17 | +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
| 18 | +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
| 19 | +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
| 20 | +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE |
| 21 | +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
| 22 | +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
| 23 | +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
| 24 | +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
| 25 | +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
| 26 | +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 27 | +// POSSIBILITY OF SUCH DAMAGE. |
| 28 | + |
| 29 | +#include <ur_controllers/twist_controller.hpp> |
| 30 | + |
| 31 | +namespace ur_controllers |
| 32 | +{ |
| 33 | +controller_interface::CallbackReturn TwistController::on_init() |
| 34 | +{ |
| 35 | + param_listener_ = std::make_shared<twist_controller::ParamListener>(get_node()); |
| 36 | + controller_params_ = param_listener_->get_params(); |
| 37 | + |
| 38 | + return controller_interface::CallbackReturn::SUCCESS; |
| 39 | +} |
| 40 | + |
| 41 | +controller_interface::CallbackReturn TwistController::on_configure(const rclcpp_lifecycle::State& /* previous_state */) |
| 42 | +{ |
| 43 | + twist_command_subscriber_ = get_node()->create_subscription<TwistStamped>( |
| 44 | + "~/twist", rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr<TwistStamped> msg) -> void { |
| 45 | + if (!subscriber_is_active_) { |
| 46 | + RCLCPP_WARN(get_node()->get_logger(), "Can't accept new commands. subscriber is inactive"); |
| 47 | + return; |
| 48 | + } |
| 49 | + if ((msg->header.stamp.sec == 0) && (msg->header.stamp.nanosec == 0)) { |
| 50 | + RCLCPP_WARN_ONCE(get_node()->get_logger(), "Received TwistStamped with zero timestamp, setting it to current " |
| 51 | + "time, this message will only be shown once"); |
| 52 | + msg->header.stamp = get_node()->now(); |
| 53 | + } |
| 54 | + |
| 55 | + if (msg->header.frame_id != controller_params_.tf_prefix + "base") { |
| 56 | + // TODO(urfeex): Support transforming the twist? |
| 57 | + RCLCPP_WARN(get_node()->get_logger(), |
| 58 | + "Received TwistStamped with frame_id '%s'. Currently, it is only supported to command twists in " |
| 59 | + "'%s'. The command will be ignored.", |
| 60 | + msg->header.frame_id.c_str(), (controller_params_.tf_prefix + "base").c_str()); |
| 61 | + return; |
| 62 | + } |
| 63 | + |
| 64 | + // TODO(urfeex): Check timestamp. Do not accept old commands. |
| 65 | + |
| 66 | + received_twist_msg_.set(*msg); |
| 67 | + }); |
| 68 | + |
| 69 | + return controller_interface::CallbackReturn::SUCCESS; |
| 70 | +} |
| 71 | + |
| 72 | +controller_interface::InterfaceConfiguration TwistController::command_interface_configuration() const |
| 73 | +{ |
| 74 | + // No command interfaces currently |
| 75 | + controller_interface::InterfaceConfiguration config; |
| 76 | + config.type = controller_interface::interface_configuration_type::INDIVIDUAL; |
| 77 | + |
| 78 | + const std::string tf_prefix = controller_params_.tf_prefix; |
| 79 | + config.names.push_back(tf_prefix + "twist/linear_velocity_x"); |
| 80 | + config.names.push_back(tf_prefix + "twist/linear_velocity_y"); |
| 81 | + config.names.push_back(tf_prefix + "twist/linear_velocity_z"); |
| 82 | + config.names.push_back(tf_prefix + "twist/angular_velocity_x"); |
| 83 | + config.names.push_back(tf_prefix + "twist/angular_velocity_y"); |
| 84 | + config.names.push_back(tf_prefix + "twist/angular_velocity_z"); |
| 85 | + |
| 86 | + return config; |
| 87 | +} |
| 88 | + |
| 89 | +controller_interface::InterfaceConfiguration TwistController::state_interface_configuration() const |
| 90 | +{ |
| 91 | + // TODO(urfeex): Add state interfaces for tcp speed |
| 92 | + |
| 93 | + controller_interface::InterfaceConfiguration config; |
| 94 | + config.type = controller_interface::interface_configuration_type::NONE; |
| 95 | + |
| 96 | + return config; |
| 97 | +} |
| 98 | + |
| 99 | +controller_interface::CallbackReturn TwistController::on_activate(const rclcpp_lifecycle::State& state) |
| 100 | +{ |
| 101 | + reset(); |
| 102 | + subscriber_is_active_ = true; |
| 103 | + |
| 104 | + return ControllerInterface::on_activate(state); |
| 105 | +} |
| 106 | + |
| 107 | +controller_interface::CallbackReturn TwistController::on_deactivate(const rclcpp_lifecycle::State&) |
| 108 | +{ |
| 109 | + subscriber_is_active_ = false; |
| 110 | + reset(); |
| 111 | + return CallbackReturn::SUCCESS; |
| 112 | +} |
| 113 | + |
| 114 | +controller_interface::return_type TwistController::update(const rclcpp::Time& /*time*/, |
| 115 | + const rclcpp::Duration& /*period*/) |
| 116 | +{ |
| 117 | + // In case we can't read from the subscriber's buffer, we will not update the command_msg_. |
| 118 | + auto current_cmd = received_twist_msg_.try_get(); |
| 119 | + if (current_cmd.has_value()) { |
| 120 | + command_msg_ = current_cmd.value(); |
| 121 | + } |
| 122 | + |
| 123 | + // TODO(urfeex): Check if the command_msg_ is valid, e.g., if the timestamp is not too old. |
| 124 | + |
| 125 | + bool success = true; |
| 126 | + success &= command_interfaces_[0].set_value(command_msg_.twist.linear.x); |
| 127 | + success &= command_interfaces_[1].set_value(command_msg_.twist.linear.y); |
| 128 | + success &= command_interfaces_[2].set_value(command_msg_.twist.linear.z); |
| 129 | + success &= command_interfaces_[3].set_value(command_msg_.twist.angular.x); |
| 130 | + success &= command_interfaces_[4].set_value(command_msg_.twist.angular.y); |
| 131 | + success &= command_interfaces_[5].set_value(command_msg_.twist.angular.z); |
| 132 | + |
| 133 | + if (!success) { |
| 134 | + RCLCPP_ERROR(get_node()->get_logger(), "Failed to write to command interfaces."); |
| 135 | + return controller_interface::return_type::ERROR; |
| 136 | + } |
| 137 | + |
| 138 | + return controller_interface::return_type::OK; |
| 139 | +} |
| 140 | + |
| 141 | +void TwistController::reset() |
| 142 | +{ |
| 143 | + command_msg_.twist.linear.x = 0.0; |
| 144 | + command_msg_.twist.linear.y = 0.0; |
| 145 | + command_msg_.twist.linear.z = 0.0; |
| 146 | + command_msg_.twist.angular.x = 0.0; |
| 147 | + command_msg_.twist.angular.y = 0.0; |
| 148 | + command_msg_.twist.angular.z = 0.0; |
| 149 | + received_twist_msg_.set(command_msg_); |
| 150 | +} |
| 151 | +} // namespace ur_controllers |
| 152 | + |
| 153 | +#include "pluginlib/class_list_macros.hpp" |
| 154 | + |
| 155 | +PLUGINLIB_EXPORT_CLASS(ur_controllers::TwistController, controller_interface::ControllerInterface) |
0 commit comments