|
| 1 | +// Copyright 2023, FZI Forschungszentrum Informatik, Created on behalf of 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 | +//---------------------------------------------------------------------- |
| 30 | +/*!\file |
| 31 | + * |
| 32 | + * \author Felix Exner [email protected] |
| 33 | + * \date 2023-06-29 |
| 34 | + */ |
| 35 | +//---------------------------------------------------------------------- |
| 36 | + |
| 37 | +#pragma once |
| 38 | +#include <tf2_ros/buffer.h> |
| 39 | +#include <tf2_ros/transform_listener.h> |
| 40 | +#include <realtime_tools/realtime_buffer.h> |
| 41 | +#include <array> |
| 42 | +#include <memory> |
| 43 | + |
| 44 | +#include <controller_interface/controller_interface.hpp> |
| 45 | +#include <geometry_msgs/msg/pose_stamped.hpp> |
| 46 | +#include <rclcpp/rclcpp.hpp> |
| 47 | +#include <std_srvs/srv/trigger.hpp> |
| 48 | +#include <ur_msgs/srv/set_force_mode.hpp> |
| 49 | + |
| 50 | +#include "force_mode_controller_parameters.hpp" |
| 51 | + |
| 52 | +namespace ur_controllers |
| 53 | +{ |
| 54 | +enum CommandInterfaces |
| 55 | +{ |
| 56 | + FORCE_MODE_TASK_FRAME_X = 0u, |
| 57 | + FORCE_MODE_TASK_FRAME_Y = 1, |
| 58 | + FORCE_MODE_TASK_FRAME_Z = 2, |
| 59 | + FORCE_MODE_TASK_FRAME_RX = 3, |
| 60 | + FORCE_MODE_TASK_FRAME_RY = 4, |
| 61 | + FORCE_MODE_TASK_FRAME_RZ = 5, |
| 62 | + FORCE_MODE_SELECTION_VECTOR_X = 6, |
| 63 | + FORCE_MODE_SELECTION_VECTOR_Y = 7, |
| 64 | + FORCE_MODE_SELECTION_VECTOR_Z = 8, |
| 65 | + FORCE_MODE_SELECTION_VECTOR_RX = 9, |
| 66 | + FORCE_MODE_SELECTION_VECTOR_RY = 10, |
| 67 | + FORCE_MODE_SELECTION_VECTOR_RZ = 11, |
| 68 | + FORCE_MODE_WRENCH_X = 12, |
| 69 | + FORCE_MODE_WRENCH_Y = 13, |
| 70 | + FORCE_MODE_WRENCH_Z = 14, |
| 71 | + FORCE_MODE_WRENCH_RX = 15, |
| 72 | + FORCE_MODE_WRENCH_RY = 16, |
| 73 | + FORCE_MODE_WRENCH_RZ = 17, |
| 74 | + FORCE_MODE_TYPE = 18, |
| 75 | + FORCE_MODE_LIMITS_X = 19, |
| 76 | + FORCE_MODE_LIMITS_Y = 20, |
| 77 | + FORCE_MODE_LIMITS_Z = 21, |
| 78 | + FORCE_MODE_LIMITS_RX = 22, |
| 79 | + FORCE_MODE_LIMITS_RY = 23, |
| 80 | + FORCE_MODE_LIMITS_RZ = 24, |
| 81 | + FORCE_MODE_ASYNC_SUCCESS = 25, |
| 82 | + FORCE_MODE_DISABLE_CMD = 26, |
| 83 | + FORCE_MODE_DAMPING = 27, |
| 84 | + FORCE_MODE_GAIN_SCALING = 28, |
| 85 | +}; |
| 86 | +enum StateInterfaces |
| 87 | +{ |
| 88 | + INITIALIZED_FLAG = 0u, |
| 89 | +}; |
| 90 | + |
| 91 | +struct ForceModeParameters |
| 92 | +{ |
| 93 | + std::array<double, 6> task_frame; |
| 94 | + std::array<double, 6> selection_vec; |
| 95 | + std::array<double, 6> limits; |
| 96 | + geometry_msgs::msg::Wrench wrench; |
| 97 | + double type; |
| 98 | + double damping_factor; |
| 99 | + double gain_scaling; |
| 100 | +}; |
| 101 | + |
| 102 | +class ForceModeController : public controller_interface::ControllerInterface |
| 103 | +{ |
| 104 | +public: |
| 105 | + controller_interface::InterfaceConfiguration command_interface_configuration() const override; |
| 106 | + |
| 107 | + controller_interface::InterfaceConfiguration state_interface_configuration() const override; |
| 108 | + |
| 109 | + controller_interface::return_type update(const rclcpp::Time& time, const rclcpp::Duration& period) override; |
| 110 | + |
| 111 | + CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override; |
| 112 | + |
| 113 | + CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override; |
| 114 | + |
| 115 | + CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override; |
| 116 | + |
| 117 | + CallbackReturn on_init() override; |
| 118 | + |
| 119 | + CallbackReturn on_cleanup(const rclcpp_lifecycle::State& previous_state) override; |
| 120 | + |
| 121 | +private: |
| 122 | + bool setForceMode(const ur_msgs::srv::SetForceMode::Request::SharedPtr req, |
| 123 | + ur_msgs::srv::SetForceMode::Response::SharedPtr resp); |
| 124 | + bool disableForceMode(const std_srvs::srv::Trigger::Request::SharedPtr req, |
| 125 | + std_srvs::srv::Trigger::Response::SharedPtr resp); |
| 126 | + rclcpp::Service<ur_msgs::srv::SetForceMode>::SharedPtr set_force_mode_srv_; |
| 127 | + rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr disable_force_mode_srv_; |
| 128 | + |
| 129 | + std::unique_ptr<tf2_ros::Buffer> tf_buffer_; |
| 130 | + std::unique_ptr<tf2_ros::TransformListener> tf_listener_; |
| 131 | + |
| 132 | + std::shared_ptr<force_mode_controller::ParamListener> param_listener_; |
| 133 | + force_mode_controller::Params params_; |
| 134 | + |
| 135 | + realtime_tools::RealtimeBuffer<ForceModeParameters> force_mode_params_buffer_; |
| 136 | + std::atomic<bool> force_mode_active_; |
| 137 | + std::atomic<bool> change_requested_; |
| 138 | + std::atomic<double> async_state_; |
| 139 | + |
| 140 | + static constexpr double ASYNC_WAITING = 2.0; |
| 141 | + /** |
| 142 | + * @brief wait until a command interface isn't in state ASYNC_WAITING anymore or until the parameter maximum_retries |
| 143 | + * have been reached |
| 144 | + */ |
| 145 | + bool waitForAsyncCommand(std::function<double(void)> get_value); |
| 146 | +}; |
| 147 | +} // namespace ur_controllers |
0 commit comments