Skip to content

Commit fda52d5

Browse files
mergify[bot]URJalaurmarp
authored
Add force mode controller (#1049) (#1193)
This enables using the robot's force_mode in a standalone controller. Force mode can be enabled and parametrized using a service call provided by the controller. --------- Co-authored-by: URJala <[email protected]> Co-authored-by: urmarp <[email protected]>
1 parent 46f8aea commit fda52d5

20 files changed

+1938
-78
lines changed

ur_controllers/CMakeLists.txt

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@ endif()
88
find_package(ament_cmake REQUIRED)
99
find_package(angles REQUIRED)
1010
find_package(controller_interface REQUIRED)
11+
find_package(geometry_msgs REQUIRED)
1112
find_package(joint_trajectory_controller REQUIRED)
1213
find_package(lifecycle_msgs REQUIRED)
1314
find_package(pluginlib REQUIRED)
@@ -16,6 +17,8 @@ find_package(rcutils REQUIRED)
1617
find_package(realtime_tools REQUIRED)
1718
find_package(std_msgs REQUIRED)
1819
find_package(std_srvs REQUIRED)
20+
find_package(tf2_geometry_msgs REQUIRED)
21+
find_package(tf2_ros REQUIRED)
1922
find_package(ur_dashboard_msgs REQUIRED)
2023
find_package(ur_msgs REQUIRED)
2124
find_package(generate_parameter_library REQUIRED)
@@ -27,6 +30,7 @@ find_package(action_msgs REQUIRED)
2730
set(THIS_PACKAGE_INCLUDE_DEPENDS
2831
angles
2932
controller_interface
33+
geometry_msgs
3034
joint_trajectory_controller
3135
lifecycle_msgs
3236
pluginlib
@@ -35,6 +39,8 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
3539
realtime_tools
3640
std_msgs
3741
std_srvs
42+
tf2_geometry_msgs
43+
tf2_ros
3844
ur_dashboard_msgs
3945
ur_msgs
4046
generate_parameter_library
@@ -45,6 +51,10 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
4551

4652
include_directories(include)
4753

54+
generate_parameter_library(
55+
force_mode_controller_parameters
56+
src/force_mode_controller_parameters.yaml
57+
)
4858

4959
generate_parameter_library(
5060
gpio_controller_parameters
@@ -72,6 +82,7 @@ generate_parameter_library(
7282
)
7383

7484
add_library(${PROJECT_NAME} SHARED
85+
src/force_mode_controller.cpp
7586
src/scaled_joint_trajectory_controller.cpp
7687
src/speed_scaling_state_broadcaster.cpp
7788
src/gpio_controller.cpp
@@ -82,6 +93,7 @@ target_include_directories(${PROJECT_NAME} PRIVATE
8293
include
8394
)
8495
target_link_libraries(${PROJECT_NAME}
96+
force_mode_controller_parameters
8597
gpio_controller_parameters
8698
speed_scaling_state_broadcaster_parameters
8799
scaled_joint_trajectory_controller_parameters
@@ -124,4 +136,23 @@ ament_export_libraries(
124136
${PROJECT_NAME}
125137
)
126138

139+
if(BUILD_TESTING)
140+
find_package(ament_cmake_gmock REQUIRED)
141+
find_package(controller_manager REQUIRED)
142+
find_package(hardware_interface REQUIRED)
143+
find_package(ros2_control_test_assets REQUIRED)
144+
145+
add_definitions(-DTEST_FILES_DIRECTORY="${CMAKE_CURRENT_SOURCE_DIR}/test")
146+
ament_add_gmock(test_load_force_mode_controller
147+
test/test_load_force_mode_controller.cpp
148+
)
149+
target_link_libraries(test_load_force_mode_controller
150+
${PROJECT_NAME}
151+
)
152+
ament_target_dependencies(test_load_force_mode_controller
153+
controller_manager
154+
ros2_control_test_assets
155+
)
156+
endif()
157+
127158
ament_package()

ur_controllers/controller_plugins.xml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,11 @@
1414
This controller publishes the Tool IO.
1515
</description>
1616
</class>
17+
<class name="ur_controllers/ForceModeController" type="ur_controllers::ForceModeController" base_class_type="controller_interface::ControllerInterface">
18+
<description>
19+
Controller to use UR's force_mode.
20+
</description>
21+
</class>
1722
<class name="ur_controllers/PassthroughTrajectoryController" type="ur_controllers::PassthroughTrajectoryController" base_class_type="controller_interface::ControllerInterface">
1823
<description>
1924
This controller forwards a joint-based trajectory to the robot controller for interpolation.

ur_controllers/doc/index.rst

Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -264,3 +264,79 @@ Implementation details / dataflow
264264
* When the hardware reports that execution has been aborted (The ``passthrough_trajectory_abort``
265265
command interface), the action will be aborted.
266266
* When the action is preempted, execution on the hardware is preempted.
267+
268+
.. _force_mode_controller:
269+
270+
ur_controllers/ForceModeController
271+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
272+
273+
This controller activates the robot's *Force Mode*. This allows direct force control running on the
274+
robot control box. This controller basically interfaces the URScript function ``force_mode(...)``.
275+
276+
Force mode can be combined with (and only with) the :ref:`passthrough trajectory controller
277+
<passthrough_trajectory_controller>` in order to execute motions under a given force constraints.
278+
279+
.. note::
280+
This is not an admittance controller, as given force constraints in a certain Cartesian
281+
dimension will overwrite the motion commands in that dimension. E.g. when specifying a certain
282+
force in the base frame's ``z`` direction, any motion resulting from the move command in the
283+
base frame's ``z`` axis will not be executed.
284+
285+
Parameters
286+
""""""""""
287+
288+
+----------------------------------+--------+---------------+---------------------------------------------------------------------+
289+
| Parameter name | Type | Default value | Description |
290+
| | | | |
291+
+----------------------------------+--------+---------------+---------------------------------------------------------------------+
292+
| ``tf_prefix`` | string | <empty> | Urdf prefix of the corresponding arm |
293+
+----------------------------------+--------+---------------+---------------------------------------------------------------------+
294+
| ``check_io_successful_retries`` | int | 10 | Amount of retries for checking if setting force_mode was successful |
295+
+----------------------------------+--------+---------------+---------------------------------------------------------------------+
296+
297+
Service interface / usage
298+
"""""""""""""""""""""""""
299+
300+
The controller provides two services: One for activating force_mode and one for leaving it. To use
301+
those services, the controller has to be in ``active`` state.
302+
303+
* ``~/stop_force_mode [std_srvs/srv/Trigger]``: Stop force mode
304+
* ``~/start_force_mode [ur_msgs/srv/SetForceMode]``: Start force mode
305+
306+
In ``ur_msgs/srv/SetForceMode`` the fields have the following meanings:
307+
308+
task_frame
309+
All information (selection vector, wrench, limits, etc) will be considered to be relative
310+
to that pose. The pose's frame_id can be anything that is transformable to the robot's
311+
``base`` frame.
312+
selection_vector_<x,y,z,rx,ry,rz>
313+
1 means that the robot will be compliant in the corresponding axis of the task frame.
314+
wrench
315+
The forces/torques the robot will apply to its environment. The robot adjusts its position
316+
along/about compliant axis in order to achieve the specified force/torque. Values have no effect for non-
317+
compliant axes.
318+
Actual wrench applied may be lower than requested due to joint safety limits.
319+
type
320+
An integer [1;3] specifying how the robot interprets the force frame
321+
322+
1
323+
The force frame is transformed in a way such that its y-axis is aligned with a vector pointing
324+
from the robot tcp towards the origin of the force frame.
325+
2
326+
The force frame is not transformed.
327+
3
328+
The force frame is transformed in a way such that its x-axis is the projection of the robot tcp
329+
velocity vector onto the x-y plane of the force frame.
330+
speed_limits
331+
Maximum allowed tcp speed (relative to the task frame). This is **only relevant for axes marked as
332+
compliant** in the selection_vector.
333+
deviation_limits
334+
For **non-compliant axes**, these values are the maximum allowed deviation along/about an axis
335+
between the actual tcp position and the one set by the program.
336+
damping_factor
337+
Force mode damping factor. Sets the damping parameter in force mode. In range [0;1], default value is 0.025
338+
A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0
339+
is no damping, here the robot will maintain the speed.
340+
gain_scaling
341+
Force mode gain scaling factor. Scales the gain in force mode. scaling parameter is in range [0;2], default is 0.5.
342+
A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard surfaces.
Lines changed: 147 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,147 @@
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

ur_controllers/package.xml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424

2525
<depend>angles</depend>
2626
<depend>controller_interface</depend>
27+
<depend>geometry_msgs</depend>
2728
<depend>joint_trajectory_controller</depend>
2829
<depend>lifecycle_msgs</depend>
2930
<depend>pluginlib</depend>
@@ -32,12 +33,16 @@
3233
<depend>realtime_tools</depend>
3334
<depend>std_msgs</depend>
3435
<depend>std_srvs</depend>
36+
<depend>tf2_geometry_msgs</depend>
37+
<depend>tf2_ros</depend>
3538
<depend>ur_dashboard_msgs</depend>
3639
<depend>ur_msgs</depend>
3740
<depend>control_msgs</depend>
3841
<depend>trajectory_msgs</depend>
3942
<depend>action_msgs</depend>
4043

44+
<test_depend>hardware_interface_testing</test_depend>
45+
4146

4247
<export>
4348
<build_type>ament_cmake</build_type>

0 commit comments

Comments
 (0)