Skip to content

Commit 8d4ba94

Browse files
authored
Freedrive Controller (#1114)
This controller allows activating freedrive mode by continuously publishing an a topic
1 parent d465561 commit 8d4ba94

24 files changed

+777
-15
lines changed

Diff for: ur_controllers/CMakeLists.txt

+17
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,11 @@ generate_parameter_library(
7171
src/scaled_joint_trajectory_controller_parameters.yaml
7272
)
7373

74+
generate_parameter_library(
75+
freedrive_mode_controller_parameters
76+
src/freedrive_mode_controller_parameters.yaml
77+
)
78+
7479
generate_parameter_library(
7580
passthrough_trajectory_controller_parameters
7681
src/passthrough_trajectory_controller_parameters.yaml
@@ -85,6 +90,7 @@ add_library(${PROJECT_NAME} SHARED
8590
src/force_mode_controller.cpp
8691
src/scaled_joint_trajectory_controller.cpp
8792
src/speed_scaling_state_broadcaster.cpp
93+
src/freedrive_mode_controller.cpp
8894
src/gpio_controller.cpp
8995
src/passthrough_trajectory_controller.cpp
9096
src/ur_configuration_controller.cpp)
@@ -97,6 +103,7 @@ target_link_libraries(${PROJECT_NAME}
97103
gpio_controller_parameters
98104
speed_scaling_state_broadcaster_parameters
99105
scaled_joint_trajectory_controller_parameters
106+
freedrive_mode_controller_parameters
100107
passthrough_trajectory_controller_parameters
101108
ur_configuration_controller_parameters
102109
)
@@ -153,6 +160,16 @@ if(BUILD_TESTING)
153160
controller_manager
154161
ros2_control_test_assets
155162
)
163+
ament_add_gmock(test_load_freedrive_mode_controller
164+
test/test_load_freedrive_mode_controller.cpp
165+
)
166+
target_link_libraries(test_load_freedrive_mode_controller
167+
${PROJECT_NAME}
168+
)
169+
ament_target_dependencies(test_load_freedrive_mode_controller
170+
controller_manager
171+
ros2_control_test_assets
172+
)
156173
endif()
157174

158175
ament_package()

Diff for: ur_controllers/controller_plugins.xml

+5
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,11 @@
1919
Controller to use UR's force_mode.
2020
</description>
2121
</class>
22+
<class name="ur_controllers/FreedriveModeController" type="ur_controllers::FreedriveModeController" base_class_type="controller_interface::ControllerInterface">
23+
<description>
24+
This controller handles the activation of the freedrive mode.
25+
</description>
26+
</class>
2227
<class name="ur_controllers/PassthroughTrajectoryController" type="ur_controllers::PassthroughTrajectoryController" base_class_type="controller_interface::ControllerInterface">
2328
<description>
2429
This controller forwards a joint-based trajectory to the robot controller for interpolation.

Diff for: ur_controllers/doc/index.rst

+38
Original file line numberDiff line numberDiff line change
@@ -340,3 +340,41 @@ damping_factor
340340
gain_scaling
341341
Force mode gain scaling factor. Scales the gain in force mode. scaling parameter is in range [0;2], default is 0.5.
342342
A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard surfaces.
343+
344+
.. _freedrive_mode_controller:
345+
346+
ur_controllers/FreedriveModeController
347+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
348+
349+
This controller activates the robot's *Freedrive Mode*, allowing to manually move the robot' joints.
350+
This controller can't be combined with any other motion controller.
351+
352+
Parameters
353+
""""""""""
354+
355+
+----------------------+--------+---------------+---------------------------------------------------------------------------------------+
356+
| Parameter name | Type | Default value | Description |
357+
| | | | |
358+
+----------------------+--------+---------------+---------------------------------------------------------------------------------------+
359+
| ``tf_prefix`` | string | <empty> | Urdf prefix of the corresponding arm |
360+
+----------------------+--------+---------------+---------------------------------------------------------------------------------------+
361+
| ``inactive_timeout`` | int | 1 | Time interval (in seconds) of message inactivity after which freedrive is deactivated |
362+
+----------------------+--------+---------------+---------------------------------------------------------------------------------------+
363+
364+
Usage
365+
"""""
366+
367+
The controller provides the ``~/enable_freedrive_mode`` topic of type ``[std_msgs/msg/Bool]`` for handling activation and deactivation:
368+
369+
* to start and keep freedrive active, you'll have to frequently publish a ``True`` msg on the indicated topic.
370+
If no further messages are received by the controller within the ``inactive_timeout`` seconds,
371+
freedrive mode will be deactivated. Hence, it is recommended to publish a ``True`` message at least every
372+
``inactive_timeout/2`` seconds.
373+
374+
.. code-block::
375+
376+
ros2 topic pub --rate 2 /freedrive_mode_controller/enable_freedrive_mode std_msgs/msg/Bool "{data: true}"
377+
378+
* to deactivate freedrive mode is enough to publish a ``False`` msg on the indicated topic or
379+
to deactivate the controller or to stop publishing ``True`` on the enable topic and wait for the
380+
controller timeout.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,130 @@
1+
// Copyright 2024, 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 Vincenzo Di Pentima [email protected]
33+
* \date 2024-09-26
34+
*/
35+
//----------------------------------------------------------------------
36+
#ifndef UR_CONTROLLERS__FREEDRIVE_MODE_CONTROLLER_HPP_
37+
#define UR_CONTROLLERS__FREEDRIVE_MODE_CONTROLLER_HPP_
38+
39+
#pragma once
40+
41+
#include <memory>
42+
#include <string>
43+
#include <vector>
44+
#include <thread>
45+
#include <mutex>
46+
47+
#include <controller_interface/controller_interface.hpp>
48+
#include <rclcpp/rclcpp.hpp>
49+
#include <rclcpp_action/server.hpp>
50+
#include <rclcpp_action/create_server.hpp>
51+
#include <rclcpp_action/server_goal_handle.hpp>
52+
#include <rclcpp/time.hpp>
53+
#include <rclcpp/duration.hpp>
54+
#include "std_msgs/msg/bool.hpp"
55+
56+
#include "freedrive_mode_controller_parameters.hpp"
57+
58+
namespace ur_controllers
59+
{
60+
enum CommandInterfaces
61+
{
62+
FREEDRIVE_MODE_ASYNC_SUCCESS = 0u,
63+
FREEDRIVE_MODE_ENABLE = 1,
64+
FREEDRIVE_MODE_ABORT = 2,
65+
};
66+
67+
using namespace std::chrono_literals; // NOLINT
68+
69+
class FreedriveModeController : public controller_interface::ControllerInterface
70+
{
71+
public:
72+
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
73+
74+
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
75+
76+
// Change the input for the update function
77+
controller_interface::return_type update(const rclcpp::Time& time, const rclcpp::Duration& period) override;
78+
79+
CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
80+
81+
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
82+
83+
CallbackReturn on_cleanup(const rclcpp_lifecycle::State& previous_state) override;
84+
85+
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
86+
87+
CallbackReturn on_init() override;
88+
89+
private:
90+
// Command interfaces: optional is used only to avoid adding reference initialization
91+
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> async_success_command_interface_;
92+
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> enable_command_interface_;
93+
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>> abort_command_interface_;
94+
95+
std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Bool>> enable_freedrive_mode_sub_;
96+
97+
rclcpp::TimerBase::SharedPtr freedrive_sub_timer_; ///< Timer to check for timeout on input
98+
mutable std::chrono::seconds timeout_interval_;
99+
void freedrive_cmd_callback(const std_msgs::msg::Bool::SharedPtr msg);
100+
101+
std::shared_ptr<freedrive_mode_controller::ParamListener> freedrive_param_listener_;
102+
freedrive_mode_controller::Params freedrive_params_;
103+
104+
std::atomic<bool> freedrive_active_;
105+
std::atomic<bool> change_requested_;
106+
std::atomic<double> async_state_;
107+
std::atomic<double> first_log_;
108+
std::atomic<double> timer_started_;
109+
110+
void start_timer();
111+
void timeout_callback();
112+
113+
std::thread logging_thread_;
114+
std::atomic<bool> logging_thread_running_;
115+
std::atomic<bool> logging_requested_;
116+
std::condition_variable logging_condition_;
117+
std::mutex log_mutex_;
118+
void log_task();
119+
void start_logging_thread();
120+
void stop_logging_thread();
121+
122+
static constexpr double ASYNC_WAITING = 2.0;
123+
/**
124+
* @brief wait until a command interface isn't in state ASYNC_WAITING anymore or until the parameter maximum_retries
125+
* have been reached
126+
*/
127+
bool waitForAsyncCommand(std::function<double(void)> get_value);
128+
};
129+
} // namespace ur_controllers
130+
#endif // UR_CONTROLLERS__PASSTHROUGH_TRAJECTORY_CONTROLLER_HPP_

0 commit comments

Comments
 (0)