Skip to content

Commit 15ae64d

Browse files
urmahpurfeex
authored andcommitted
Added commands to set pd controller gains and maximum joint torques (#342)
Co-authored-by: Felix Exner <feex@universal-robots.com>
1 parent 9d88d2a commit 15ae64d

File tree

8 files changed

+266
-2
lines changed

8 files changed

+266
-2
lines changed

doc/architecture/script_command_interface.rst

Lines changed: 22 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

@@ -150,6 +154,24 @@ The robot reads from the "script_command_socket" expecting a 32 bit integer repr
150154
2 sensor_mass in kg (floating point)
151155
3-5 sensor_mesurement_offset in m, displacement from the tool flange (3d floating point)
152156
6-9 sensor_cog in m, displacement from the tool flange (3d floating point)
157+
158+
.. table:: With setPDControllerGains command
159+
:widths: auto
160+
161+
===== =====
162+
index meaning
163+
===== =====
164+
1-6 Kp gains for each joint, used in the PD control loop running in the external control script (floating point)
165+
7-12 Kd gains for each joint, used in the PD control loop running in the external control script (floating point)
166+
===== =====
167+
168+
.. table:: With setMaxJointTorques command
169+
:widths: auto
170+
171+
===== =====
172+
index meaning
173+
===== =====
174+
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)
153175
===== =====
154176

155177
.. table:: With setGravity command

examples/script_command_interface.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,12 @@ 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+
run_cmd("Setting max joint torques",
97+
[]() { g_my_robot->getUrDriver()->setMaxJointTorques({ 27.0, 27.0, 14.0, 4.5, 4.5, 4.5 }); });
9298
}
9399
URCL_LOG_INFO("Script command thread finished.");
94100
}

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
/*!

include/ur_client_library/ur/ur_driver.h

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -819,6 +819,32 @@ class UrDriver
819819
const vector3d_t& sensor_measuring_offset = { 0.0, 0.0, 0.0 },
820820
const vector3d_t& sensor_cog = { 0.0, 0.0, 0.0 });
821821

822+
/*!
823+
* \brief Set gains for the PD controller running in the external control script. The PD controller computes joint
824+
* torques based on either tcp poses or joint poses and applies the torques to the robot using the direct_torque
825+
* function. The gains can be used to change the response of the controller. Be aware that changing the controller
826+
* response can make it unstable.
827+
* The PD controller can be used without explicitly defining those gains, as it contains a set of default gains for
828+
* each robot model.
829+
*
830+
* \param kp A vector6d of proportional gains for each of the joints in the robot.
831+
* \param kd A vector6d of derivative gains for each of the joints in the robot.
832+
*
833+
* \returns True, if the write was performed successfully, false otherwise.
834+
*/
835+
bool setPDControllerGains(const urcl::vector6d_t& kp, const urcl::vector6d_t& kd);
836+
837+
/*!
838+
* \brief Set the maximum joint torques for the PD controller running in the external control script. The PD
839+
* controller will clamp the torques between +-max_joint_torques before aplying them to the robot using the
840+
* direct_torque function.
841+
*
842+
* \param max_joint_torques A vector6d of the maximum joint torques for each of the joints.
843+
*
844+
* \returns True, if the write was performed successfully, false otherwise.
845+
*/
846+
bool setMaxJointTorques(const urcl::vector6d_t& max_joint_torques);
847+
822848
/*!
823849
* \brief Write a keepalive signal only.
824850
*

resources/external_control.urscript

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,8 @@ FT_RTDE_INPUT_ENABLE = 8
6060
SET_GRAVITY = 9
6161
SET_TCP_OFFSET = 10
6262
SET_FRICTION_SCALES = 11
63+
SET_PD_CONTROLLER_GAINS = 12
64+
SET_MAX_JOINT_TORQUES = 13
6365
SCRIPT_COMMAND_DATA_DIMENSION = 28
6466

6567
FREEDRIVE_MODE_START = 1
@@ -901,6 +903,11 @@ thread script_commands():
901903
elif command == SET_TCP_OFFSET:
902904
tcp_offset = p[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]
903905
set_tcp(tcp_offset)
906+
elif command == SET_PD_CONTROLLER_GAINS:
907+
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]
908+
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]
909+
elif command == SET_MAX_JOINT_TORQUES:
910+
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]
904911
end
905912
end
906913
end

src/control/script_command_interface.cpp

Lines changed: 59 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -385,6 +385,64 @@ bool ScriptCommandInterface::setTcpOffset(const vector6d_t& offset)
385385
return server_.write(client_fd_, buffer, sizeof(buffer), written);
386386
}
387387

388+
bool ScriptCommandInterface::setPDControllerGains(const urcl::vector6d_t* kp, const urcl::vector6d_t* kd)
389+
{
390+
const int message_length = 13;
391+
uint8_t buffer[sizeof(int32_t) * MAX_MESSAGE_LENGTH];
392+
uint8_t* b_pos = buffer;
393+
394+
int32_t val = htobe32(toUnderlying(ScriptCommand::SET_PD_CONTROLLER_GAINS));
395+
b_pos += append(b_pos, val);
396+
397+
for (auto const& p_gain : *kp)
398+
{
399+
val = htobe32(static_cast<int32_t>(round(p_gain * MULT_JOINTSTATE)));
400+
b_pos += append(b_pos, val);
401+
}
402+
403+
for (auto const& d_gain : *kd)
404+
{
405+
val = htobe32(static_cast<int32_t>(round(d_gain * MULT_JOINTSTATE)));
406+
b_pos += append(b_pos, val);
407+
}
408+
409+
// writing zeros to allow usage with other script commands
410+
for (size_t i = message_length; i < MAX_MESSAGE_LENGTH; i++)
411+
{
412+
val = htobe32(0);
413+
b_pos += append(b_pos, val);
414+
}
415+
size_t written;
416+
417+
return server_.write(client_fd_, buffer, sizeof(buffer), written);
418+
}
419+
420+
bool ScriptCommandInterface::setMaxJointTorques(const urcl::vector6d_t* max_joint_torques)
421+
{
422+
const int message_length = 7;
423+
uint8_t buffer[sizeof(int32_t) * MAX_MESSAGE_LENGTH];
424+
uint8_t* b_pos = buffer;
425+
426+
int32_t val = htobe32(toUnderlying(ScriptCommand::SET_MAX_JOINT_TORQUES));
427+
b_pos += append(b_pos, val);
428+
429+
for (auto const& max_torque : *max_joint_torques)
430+
{
431+
val = htobe32(static_cast<int32_t>(round(max_torque * MULT_JOINTSTATE)));
432+
b_pos += append(b_pos, val);
433+
}
434+
435+
// writing zeros to allow usage with other script commands
436+
for (size_t i = message_length; i < MAX_MESSAGE_LENGTH; i++)
437+
{
438+
val = htobe32(0);
439+
b_pos += append(b_pos, val);
440+
}
441+
size_t written;
442+
443+
return server_.write(client_fd_, buffer, sizeof(buffer), written);
444+
}
445+
388446
bool ScriptCommandInterface::clientConnected()
389447
{
390448
return client_connected_;
@@ -452,4 +510,4 @@ bool ScriptCommandInterface::robotVersionSupportsCommandOrWarn(const VersionInfo
452510
}
453511

454512
} // namespace control
455-
} // namespace urcl
513+
} // namespace urcl

src/ur/ur_driver.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -635,6 +635,54 @@ bool UrDriver::setTcpOffset(const vector6d_t& tcp_offset)
635635
}
636636
}
637637

638+
bool UrDriver::setPDControllerGains(const urcl::vector6d_t& kp, const urcl::vector6d_t& kd)
639+
{
640+
if (!std::all_of(kp.begin(), kp.end(), [](double v) { return v >= 0.0; }))
641+
{
642+
throw InvalidRange("kp should be larger than zero");
643+
}
644+
645+
if (!std::all_of(kd.begin(), kd.end(), [](double v) { return v >= 0.0; }))
646+
{
647+
throw InvalidRange("kd should be larger than zero");
648+
}
649+
650+
if (script_command_interface_->clientConnected())
651+
{
652+
return script_command_interface_->setPDControllerGains(&kp, &kd);
653+
}
654+
else
655+
{
656+
URCL_LOG_ERROR("Script command interface is not running. Unable to set PD Controller gains.");
657+
return 0;
658+
}
659+
}
660+
661+
bool UrDriver::setMaxJointTorques(const urcl::vector6d_t& max_joint_torques)
662+
{
663+
const urcl::vector6d_t max_torques_for_robot_type =
664+
control::getMaxTorquesFromRobotType(primary_client_->getRobotType());
665+
if (!std::equal(max_joint_torques.begin(), max_joint_torques.end(), max_torques_for_robot_type.begin(),
666+
[](double v1, double v2) { return v1 <= v2 && v1 >= 0.0; }))
667+
{
668+
std::stringstream ss;
669+
ss << "The max joint torques should be smaller or equal to the maximum joint torques for the robot type and larger "
670+
"than zero. Provided max joint torques "
671+
<< max_joint_torques << " and maximum joint torques for the robot type " << max_torques_for_robot_type;
672+
throw InvalidRange(ss.str().c_str());
673+
}
674+
675+
if (script_command_interface_->clientConnected())
676+
{
677+
return script_command_interface_->setMaxJointTorques(&max_joint_torques);
678+
}
679+
else
680+
{
681+
URCL_LOG_ERROR("Script command interface is not running. Unable to set max joint torques.");
682+
return 0;
683+
}
684+
}
685+
638686
bool UrDriver::writeKeepalive(const RobotReceiveTimeout& robot_receive_timeout)
639687
{
640688
vector6d_t* fake = nullptr;

tests/test_script_command_interface.cpp

Lines changed: 70 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -432,7 +432,6 @@ TEST_F(ScriptCommandInterfaceTest, test_ft_rtde_input_enable)
432432
{
433433
// Wait for the client to connect to the server
434434
waitForClientConnection();
435-
436435
double sensor_mass = 1.42;
437436
vector3d_t sensor_measuring_offset = { 0.1, 0.2, 0.3 };
438437
vector3d_t sensor_cog = { 0.01, 0.02, 0.03 };
@@ -490,6 +489,7 @@ TEST_F(ScriptCommandInterfaceTest, test_set_gravity)
490489

491490
vector3d_t gravity = { 0.1, 0.2, -9.81 };
492491
script_command_interface_->setGravity(&gravity);
492+
493493
int32_t command;
494494
std::vector<int32_t> message;
495495
client_->readMessage(command, message);
@@ -635,6 +635,75 @@ TEST_F(ScriptCommandInterfaceTest, test_set_friction_scales_returns_false_on_old
635635
old_client->close();
636636
}
637637

638+
TEST_F(ScriptCommandInterfaceTest, test_set_pd_controller_gains)
639+
{
640+
// Wait for the client to connect to the server
641+
waitForClientConnection();
642+
643+
urcl::vector6d_t kp = { 220.2, 220.2, 300.0, 10.32, 10.32, 10.32 };
644+
urcl::vector6d_t kd = { 29.68, 29.68, 35.0, 6.4, 6.4, 6.4 };
645+
script_command_interface_->setPDControllerGains(&kp, &kd);
646+
647+
int32_t command;
648+
std::vector<int32_t> message;
649+
client_->readMessage(command, message);
650+
651+
// 12 is set PD controller gains
652+
int32_t expected_command = 12;
653+
EXPECT_EQ(command, expected_command);
654+
655+
int32_t message_idx = 0;
656+
657+
for (auto& p_gain : kp)
658+
{
659+
const double received_gain = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
660+
EXPECT_EQ(p_gain, received_gain);
661+
message_idx = message_idx + 1;
662+
}
663+
664+
for (auto& d_gain : kd)
665+
{
666+
const double received_gain = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
667+
EXPECT_EQ(d_gain, received_gain);
668+
message_idx = message_idx + 1;
669+
}
670+
671+
// The rest of the message should be zero
672+
int32_t message_sum = std::accumulate(std::begin(message) + message_idx, std::end(message), 0);
673+
int32_t expected_message_sum = 0;
674+
EXPECT_EQ(message_sum, expected_message_sum);
675+
}
676+
677+
TEST_F(ScriptCommandInterfaceTest, test_set_max_joint_torques)
678+
{
679+
// Wait for the client to connect to the server
680+
waitForClientConnection();
681+
682+
urcl::vector6d_t max_joint_torques = { 100.0, 150.0, 21.2, 10.32, 10.32, 10.32 };
683+
script_command_interface_->setMaxJointTorques(&max_joint_torques);
684+
685+
int32_t command;
686+
std::vector<int32_t> message;
687+
client_->readMessage(command, message);
688+
689+
// 13 is set max joint torques
690+
int32_t expected_command = 13;
691+
EXPECT_EQ(command, expected_command);
692+
693+
int32_t message_idx = 0;
694+
695+
for (auto& max_torque : max_joint_torques)
696+
{
697+
const double received_max_torque = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
698+
EXPECT_EQ(max_torque, received_max_torque);
699+
message_idx = message_idx + 1;
700+
}
701+
702+
// The rest of the message should be zero
703+
int32_t message_sum = std::accumulate(std::begin(message) + message_idx, std::end(message), 0);
704+
int32_t expected_message_sum = 0;
705+
EXPECT_EQ(message_sum, expected_message_sum);
706+
}
638707
int main(int argc, char* argv[])
639708
{
640709
::testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)