Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 23 additions & 0 deletions doc/architecture/script_command_interface.rst
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@ At the time of writing the ``ScriptCommandInterface`` provides the following fun
<https://github.com/UniversalRobots/Universal_Robots_Client_Library/blob/master/examples/tool_contact_example.cpp>`_
for more information.
- ``setFrictionCompensation()``: Set friction compensation for torque command.
- ``setPDControllerGains()``: Set PD gains for the PD control loop running in the external control script.
- ``setMaxJointTorques()``: Set Max joint torques for the PD control loop running in the external control script.

Communication protocol
----------------------
Expand Down Expand Up @@ -50,6 +52,8 @@ The robot reads from the "script_command_socket" expecting a 32 bit integer repr
- 5: startToolContact
- 6: endToolContact
- 7: setFrictionCompensation
- 8: setPDControllerGains
- 9: setMaxJointTorques
1-27 data fields specific to the command
===== =====

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

.. table:: With setPDControllerGains command
:widths: auto

===== =====
index meaning
===== =====
1-6 Kp gains for each joint, used in the PD control loop running in the external control script (floating point)
7-12 Kd gains for each joint, used in the PD control loop running in the external control script (floating point)
===== =====

.. table:: With setMaxJointTorques command
:widths: auto

===== =====
index meaning
===== =====
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)
===== =====

.. note::
In URScript the ``socket_read_binary_integer()`` function is used to read the data from the
script command socket. The first index in that function's return value is the number of integers read,
Expand Down
6 changes: 6 additions & 0 deletions examples/script_command_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,12 @@ void sendScriptCommands()
run_cmd("Disabling tool contact mode", []() { g_my_robot->getUrDriver()->endToolContact(); });
run_cmd("Setting friction_compensation variable to `true`",
[]() { g_my_robot->getUrDriver()->setFrictionCompensation(true); });
run_cmd("Setting PD controller gains", []() {
g_my_robot->getUrDriver()->setPDControllerGains({ 500.0, 500.0, 300.0, 124.0, 124.0, 124.0 },
{ 44.72, 44.72, 34.64, 22.27, 22.27, 22.27 });
});
run_cmd("Setting max joint torques",
[]() { g_my_robot->getUrDriver()->setMaxJointTorques({ 27.0, 27.0, 14.0, 4.5, 4.5, 4.5 }); });
}
URCL_LOG_INFO("Script command thread finished.");
}
Expand Down
26 changes: 26 additions & 0 deletions include/ur_client_library/control/script_command_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,30 @@ class ScriptCommandInterface : public ReverseInterface
*/
bool setFrictionCompensation(const bool friction_compensation_enabled);

/*!
* \brief Set gains for the PD controller running in the external control script. The PD controller computes joint
* torques based on either tcp poses or joint poses and applies the torques to the robot using the torque_command
* function. The gains can be used to change the response of the controller. Be aware that changing the controller
* response can make it unstable.
*
* \param kp A vector6d of proportional gains for each of the joints in the robot.
* \param kd A vector6d of derivative gains for each of the joints in the robot.
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool setPDControllerGains(const urcl::vector6d_t* kp, const urcl::vector6d_t* kd);

/*!
* \brief Set the maximum joint torques for the PD controller running in the external control script. The PD
* controller will clamp the torques between +-max_joint_torques before aplying them to the robot using the
* torque_command function.
*
* \param max_joint_torques A vector6d of the maximum joint torques for each of the joints.
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool setMaxJointTorques(const urcl::vector6d_t* max_joint_torques);

/*!
* \brief Returns whether a client/robot is connected to this server.
*
Expand Down Expand Up @@ -196,6 +220,8 @@ class ScriptCommandInterface : public ReverseInterface
START_TOOL_CONTACT = 5, ///< Start detecting tool contact
END_TOOL_CONTACT = 6, ///< End detecting tool contact
SET_FRICTION_COMPENSATION = 7, ///< Set friction compensation
SET_PD_CONTROLLER_GAINS = 8, ///< Set PD controller gains
SET_MAX_JOINT_TORQUES = 9, ///< Set max joint torques
};

bool client_connected_;
Expand Down
24 changes: 24 additions & 0 deletions include/ur_client_library/ur/ur_driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -725,6 +725,30 @@ class UrDriver
*/
bool setFrictionCompensation(const bool friction_compensation_enabled);

/*!
* \brief Set gains for the PD controller running in the external control script. The PD controller computes joint
* torques based on either tcp poses or joint poses and applies the torques to the robot using the torque_command
* function. The gains can be used to change the response of the controller. Be aware that changing the controller
* response can make it unstable.
*
* \param kp A vector6d of proportional gains for each of the joints in the robot.
* \param kd A vector6d of derivative gains for each of the joints in the robot.
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool setPDControllerGains(const urcl::vector6d_t& kp, const urcl::vector6d_t& kd);

/*!
* \brief Set the maximum joint torques for the PD controller running in the external control script. The PD
* controller will clamp the torques between +-max_joint_torques before aplying them to the robot using the
* torque_command function.
*
* \param max_joint_torques A vector6d of the maximum joint torques for each of the joints.
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool setMaxJointTorques(const urcl::vector6d_t& max_joint_torques);

/*!
* \brief Write a keepalive signal only.
*
Expand Down
7 changes: 7 additions & 0 deletions resources/external_control.urscript
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@ END_FORCE_MODE = 4
START_TOOL_CONTACT = 5
END_TOOL_CONTACT = 6
SET_FRICTION_COMPENSATION = 7
SET_PD_CONTROLLER_GAINS = 8
SET_MAX_JOINT_TORQUES = 9
SCRIPT_COMMAND_DATA_DIMENSION = 28

FREEDRIVE_MODE_START = 1
Expand Down Expand Up @@ -757,6 +759,11 @@ thread script_commands():
else:
friction_compensation_enabled = True
end
elif command == SET_PD_CONTROLLER_GAINS:
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]
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]
elif command == SET_MAX_JOINT_TORQUES:
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]
end
end
end
Expand Down
58 changes: 58 additions & 0 deletions src/control/script_command_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,6 +245,64 @@ bool ScriptCommandInterface::setFrictionCompensation(const bool friction_compens
return server_.write(client_fd_, buffer, sizeof(buffer), written);
}

bool ScriptCommandInterface::setPDControllerGains(const urcl::vector6d_t* kp, const urcl::vector6d_t* kd)
{
const int message_length = 13;
uint8_t buffer[sizeof(int32_t) * MAX_MESSAGE_LENGTH];
uint8_t* b_pos = buffer;

int32_t val = htobe32(toUnderlying(ScriptCommand::SET_PD_CONTROLLER_GAINS));
b_pos += append(b_pos, val);

for (auto const& p_gain : *kp)
{
val = htobe32(static_cast<int32_t>(round(p_gain * MULT_JOINTSTATE)));
b_pos += append(b_pos, val);
}

for (auto const& d_gain : *kd)
{
val = htobe32(static_cast<int32_t>(round(d_gain * MULT_JOINTSTATE)));
b_pos += append(b_pos, val);
}

// writing zeros to allow usage with other script commands
for (size_t i = message_length; i < MAX_MESSAGE_LENGTH; i++)
{
val = htobe32(0);
b_pos += append(b_pos, val);
}
size_t written;

return server_.write(client_fd_, buffer, sizeof(buffer), written);
}

bool ScriptCommandInterface::setMaxJointTorques(const urcl::vector6d_t* max_joint_torques)
{
const int message_length = 7;
uint8_t buffer[sizeof(int32_t) * MAX_MESSAGE_LENGTH];
uint8_t* b_pos = buffer;

int32_t val = htobe32(toUnderlying(ScriptCommand::SET_MAX_JOINT_TORQUES));
b_pos += append(b_pos, val);

for (auto const& max_torque : *max_joint_torques)
{
val = htobe32(static_cast<int32_t>(round(max_torque * MULT_JOINTSTATE)));
b_pos += append(b_pos, val);
}

// writing zeros to allow usage with other script commands
for (size_t i = message_length; i < MAX_MESSAGE_LENGTH; i++)
{
val = htobe32(0);
b_pos += append(b_pos, val);
}
size_t written;

return server_.write(client_fd_, buffer, sizeof(buffer), written);
}

bool ScriptCommandInterface::clientConnected()
{
return client_connected_;
Expand Down
48 changes: 48 additions & 0 deletions src/ur/ur_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -573,6 +573,54 @@ bool UrDriver::setFrictionCompensation(const bool friction_compensation_enabled)
}
}

bool UrDriver::setPDControllerGains(const urcl::vector6d_t& kp, const urcl::vector6d_t& kd)
{
if (!std::all_of(kp.begin(), kp.end(), [](double v) { return v >= 0.0; }))
{
throw InvalidRange("kp should be larger than zero");
}

if (!std::all_of(kd.begin(), kd.end(), [](double v) { return v >= 0.0; }))
{
throw InvalidRange("kd should be larger than zero");
}

if (script_command_interface_->clientConnected())
{
return script_command_interface_->setPDControllerGains(&kp, &kd);
}
else
{
URCL_LOG_ERROR("Script command interface is not running. Unable to set PD Controller gains.");
return 0;
}
}

bool UrDriver::setMaxJointTorques(const urcl::vector6d_t& max_joint_torques)
{
const urcl::vector6d_t max_torques_for_robot_type =
control::getMaxTorquesFromRobotType(primary_client_->getRobotType());
if (!std::equal(max_joint_torques.begin(), max_joint_torques.end(), max_torques_for_robot_type.begin(),
[](double v1, double v2) { return v1 <= v2 && v1 >= 0.0; }))
{
std::stringstream ss;
ss << "The max joint torques should be smaller or equal to the maximum joint torques for the robot type and larger "
"than zero. Provided max joint torques "
<< max_joint_torques << " and maximum joint torques for the robot type " << max_torques_for_robot_type;
throw InvalidRange(ss.str().c_str());
}

if (script_command_interface_->clientConnected())
{
return script_command_interface_->setMaxJointTorques(&max_joint_torques);
}
else
{
URCL_LOG_ERROR("Script command interface is not running. Unable to set max joint torques.");
return 0;
}
}

bool UrDriver::writeKeepalive(const RobotReceiveTimeout& robot_receive_timeout)
{
vector6d_t* fake = nullptr;
Expand Down
70 changes: 70 additions & 0 deletions tests/test_script_command_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -421,6 +421,76 @@ TEST_F(ScriptCommandInterfaceTest, test_set_friction_compensation)
EXPECT_EQ(message_sum, expected_message_sum);
}

TEST_F(ScriptCommandInterfaceTest, test_set_pd_controller_gains)
{
// Wait for the client to connect to the server
waitForClientConnection();

urcl::vector6d_t kp = { 220.2, 220.2, 300.0, 10.32, 10.32, 10.32 };
urcl::vector6d_t kd = { 29.68, 29.68, 35.0, 6.4, 6.4, 6.4 };
script_command_interface_->setPDControllerGains(&kp, &kd);

int32_t command;
std::vector<int32_t> message;
client_->readMessage(command, message);

// 8 is set PD controller gains
int32_t expected_command = 8;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We could think about moving the enum to a public namespace so that can be reused here. or is there a specific reason why enum class ScriptCommand is a private member of ScriptCommandInterface?

That's probably not for this PR, however.

Copy link
Contributor Author

@urmahp urmahp Jun 5, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No I think its because it is only intended to be used when sending commands to the external control script. But would make sense to make them available for the test cases. But yes should probably be done in separate PR.

EXPECT_EQ(command, expected_command);

int32_t message_idx = 0;

for (auto& p_gain : kp)
{
const double received_gain = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
EXPECT_EQ(p_gain, received_gain);
message_idx = message_idx + 1;
}

for (auto& d_gain : kd)
{
const double received_gain = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
EXPECT_EQ(d_gain, received_gain);
message_idx = message_idx + 1;
}

// The rest of the message should be zero
int32_t message_sum = std::accumulate(std::begin(message) + message_idx, std::end(message), 0);
int32_t expected_message_sum = 0;
EXPECT_EQ(message_sum, expected_message_sum);
}

TEST_F(ScriptCommandInterfaceTest, test_set_max_joint_torques)
{
// Wait for the client to connect to the server
waitForClientConnection();

urcl::vector6d_t max_joint_torques = { 100.0, 150.0, 21.2, 10.32, 10.32, 10.32 };
script_command_interface_->setMaxJointTorques(&max_joint_torques);

int32_t command;
std::vector<int32_t> message;
client_->readMessage(command, message);

// 9 is set max joint torques
int32_t expected_command = 9;
EXPECT_EQ(command, expected_command);

int32_t message_idx = 0;

for (auto& max_torque : max_joint_torques)
{
const double received_max_torque = (double)message[message_idx] / script_command_interface_->MULT_JOINTSTATE;
EXPECT_EQ(max_torque, received_max_torque);
message_idx = message_idx + 1;
}

// The rest of the message should be zero
int32_t message_sum = std::accumulate(std::begin(message) + message_idx, std::end(message), 0);
int32_t expected_message_sum = 0;
EXPECT_EQ(message_sum, expected_message_sum);
}

int main(int argc, char* argv[])
{
::testing::InitGoogleTest(&argc, argv);
Expand Down
Loading