Script command interface
The Script Command Interface allows sending predefined commands to the robot while there is URScript running that is connected to it.
An example to utilize the script command interface can be found in the freedrive_example.cpp.
In order to use the ScriptCommandInterface, there has to be a script code running on the robot
that connects to the ScriptCommandInterface. This happens as part of the big
external_control.urscript. In order to reuse that with this example, we will create a full
UrDriver and leverage the ScriptCommandInterface through this.
At first, we create a ExampleRobotWrapper object in order to initialize communication with the
robot.
121 g_my_robot =
122 std::make_unique<ExampleRobotWrapper>(robot_ip, OUTPUT_RECIPE, INPUT_RECIPE, g_HEADLESS, "external_control.urp");
123
124 // Check if the robot version supports the friction scales command (requires 5.25.1 / 10.12.1)
125 auto version = g_my_robot->getUrDriver()->getVersion();
126 g_support_set_friction_scales = (version.major == 5 && version >= urcl::VersionInformation::fromString("5.25.1")) ||
127 (version.major >= 10 && version >= urcl::VersionInformation::fromString("10.12.1"));
128 if (!g_support_set_friction_scales)
129 {
130 URCL_LOG_INFO("Setting friction scales is not supported on this robot (version %s). "
131 "Requires at least 5.25.1 / 10.12.1. Skipping friction scale commands.",
132 version.toString().c_str());
133 }
134
135 if (!g_my_robot->isHealthy())
136 {
137 URCL_LOG_ERROR("Something in the robot initialization went wrong. Exiting. Please check the output above.");
138 return 1;
139 }
140
141 // We will send script commands from a separate thread. That will stay active as long as
142 // g_running is true.
143 g_running = true;
144 std::thread script_command_send_thread(sendScriptCommands);
The script commands will be sent in a separate thread which will be explained later.
Since the connection to the script command interface runs as part of the bigger external_control
script, we’ll wrap the calls alongside a full ExampleRobotWrapper. Hence, we’ll have to send
keepalive signals regularly to keep the script running:
148 std::chrono::duration<double> time_done(0);
149 std::chrono::duration<double> timeout(second_to_run);
150 auto stopwatch_last = std::chrono::steady_clock::now();
151 auto stopwatch_now = stopwatch_last;
152 while ((time_done < timeout || second_to_run.count() == 0) && g_my_robot->isHealthy())
153 {
154 g_my_robot->getUrDriver()->writeKeepalive();
155
156 stopwatch_now = std::chrono::steady_clock::now();
157 time_done += stopwatch_now - stopwatch_last;
158 stopwatch_last = stopwatch_now;
159 std::this_thread::sleep_for(
160 std::chrono::milliseconds(static_cast<int>(1.0 / g_my_robot->getUrDriver()->getControlFrequency())));
161 }
162
163 URCL_LOG_INFO("Timeout reached.");
164 g_my_robot->getUrDriver()->stopControl();
Sending script commands
Once the script is running on the robot, a connection to the driver’s script command interface
should be established. The UrDriver forwards most calls of the ScriptCommandInterface and
we will use that interface in this example. To send a script command, we can e.g. use
g_my_robot->getUrDriver()->zeroFTSensor().
In the example, we have wrapped the calls into a lambda function that will wait a specific timeout, print a log output what command will be sent and then call the respective command:
68 run_cmd("Setting tool voltage to 24V",
69 []() { g_my_robot->getUrDriver()->setToolVoltage(urcl::ToolVoltage::_24V); });
70 run_cmd("Enabling tool contact mode", []() { g_my_robot->getUrDriver()->startToolContact(); });
71
72 if (g_support_set_friction_scales)
73 {
74 // setFrictionScales is only supported from PolyScope 5.25.1 / PolyScope X 10.12.1 and upwards.
75 run_cmd("Turn off friction_compensation by setting the friction scales to zeroes",
76 []() { g_my_robot->getUrDriver()->setFrictionScales({ 0, 0, 0, 0, 0, 0 }, { 0, 0, 0, 0, 0, 0 }); });
77 }
78 run_cmd("Setting tool voltage to 0V", []() { g_my_robot->getUrDriver()->setToolVoltage(urcl::ToolVoltage::OFF); });
79 run_cmd("Zeroing the force torque sensor", []() { g_my_robot->getUrDriver()->zeroFTSensor(); });
80 run_cmd("Disabling tool contact mode", []() { g_my_robot->getUrDriver()->endToolContact(); });
81 run_cmd("Setting TCP offset to [0.0, 0.0, 0.10, 0.0, 0.0, 0.0]",
82 []() { g_my_robot->getUrDriver()->setTcpOffset({ 0.0, 0.0, 0.10, 0.0, 0.0, 0.0 }); });
83
84 if (g_support_set_friction_scales)
85 {
86 // setFrictionScales is only supported from PolyScope 5.25.1 / PolyScope X 10.12.1 and upwards.
87 run_cmd("Turn on friction_compensation by setting the friction scales to non-zero values", []() {
88 g_my_robot->getUrDriver()->setFrictionScales({ 0.9, 0.9, 0.8, 0.9, 0.9, 0.9 },
89 { 0.8, 0.8, 0.7, 0.8, 0.8, 0.8 });
90 });
91 }
92 }
The lambda itself looks like this:
52 auto run_cmd = [](const std::string& log_output, std::function<void()> func) {
53 const std::chrono::seconds timeout(3);
54 if (g_running)
55 {
56 // We wait a fixed time so that not each command is run directly behind each other.
57 // This is done for example purposes only, so users can follow the effect on the teach
58 // pendant.
59 std::this_thread::sleep_for(timeout);
60 URCL_LOG_INFO(log_output.c_str());
61 func();
62 }
63 };
For a list of all available script commands, please refer to the ScriptCommandInterface class
here.