Skip to content

Commit f45dda1

Browse files
urmahpurfeex
andauthored
Added commands to set pd controller gains and maximum joint torques (#342)
Co-authored-by: Felix Exner <[email protected]>
1 parent 9cecbff commit f45dda1

File tree

8 files changed

+266
-0
lines changed

8 files changed

+266
-0
lines changed

doc/architecture/script_command_interface.rst

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@ At the time of writing the ``ScriptCommandInterface`` provides the following fun
2121
<https://github.com/UniversalRobots/Universal_Robots_Client_Library/blob/master/examples/tool_contact_example.cpp>`_
2222
for more information.
2323
- ``setFrictionCompensation()``: Set friction compensation for torque command.
24+
- ``setPDControllerGains()``: Set PD gains for the PD control loop running in the external control script.
25+
- ``setMaxJointTorques()``: Set Max joint torques for the PD control loop running in the external control script.
2426

2527
Communication protocol
2628
----------------------
@@ -50,6 +52,8 @@ The robot reads from the "script_command_socket" expecting a 32 bit integer repr
5052
- 5: startToolContact
5153
- 6: endToolContact
5254
- 7: setFrictionCompensation
55+
- 8: setPDControllerGains
56+
- 9: setMaxJointTorques
5357
1-27 data fields specific to the command
5458
===== =====
5559

@@ -132,6 +136,25 @@ The robot reads from the "script_command_socket" expecting a 32 bit integer repr
132136
1 friction_compensation_enabled enable/disable friction compensation for torque command.
133137
===== =====
134138

139+
.. table:: With setPDControllerGains command
140+
:widths: auto
141+
142+
===== =====
143+
index meaning
144+
===== =====
145+
1-6 Kp gains for each joint, used in the PD control loop running in the external control script (floating point)
146+
7-12 Kd gains for each joint, used in the PD control loop running in the external control script (floating point)
147+
===== =====
148+
149+
.. table:: With setMaxJointTorques command
150+
:widths: auto
151+
152+
===== =====
153+
index meaning
154+
===== =====
155+
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)
156+
===== =====
157+
135158
.. note::
136159
In URScript the ``socket_read_binary_integer()`` function is used to read the data from the
137160
script command socket. The first index in that function's return value is the number of integers read,

examples/script_command_interface.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,12 @@ void sendScriptCommands()
7474
run_cmd("Disabling tool contact mode", []() { g_my_robot->getUrDriver()->endToolContact(); });
7575
run_cmd("Setting friction_compensation variable to `true`",
7676
[]() { g_my_robot->getUrDriver()->setFrictionCompensation(true); });
77+
run_cmd("Setting PD controller gains", []() {
78+
g_my_robot->getUrDriver()->setPDControllerGains({ 500.0, 500.0, 300.0, 124.0, 124.0, 124.0 },
79+
{ 44.72, 44.72, 34.64, 22.27, 22.27, 22.27 });
80+
});
81+
run_cmd("Setting max joint torques",
82+
[]() { g_my_robot->getUrDriver()->setMaxJointTorques({ 27.0, 27.0, 14.0, 4.5, 4.5, 4.5 }); });
7783
}
7884
URCL_LOG_INFO("Script command thread finished.");
7985
}

include/ur_client_library/control/script_command_interface.h

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,32 @@ class ScriptCommandInterface : public ReverseInterface
158158
*/
159159
bool setFrictionCompensation(const bool friction_compensation_enabled);
160160

161+
/*!
162+
* \brief Set gains for the PD controller running in the external control script. The PD controller computes joint
163+
* torques based on either tcp poses or joint poses and applies the torques to the robot using the torque_command
164+
* function. The gains can be used to change the response of the controller. Be aware that changing the controller
165+
* response can make it unstable.
166+
* The PD controller can be used without explicitly defining those gains, as it contains a set of default gains for
167+
* each robot model.
168+
*
169+
* \param kp A vector6d of proportional gains for each of the joints in the robot.
170+
* \param kd A vector6d of derivative gains for each of the joints in the robot.
171+
*
172+
* \returns True, if the write was performed successfully, false otherwise.
173+
*/
174+
bool setPDControllerGains(const urcl::vector6d_t* kp, const urcl::vector6d_t* kd);
175+
176+
/*!
177+
* \brief Set the maximum joint torques for the PD controller running in the external control script. The PD
178+
* controller will clamp the torques between +-max_joint_torques before aplying them to the robot using the
179+
* torque_command function.
180+
*
181+
* \param max_joint_torques A vector6d of the maximum joint torques for each of the joints.
182+
*
183+
* \returns True, if the write was performed successfully, false otherwise.
184+
*/
185+
bool setMaxJointTorques(const urcl::vector6d_t* max_joint_torques);
186+
161187
/*!
162188
* \brief Returns whether a client/robot is connected to this server.
163189
*
@@ -196,6 +222,8 @@ class ScriptCommandInterface : public ReverseInterface
196222
START_TOOL_CONTACT = 5, ///< Start detecting tool contact
197223
END_TOOL_CONTACT = 6, ///< End detecting tool contact
198224
SET_FRICTION_COMPENSATION = 7, ///< Set friction compensation
225+
SET_PD_CONTROLLER_GAINS = 8, ///< Set PD controller gains
226+
SET_MAX_JOINT_TORQUES = 9, ///< Set max joint torques
199227
};
200228

201229
bool client_connected_;

include/ur_client_library/ur/ur_driver.h

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -725,6 +725,32 @@ class UrDriver
725725
*/
726726
bool setFrictionCompensation(const bool friction_compensation_enabled);
727727

728+
/*!
729+
* \brief Set gains for the PD controller running in the external control script. The PD controller computes joint
730+
* torques based on either tcp poses or joint poses and applies the torques to the robot using the torque_command
731+
* function. The gains can be used to change the response of the controller. Be aware that changing the controller
732+
* response can make it unstable.
733+
* The PD controller can be used without explicitly defining those gains, as it contains a set of default gains for
734+
* each robot model.
735+
*
736+
* \param kp A vector6d of proportional gains for each of the joints in the robot.
737+
* \param kd A vector6d of derivative gains for each of the joints in the robot.
738+
*
739+
* \returns True, if the write was performed successfully, false otherwise.
740+
*/
741+
bool setPDControllerGains(const urcl::vector6d_t& kp, const urcl::vector6d_t& kd);
742+
743+
/*!
744+
* \brief Set the maximum joint torques for the PD controller running in the external control script. The PD
745+
* controller will clamp the torques between +-max_joint_torques before aplying them to the robot using the
746+
* torque_command function.
747+
*
748+
* \param max_joint_torques A vector6d of the maximum joint torques for each of the joints.
749+
*
750+
* \returns True, if the write was performed successfully, false otherwise.
751+
*/
752+
bool setMaxJointTorques(const urcl::vector6d_t& max_joint_torques);
753+
728754
/*!
729755
* \brief Write a keepalive signal only.
730756
*

resources/external_control.urscript

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,8 @@ END_FORCE_MODE = 4
5353
START_TOOL_CONTACT = 5
5454
END_TOOL_CONTACT = 6
5555
SET_FRICTION_COMPENSATION = 7
56+
SET_PD_CONTROLLER_GAINS = 8
57+
SET_MAX_JOINT_TORQUES = 9
5658
SCRIPT_COMMAND_DATA_DIMENSION = 28
5759

5860
FREEDRIVE_MODE_START = 1
@@ -757,6 +759,11 @@ thread script_commands():
757759
else:
758760
friction_compensation_enabled = True
759761
end
762+
elif command == SET_PD_CONTROLLER_GAINS:
763+
pd_controller_gains.kp = [raw_command[2] / MULT_jointstate, raw_command[3] / MULT_jointstate, raw_command[4] / MULT_jointstate, raw_command[5] / MULT_jointstate, raw_command[6] / MULT_jointstate, raw_command[7] / MULT_jointstate]
764+
pd_controller_gains.kd = [raw_command[8] / MULT_jointstate, raw_command[9] / MULT_jointstate, raw_command[10] / MULT_jointstate, raw_command[11] / MULT_jointstate, raw_command[12] / MULT_jointstate, raw_command[13] / MULT_jointstate]
765+
elif command == SET_MAX_JOINT_TORQUES:
766+
max_joint_torques = [raw_command[2] / MULT_jointstate, raw_command[3] / MULT_jointstate, raw_command[4] / MULT_jointstate, raw_command[5] / MULT_jointstate, raw_command[6] / MULT_jointstate, raw_command[7] / MULT_jointstate]
760767
end
761768
end
762769
end

src/control/script_command_interface.cpp

Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -245,6 +245,64 @@ bool ScriptCommandInterface::setFrictionCompensation(const bool friction_compens
245245
return server_.write(client_fd_, buffer, sizeof(buffer), written);
246246
}
247247

248+
bool ScriptCommandInterface::setPDControllerGains(const urcl::vector6d_t* kp, const urcl::vector6d_t* kd)
249+
{
250+
const int message_length = 13;
251+
uint8_t buffer[sizeof(int32_t) * MAX_MESSAGE_LENGTH];
252+
uint8_t* b_pos = buffer;
253+
254+
int32_t val = htobe32(toUnderlying(ScriptCommand::SET_PD_CONTROLLER_GAINS));
255+
b_pos += append(b_pos, val);
256+
257+
for (auto const& p_gain : *kp)
258+
{
259+
val = htobe32(static_cast<int32_t>(round(p_gain * MULT_JOINTSTATE)));
260+
b_pos += append(b_pos, val);
261+
}
262+
263+
for (auto const& d_gain : *kd)
264+
{
265+
val = htobe32(static_cast<int32_t>(round(d_gain * MULT_JOINTSTATE)));
266+
b_pos += append(b_pos, val);
267+
}
268+
269+
// writing zeros to allow usage with other script commands
270+
for (size_t i = message_length; i < MAX_MESSAGE_LENGTH; i++)
271+
{
272+
val = htobe32(0);
273+
b_pos += append(b_pos, val);
274+
}
275+
size_t written;
276+
277+
return server_.write(client_fd_, buffer, sizeof(buffer), written);
278+
}
279+
280+
bool ScriptCommandInterface::setMaxJointTorques(const urcl::vector6d_t* max_joint_torques)
281+
{
282+
const int message_length = 7;
283+
uint8_t buffer[sizeof(int32_t) * MAX_MESSAGE_LENGTH];
284+
uint8_t* b_pos = buffer;
285+
286+
int32_t val = htobe32(toUnderlying(ScriptCommand::SET_MAX_JOINT_TORQUES));
287+
b_pos += append(b_pos, val);
288+
289+
for (auto const& max_torque : *max_joint_torques)
290+
{
291+
val = htobe32(static_cast<int32_t>(round(max_torque * MULT_JOINTSTATE)));
292+
b_pos += append(b_pos, val);
293+
}
294+
295+
// writing zeros to allow usage with other script commands
296+
for (size_t i = message_length; i < MAX_MESSAGE_LENGTH; i++)
297+
{
298+
val = htobe32(0);
299+
b_pos += append(b_pos, val);
300+
}
301+
size_t written;
302+
303+
return server_.write(client_fd_, buffer, sizeof(buffer), written);
304+
}
305+
248306
bool ScriptCommandInterface::clientConnected()
249307
{
250308
return client_connected_;

src/ur/ur_driver.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -573,6 +573,54 @@ bool UrDriver::setFrictionCompensation(const bool friction_compensation_enabled)
573573
}
574574
}
575575

576+
bool UrDriver::setPDControllerGains(const urcl::vector6d_t& kp, const urcl::vector6d_t& kd)
577+
{
578+
if (!std::all_of(kp.begin(), kp.end(), [](double v) { return v >= 0.0; }))
579+
{
580+
throw InvalidRange("kp should be larger than zero");
581+
}
582+
583+
if (!std::all_of(kd.begin(), kd.end(), [](double v) { return v >= 0.0; }))
584+
{
585+
throw InvalidRange("kd should be larger than zero");
586+
}
587+
588+
if (script_command_interface_->clientConnected())
589+
{
590+
return script_command_interface_->setPDControllerGains(&kp, &kd);
591+
}
592+
else
593+
{
594+
URCL_LOG_ERROR("Script command interface is not running. Unable to set PD Controller gains.");
595+
return 0;
596+
}
597+
}
598+
599+
bool UrDriver::setMaxJointTorques(const urcl::vector6d_t& max_joint_torques)
600+
{
601+
const urcl::vector6d_t max_torques_for_robot_type =
602+
control::getMaxTorquesFromRobotType(primary_client_->getRobotType());
603+
if (!std::equal(max_joint_torques.begin(), max_joint_torques.end(), max_torques_for_robot_type.begin(),
604+
[](double v1, double v2) { return v1 <= v2 && v1 >= 0.0; }))
605+
{
606+
std::stringstream ss;
607+
ss << "The max joint torques should be smaller or equal to the maximum joint torques for the robot type and larger "
608+
"than zero. Provided max joint torques "
609+
<< max_joint_torques << " and maximum joint torques for the robot type " << max_torques_for_robot_type;
610+
throw InvalidRange(ss.str().c_str());
611+
}
612+
613+
if (script_command_interface_->clientConnected())
614+
{
615+
return script_command_interface_->setMaxJointTorques(&max_joint_torques);
616+
}
617+
else
618+
{
619+
URCL_LOG_ERROR("Script command interface is not running. Unable to set max joint torques.");
620+
return 0;
621+
}
622+
}
623+
576624
bool UrDriver::writeKeepalive(const RobotReceiveTimeout& robot_receive_timeout)
577625
{
578626
vector6d_t* fake = nullptr;

tests/test_script_command_interface.cpp

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -421,6 +421,76 @@ TEST_F(ScriptCommandInterfaceTest, test_set_friction_compensation)
421421
EXPECT_EQ(message_sum, expected_message_sum);
422422
}
423423

424+
TEST_F(ScriptCommandInterfaceTest, test_set_pd_controller_gains)
425+
{
426+
// Wait for the client to connect to the server
427+
waitForClientConnection();
428+
429+
urcl::vector6d_t kp = { 220.2, 220.2, 300.0, 10.32, 10.32, 10.32 };
430+
urcl::vector6d_t kd = { 29.68, 29.68, 35.0, 6.4, 6.4, 6.4 };
431+
script_command_interface_->setPDControllerGains(&kp, &kd);
432+
433+
int32_t command;
434+
std::vector<int32_t> message;
435+
client_->readMessage(command, message);
436+
437+
// 8 is set PD controller gains
438+
int32_t expected_command = 8;
439+
EXPECT_EQ(command, expected_command);
440+
441+
int32_t message_idx = 0;
442+
443+
for (auto& p_gain : kp)
444+
{
445+
const double received_gain = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
446+
EXPECT_EQ(p_gain, received_gain);
447+
message_idx = message_idx + 1;
448+
}
449+
450+
for (auto& d_gain : kd)
451+
{
452+
const double received_gain = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
453+
EXPECT_EQ(d_gain, received_gain);
454+
message_idx = message_idx + 1;
455+
}
456+
457+
// The rest of the message should be zero
458+
int32_t message_sum = std::accumulate(std::begin(message) + message_idx, std::end(message), 0);
459+
int32_t expected_message_sum = 0;
460+
EXPECT_EQ(message_sum, expected_message_sum);
461+
}
462+
463+
TEST_F(ScriptCommandInterfaceTest, test_set_max_joint_torques)
464+
{
465+
// Wait for the client to connect to the server
466+
waitForClientConnection();
467+
468+
urcl::vector6d_t max_joint_torques = { 100.0, 150.0, 21.2, 10.32, 10.32, 10.32 };
469+
script_command_interface_->setMaxJointTorques(&max_joint_torques);
470+
471+
int32_t command;
472+
std::vector<int32_t> message;
473+
client_->readMessage(command, message);
474+
475+
// 9 is set max joint torques
476+
int32_t expected_command = 9;
477+
EXPECT_EQ(command, expected_command);
478+
479+
int32_t message_idx = 0;
480+
481+
for (auto& max_torque : max_joint_torques)
482+
{
483+
const double received_max_torque = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
484+
EXPECT_EQ(max_torque, received_max_torque);
485+
message_idx = message_idx + 1;
486+
}
487+
488+
// The rest of the message should be zero
489+
int32_t message_sum = std::accumulate(std::begin(message) + message_idx, std::end(message), 0);
490+
int32_t expected_message_sum = 0;
491+
EXPECT_EQ(message_sum, expected_message_sum);
492+
}
493+
424494
int main(int argc, char* argv[])
425495
{
426496
::testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)