Skip to content

Commit 713b6d4

Browse files
urrskurmahpurfeex
committed
Added PD torque controller in joint space (#336)
The pd controller in joint space will accept joint targets and compute joint torques based on PD control scheme. Co-authored-by: Mads Holm Peters <mahp@universal-robots.com> Co-authored-by: Felix Exner <feex@universal-robots.com>
1 parent 6ec1ee0 commit 713b6d4

14 files changed

+728
-37
lines changed

doc/architecture/script_command_interface.rst

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@ At the time of writing the ``ScriptCommandInterface`` provides the following fun
2525
- ``setGravity()``: Set the gravity vector for the robot.
2626
- ``setTcpOffset()``: Set the TCP offset of the robot.
2727
- ``setFrictionScales()``: Set viscous and Coulomb friction scale factors for direct torque control.
28+
- ``setPDControllerGains()``: Set PD gains for the PD control loop running in the external control script.
29+
- ``setMaxJointTorques()``: Set Max joint torques for the PD control loop running in the external control script.
2830

2931
Communication protocol
3032
----------------------
@@ -58,6 +60,8 @@ The robot reads from the "script_command_socket" expecting a 32 bit integer repr
5860
- 9: setGravity
5961
- 10: setTcpOffset
6062
- 11: setFrictionScales
63+
- 12: setPDControllerGains
64+
- 13: setMaxJointTorques
6165
1-27 data fields specific to the command
6266
===== =====
6367

@@ -152,6 +156,25 @@ The robot reads from the "script_command_socket" expecting a 32 bit integer repr
152156
6-9 sensor_cog in m, displacement from the tool flange (3d floating point)
153157
===== =====
154158

159+
.. table:: With setPDControllerGains command
160+
:widths: auto
161+
162+
===== =====
163+
index meaning
164+
===== =====
165+
1-6 Kp gains for each joint, used in the PD control loop running in the external control script (floating point)
166+
7-12 Kd gains for each joint, used in the PD control loop running in the external control script (floating point)
167+
===== =====
168+
169+
.. table:: With setMaxJointTorques command
170+
:widths: auto
171+
172+
===== =====
173+
index meaning
174+
===== =====
175+
1-6 max_joint_torques for each joint, used to clamp the torques between +-max_joint_torques before applying them to the robot in the PD control loop running in the external control script (floating point)
176+
===== =====
177+
155178
.. table:: With setGravity command
156179
:widths: auto
157180

@@ -170,6 +193,8 @@ The robot reads from the "script_command_socket" expecting a 32 bit integer repr
170193
1-6 TCP offset as [x, y, z, rx, ry, rz] given in the flange coordinate system in SI units (meters and radians, floating point)
171194
===== =====
172195

196+
197+
173198
.. table:: With setFrictionScales command
174199
:widths: auto
175200

examples/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -62,3 +62,7 @@ target_link_libraries(instruction_executor ur_client_library::urcl)
6262
add_executable(external_fts_through_rtde
6363
external_fts_through_rtde.cpp)
6464
target_link_libraries(external_fts_through_rtde ur_client_library::urcl)
65+
66+
add_executable(pd_controller_example
67+
pd_controller_example.cpp)
68+
target_link_libraries(pd_controller_example ur_client_library::urcl)

examples/pd_controller_example.cpp

Lines changed: 225 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,225 @@
1+
// this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2+
3+
// -- BEGIN LICENSE BLOCK ----------------------------------------------
4+
// Copyright 2025 Universal Robots A/S
5+
//
6+
// Redistribution and use in source and binary forms, with or without
7+
// modification, are permitted provided that the following conditions are met:
8+
//
9+
// * Redistributions of source code must retain the above copyright
10+
// notice, this list of conditions and the following disclaimer.
11+
//
12+
// * Redistributions in binary form must reproduce the above copyright
13+
// notice, this list of conditions and the following disclaimer in the
14+
// documentation and/or other materials provided with the distribution.
15+
//
16+
// * Neither the name of the {copyright_holder} nor the names of its
17+
// contributors may be used to endorse or promote products derived from
18+
// this software without specific prior written permission.
19+
//
20+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
24+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30+
// POSSIBILITY OF SUCH DAMAGE.
31+
// -- END LICENSE BLOCK ------------------------------------------------
32+
33+
#include "ur_client_library/example_robot_wrapper.h"
34+
#include "ur_client_library/ur/dashboard_client.h"
35+
#include "ur_client_library/ur/ur_driver.h"
36+
#include "ur_client_library/types.h"
37+
#include "ur_client_library/ur/instruction_executor.h"
38+
39+
#include <iostream>
40+
#include <memory>
41+
#include <cmath>
42+
#include <signal.h>
43+
44+
using namespace urcl;
45+
46+
const std::string DEFAULT_ROBOT_IP = "192.168.56.101";
47+
const std::string SCRIPT_FILE = "resources/external_control.urscript";
48+
const std::string OUTPUT_RECIPE = "examples/resources/rtde_output_recipe.txt";
49+
const std::string INPUT_RECIPE = "examples/resources/rtde_input_recipe.txt";
50+
51+
std::unique_ptr<ExampleRobotWrapper> g_my_robot;
52+
53+
void signal_callback_handler(int signum)
54+
{
55+
std::cout << "Caught signal " << signum << std::endl;
56+
if (g_my_robot != nullptr)
57+
{
58+
// Stop control of the robot
59+
g_my_robot->getUrDriver()->stopControl();
60+
}
61+
// Terminate program
62+
exit(signum);
63+
}
64+
65+
struct DataStorage
66+
{
67+
std::vector<urcl::vector6d_t> target;
68+
std::vector<urcl::vector6d_t> actual;
69+
std::vector<double> time;
70+
71+
void write_to_file(const std::string& filename)
72+
{
73+
std::fstream output(filename, std::ios::out);
74+
output << "timestamp,target0,target1,target2,target3,target4,target5,actual0,actual1,actual2,"
75+
"actual3,actual4,actual5\n";
76+
for (size_t i = 0; i < time.size(); ++i)
77+
{
78+
output << time[i];
79+
for (auto& t : target[i])
80+
{
81+
output << "," << t;
82+
}
83+
for (auto& a : actual[i])
84+
{
85+
output << "," << a;
86+
}
87+
output << "\n";
88+
}
89+
output.close();
90+
}
91+
};
92+
93+
bool pd_control_loop(DataStorage& data_storage, const std::string& actual_data_name,
94+
const comm::ControlMode control_mode, const urcl::vector6d_t& amplitude)
95+
{
96+
const int32_t running_time = 13;
97+
double time = 0.0;
98+
99+
// Reserve space for expected amount of data
100+
data_storage.actual.reserve(running_time * 500);
101+
data_storage.target.reserve(running_time * 500);
102+
data_storage.time.reserve(running_time * 500);
103+
104+
urcl::vector6d_t actual, target, start = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
105+
106+
rtde_interface::DataPackage data_pkg(g_my_robot->getUrDriver()->getRTDEOutputRecipe());
107+
108+
bool first_pass = true;
109+
while (time < running_time)
110+
{
111+
const auto t_start = std::chrono::high_resolution_clock::now();
112+
// Read latest RTDE package. This will block for a hard-coded timeout (see UrDriver), so the
113+
// robot will effectively be in charge of setting the frequency of this loop.
114+
// In a real-world application this thread should be scheduled with real-time priority in order
115+
// to ensure that this is called in time.
116+
if (!g_my_robot->getUrDriver()->getDataPackage(data_pkg))
117+
{
118+
URCL_LOG_WARN("Could not get fresh data package from robot");
119+
return false;
120+
}
121+
// Read current joint positions from robot data
122+
if (!data_pkg.getData(actual_data_name, actual))
123+
{
124+
// This throwing should never happen unless misconfigured
125+
std::string error_msg =
126+
"Did not find '" + actual_data_name + "' in data sent from robot. This should not happen!";
127+
throw std::runtime_error(error_msg);
128+
}
129+
130+
if (first_pass)
131+
{
132+
target = actual;
133+
start = actual;
134+
for (size_t i = 0; i < start.size(); ++i)
135+
{
136+
start[i] = start[i] - amplitude[i];
137+
}
138+
first_pass = false;
139+
}
140+
141+
for (size_t i = 0; i < target.size(); ++i)
142+
{
143+
target[i] = start[i] + amplitude[i] * cos(time);
144+
}
145+
146+
// Setting the RobotReceiveTimeout time is for example purposes only. This will make the example running more
147+
// reliable on non-realtime systems. Use with caution in productive applications.
148+
bool ret = g_my_robot->getUrDriver()->writeJointCommand(target, control_mode, RobotReceiveTimeout::millisec(100));
149+
if (!ret)
150+
{
151+
URCL_LOG_ERROR("Could not send joint command. Make sure that the robot is in remote control mode and connected "
152+
"with a network cable.");
153+
return false;
154+
}
155+
156+
// Increment time and log data
157+
const auto t_end = std::chrono::high_resolution_clock::now();
158+
const double elapsed_time_ms = std::chrono::duration<double, std::milli>(t_end - t_start).count() / 1000;
159+
time = time + elapsed_time_ms;
160+
data_storage.actual.push_back(actual);
161+
data_storage.target.push_back(target);
162+
data_storage.time.push_back(time);
163+
}
164+
165+
return true;
166+
}
167+
168+
int main(int argc, char* argv[])
169+
{
170+
// This will make sure that we stop controlling the robot if the user presses ctrl-c
171+
signal(SIGINT, signal_callback_handler);
172+
173+
urcl::setLogLevel(urcl::LogLevel::INFO);
174+
175+
// Parse the ip arguments if given
176+
std::string robot_ip = DEFAULT_ROBOT_IP;
177+
if (argc > 1)
178+
{
179+
robot_ip = std::string(argv[1]);
180+
}
181+
182+
const bool headless_mode = true;
183+
g_my_robot = std::make_unique<ExampleRobotWrapper>(robot_ip, OUTPUT_RECIPE, INPUT_RECIPE, headless_mode);
184+
185+
if (!g_my_robot->isHealthy())
186+
{
187+
URCL_LOG_ERROR("Something in the robot initialization went wrong. Exiting. Please check the output above.");
188+
return 1;
189+
}
190+
191+
{
192+
auto robot_version = g_my_robot->getUrDriver()->getVersion();
193+
if (robot_version < urcl::VersionInformation::fromString("5.23.0") ||
194+
(robot_version.major > 5 && robot_version < urcl::VersionInformation::fromString("10.10.0")))
195+
{
196+
URCL_LOG_ERROR("This example requires a robot with at least version 5.23.0 / 10.10.0. Your robot has version %s.",
197+
robot_version.toString().c_str());
198+
return 0;
199+
}
200+
}
201+
202+
auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->getUrDriver());
203+
204+
URCL_LOG_INFO("Move the robot to initial position");
205+
instruction_executor->moveJ(urcl::vector6d_t{ 0, -1.67, -0.65, -1.59, 1.61, 5.09 }, 0.5, 0.2, 5);
206+
207+
DataStorage joint_controller_storage;
208+
209+
// Once RTDE communication is started, we have to make sure to read from the interface buffer, as
210+
// otherwise we will get pipeline overflows. Therefor, do this directly before starting your main
211+
// loop.
212+
g_my_robot->getUrDriver()->startRTDECommunication();
213+
URCL_LOG_INFO("Start controlling the robot using the PD controller");
214+
const bool completed_joint_control =
215+
pd_control_loop(joint_controller_storage, "actual_q", comm::ControlMode::MODE_PD_CONTROLLER_JOINT,
216+
{ 0.2, 0.2, 0.2, 0.2, 0.2, 0.2 });
217+
if (!completed_joint_control)
218+
{
219+
URCL_LOG_ERROR("Didn't complete pd control in joint space");
220+
g_my_robot->getUrDriver()->stopControl();
221+
return 1;
222+
}
223+
224+
return 0;
225+
}

examples/script_command_interface.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,13 @@ void sendScriptCommands()
8989
{ 0.8, 0.8, 0.7, 0.8, 0.8, 0.8 });
9090
});
9191
}
92+
run_cmd("Setting PD controller gains", []() {
93+
g_my_robot->getUrDriver()->setPDControllerGains({ 500.0, 500.0, 300.0, 124.0, 124.0, 124.0 },
94+
{ 44.72, 44.72, 34.64, 22.27, 22.27, 22.27 });
95+
});
96+
// The following will have no effect on PolyScope < 5.23 / 10.10
97+
run_cmd("Setting max joint torques",
98+
[]() { g_my_robot->getUrDriver()->setMaxJointTorques({ 27.0, 27.0, 14.0, 4.5, 4.5, 4.5 }); });
9299
}
93100
URCL_LOG_INFO("Script command thread finished.");
94101
}

include/ur_client_library/comm/control_mode.h

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,8 @@ enum class ControlMode : int32_t
5454
MODE_TOOL_IN_CONTACT =
5555
7, ///< Used only internally in the script, when robot is in tool contact, clear by endToolContact()
5656
MODE_TORQUE = 8, ///< Set when torque control is active.
57-
END ///< This is not an actual control mode, but used internally to get the number of control modes
57+
MODE_PD_CONTROLLER_JOINT = 9, ///< Set when PD control in joint space is active
58+
END ///< This is not an actual control mode, but used internally to get the number of control modes
5859
};
5960

6061
/*!
@@ -65,8 +66,8 @@ class ControlModeTypes
6566
public:
6667
// Control modes that require realtime communication
6768
static const inline std::vector<ControlMode> REALTIME_CONTROL_MODES = {
68-
ControlMode::MODE_SERVOJ, ControlMode::MODE_SPEEDJ, ControlMode::MODE_SPEEDL, ControlMode::MODE_POSE,
69-
ControlMode::MODE_TORQUE
69+
ControlMode::MODE_SERVOJ, ControlMode::MODE_SPEEDJ, ControlMode::MODE_SPEEDL,
70+
ControlMode::MODE_POSE, ControlMode::MODE_TORQUE, ControlMode::MODE_PD_CONTROLLER_JOINT
7071
};
7172

7273
// Control modes that doesn't require realtime communication

include/ur_client_library/control/script_command_interface.h

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -222,6 +222,32 @@ class ScriptCommandInterface : public ReverseInterface
222222
const vector3d_t& sensor_measuring_offset = { 0.0, 0.0, 0.0 },
223223
const vector3d_t& sensor_cog = { 0.0, 0.0, 0.0 });
224224

225+
/*!
226+
* \brief Set gains for the PD controller running in the external control script. The PD controller computes joint
227+
* torques based on either tcp poses or joint poses and applies the torques to the robot using the direct_torque
228+
* function. The gains can be used to change the response of the controller. Be aware that changing the controller
229+
* response can make it unstable.
230+
* The PD controller can be used without explicitly defining those gains, as it contains a set of default gains for
231+
* each robot model.
232+
*
233+
* \param kp A vector6d of proportional gains for each of the joints in the robot.
234+
* \param kd A vector6d of derivative gains for each of the joints in the robot.
235+
*
236+
* \returns True, if the write was performed successfully, false otherwise.
237+
*/
238+
bool setPDControllerGains(const urcl::vector6d_t* kp, const urcl::vector6d_t* kd);
239+
240+
/*!
241+
* \brief Set the maximum joint torques for the PD controller running in the external control script. The PD
242+
* controller will clamp the torques between +-max_joint_torques before aplying them to the robot using the
243+
* direct_torque function.
244+
*
245+
* \param max_joint_torques A vector6d of the maximum joint torques for each of the joints.
246+
*
247+
* \returns True, if the write was performed successfully, false otherwise.
248+
*/
249+
bool setMaxJointTorques(const urcl::vector6d_t* max_joint_torques);
250+
225251
/*!
226252
* \brief Returns whether a client/robot is connected to this server.
227253
*
@@ -264,6 +290,8 @@ class ScriptCommandInterface : public ReverseInterface
264290
SET_GRAVITY = 9, ///< Set gravity vector
265291
SET_TCP_OFFSET = 10, ///< Set TCP offset
266292
SET_FRICTION_SCALES = 11, ///< Set viscous and Coulomb friction scales for direct_torque
293+
SET_PD_CONTROLLER_GAINS = 12, ///< Set PD controller gains
294+
SET_MAX_JOINT_TORQUES = 13, ///< Set max joint torques
267295
};
268296

269297
/*!

0 commit comments

Comments
 (0)