Skip to content

Commit 8b3104d

Browse files
authored
Merge pull request #3 from urfeex/win-build
Merge current master and fix file handling
2 parents 262a912 + 4842441 commit 8b3104d

File tree

6 files changed

+96
-45
lines changed

6 files changed

+96
-45
lines changed

CHANGELOG.rst

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,43 @@
22
Changelog for package ur_client_library
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
1.7.0 (2025-02-19)
6+
------------------
7+
* Make UrDriver tests run without ctest (`#270 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/270>`_)
8+
* UrDriver: Send program in headless mode after creating trajectory and script_command servers (`#271 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/271>`_)
9+
* Improve limit check (`#256 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/256>`_)
10+
* Use colored log output and timestamps in default log handler (`#267 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/267>`_)
11+
* Parametrize reconnection time for UrDriver (`#266 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/266>`_)
12+
Co-authored-by: Dominic Reber <71256590+domire8@users.noreply.github.com>
13+
* Fix DashboardClient load program from subdir (`#269 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/269>`_)
14+
* Increase dashboard timeout in ExampleRobotWrapper to 10s
15+
* Disable internal deprecation warning
16+
* Use a config struct for initializing UrDriver (`#264 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/pull/264>`_)
17+
* Use ExampleRobotWrapper for initialization in all examples (`#265 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/265>`_)
18+
* Enable nightly CI jobs (`#263 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/263>`_)
19+
* Expose diagnostic error codes (`#225 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/225>`_)
20+
* RTDEClient: pause and stop in destructor only if running (`#257 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/257>`_)
21+
* Use coverage flags to distinguish between runs (`#261 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/261>`_)
22+
* Fix branch name for integration tests run on push (`#262 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/262>`_)
23+
* Add codecov/test-results-action (`#260 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/260>`_)
24+
* Fix GH edit URL for trajectory_point_interface example (`#259 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/259>`_)
25+
* Update URL check
26+
* Show which example is running in run_examples.sh
27+
* Add documentation for all examples (`#258 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/pull/258>`_)
28+
* Update RT setup documentation to point to urcl docs
29+
* Use EXPECT_NEAR vs EXPECT_EQ
30+
* Fix typo in start_ursim.sh help
31+
* Make CI capable to run with urcap
32+
* Use ExampleRobotWrapper in integration tests (`#252 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/pull/252>`_)
33+
* Add a wrapper to handle all robot setup (`#252 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/pull/252>`_)
34+
* Allow clang-format to indent preprocessor directives (`#246 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/246>`_)
35+
* docs: Clarify that the motion functions use script functions for execution (`#255 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/255>`_)
36+
* Update link to sphinx-doc.org using https (`#247 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/247>`_)
37+
* Use joint speed for extrapolation rather than differences (`#254 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/254>`_)
38+
* Move setup instructions to ur_client_library (`#248 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/248>`_)
39+
* Add more information about acceleration/velocity parametrization in trajectory examples (`#251 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/251>`_)
40+
* Contributors: Felix Exner, Rune Søe-Knudsen, jessica-chen-ocado, Dominic Reber
41+
542
1.6.0 (2025-01-23)
643
------------------
744
* Do not throw exception in DashboardClient::sendRequest (`#249 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/249>`_)

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>ur_client_library</name>
5-
<version>1.6.0</version>
5+
<version>1.7.0</version>
66
<description>Standalone C++ library for accessing Universal Robots interfaces. This has been forked off the ur_robot_driver.</description>
77
<author>Thomas Timm Andersen</author>
88
<author>Simon Rasmussen</author>

resources/external_control.urscript

Lines changed: 20 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -99,16 +99,23 @@ def targetWithinLimits(step_start, step_end, time):
9999
while idx < 6:
100100
local velocity = norm(step_end[idx] - step_start[idx]) / time
101101
if velocity > JOINT_IGNORE_SPEED:
102-
local str = str_cat(str_cat("Velocity ", velocity), str_cat(str_cat(" required to reach the received target ", step_end), str_cat(str_cat(" within ", time), " seconds is exceeding the joint velocity limits. Ignoring commands until a valid command is received.")))
102+
local str = str_cat(
103+
str_cat("Velocity ", velocity), str_cat(
104+
str_cat(" required in joint ", idx), str_cat(
105+
str_cat(" to go from ", step_start[idx]), str_cat(
106+
str_cat(" to ", step_end[idx]), str_cat(
107+
str_cat(" within ", time), " seconds is exceeding the joint velocity limits. Ignoring commands until a valid command is received.")))))
103108
if violation_popup_counter == 0:
104109
# We want a popup when an invalid commant is sent. As long as we keep sending invalid
105110
# commands, we do not want to repeat the popup.
106-
popup(str, title="External Control error", blocking=False, error=True)
111+
popup(str, title="External Control speed limit", blocking=False, warning=True)
107112
end
108113
if violation_popup_counter * get_steptime() % 5.0 == 0:
109114
# We want to have a log printed regularly. We are receiving motion commands that are not
110115
# feasible. The user should have a chance to know about this.
111116
textmsg(str)
117+
textmsg("start configuration: ", step_start)
118+
textmsg("end configuration: ", step_end)
112119
end
113120
violation_popup_counter = violation_popup_counter + 1
114121
return False
@@ -143,8 +150,10 @@ end
143150

144151
def set_servo_setpoint(q):
145152
cmd_servo_state = SERVO_RUNNING
146-
cmd_servo_q_last = cmd_servo_q
147-
cmd_servo_q = q
153+
if targetWithinLimits(cmd_servo_q, q, steptime):
154+
cmd_servo_q_last = cmd_servo_q
155+
cmd_servo_q = q
156+
end
148157
end
149158

150159
def extrapolate():
@@ -156,7 +165,6 @@ end
156165
thread servoThread():
157166
textmsg("ExternalControl: Starting servo thread")
158167
state = SERVO_IDLE
159-
local q_last = get_joint_positions()
160168
while control_mode == MODE_SERVOJ:
161169
enter_critical
162170
q = cmd_servo_q
@@ -176,17 +184,11 @@ thread servoThread():
176184
end
177185

178186
q = extrapolate()
179-
if targetWithinLimits(q_last, q, steptime):
180-
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
181-
q_last = q
182-
end
187+
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
183188

184189
elif state == SERVO_RUNNING:
185190
extrapolate_count = 0
186-
if targetWithinLimits(q_last, q, steptime):
187-
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
188-
q_last = q
189-
end
191+
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
190192
else:
191193
extrapolate_count = 0
192194
sync()
@@ -555,7 +557,6 @@ end
555557
thread servoThreadP():
556558
textmsg("Starting pose servo thread")
557559
state = SERVO_IDLE
558-
local q_last = get_joint_positions()
559560
while control_mode == MODE_POSE:
560561
enter_critical
561562
q = cmd_servo_q
@@ -575,15 +576,11 @@ thread servoThreadP():
575576
end
576577

577578
q = extrapolate()
578-
if targetWithinLimits(q_last, q, steptime):
579-
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
580-
end
579+
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
581580

582581
elif state == SERVO_RUNNING:
583582
extrapolate_count = 0
584-
if targetWithinLimits(q_last, q, steptime):
585-
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
586-
end
583+
servoj(q, t=steptime, {{SERVO_J_REPLACE}})
587584
else:
588585
extrapolate_count = 0
589586
sync()
@@ -594,12 +591,6 @@ thread servoThreadP():
594591
stopj(STOPJ_ACCELERATION)
595592
end
596593

597-
def set_servo_pose(pose):
598-
cmd_servo_state = SERVO_RUNNING
599-
cmd_servo_q_last = cmd_servo_q
600-
cmd_servo_q = get_inverse_kin(pose, cmd_servo_q)
601-
end
602-
603594
def tool_contact_detection():
604595
# Detect tool contact in the directions that the TCP is moving
605596
step_back = tool_contact(direction = get_actual_tcp_speed())
@@ -718,6 +709,7 @@ while control_mode > MODE_STOPPED:
718709
join thread_move
719710
end
720711
if control_mode == MODE_SERVOJ:
712+
cmd_servo_q = get_joint_positions()
721713
thread_move = run servoThread()
722714
elif control_mode == MODE_SPEEDJ:
723715
thread_move = run speedThread()
@@ -727,6 +719,7 @@ while control_mode > MODE_STOPPED:
727719
elif control_mode == MODE_SPEEDL:
728720
thread_move = run speedlThread()
729721
elif control_mode == MODE_POSE:
722+
cmd_servo_q = get_joint_positions()
730723
thread_move = run servoThreadP()
731724
end
732725
end
@@ -756,7 +749,7 @@ while control_mode > MODE_STOPPED:
756749
set_speedl(twist)
757750
elif control_mode == MODE_POSE:
758751
pose = p[params_mult[2] / MULT_jointstate, params_mult[3] / MULT_jointstate, params_mult[4] / MULT_jointstate, params_mult[5] / MULT_jointstate, params_mult[6] / MULT_jointstate, params_mult[7] / MULT_jointstate]
759-
set_servo_pose(pose)
752+
set_servo_setpoint(get_inverse_kin(pose, cmd_servo_q))
760753
elif control_mode == MODE_FREEDRIVE:
761754
if params_mult[2] == FREEDRIVE_MODE_START:
762755
textmsg("Entering freedrive mode")

src/default_log_handler.cpp

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -30,29 +30,34 @@
3030

3131
#include "ur_client_library/default_log_handler.h"
3232
#include <stdio.h>
33+
#include <chrono>
34+
#include <string>
3335

3436
namespace urcl
3537
{
38+
3639
DefaultLogHandler::DefaultLogHandler() = default;
3740

3841
void DefaultLogHandler::log(const char* file, int line, LogLevel loglevel, const char* log)
3942
{
43+
auto timestamp = std::chrono::duration<double>(std::chrono::system_clock::now().time_since_epoch());
44+
4045
switch (loglevel)
4146
{
4247
case LogLevel::INFO:
43-
printf("%s%s %i: %s \n", "INFO ", file, line, log);
48+
printf("[%f] %s%s %i: %s \n", timestamp.count(), "INFO ", file, line, log);
4449
break;
4550
case LogLevel::DEBUG:
46-
printf("%s%s %i: %s \n", "DEBUG ", file, line, log);
51+
printf("\033[36m[%f] %s%s %i: %s \033[0m\n", timestamp.count(), "DEBUG ", file, line, log);
4752
break;
4853
case LogLevel::WARN:
49-
printf("%s%s %i: %s \n", "WARN ", file, line, log);
54+
printf("\033[33m[%f] %s%s %i: %s \033[0m\n", timestamp.count(), "WARN ", file, line, log);
5055
break;
5156
case LogLevel::ERROR:
52-
printf("%s%s %i: %s \n", "ERROR ", file, line, log);
57+
printf("\033[31m[%f] %s%s %i: %s \033[0m\n", timestamp.count(), "ERROR ", file, line, log);
5358
break;
5459
case LogLevel::FATAL:
55-
printf("%s%s %i: %s \n", "FATAL ", file, line, log);
60+
printf("\033[31m[%f] %s%s %i: %s \033[0m\n", timestamp.count(), "FATAL ", file, line, log);
5661
break;
5762
default:
5863
break;

src/ur/ur_driver.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -148,6 +148,9 @@ void UrDriver::init(const UrDriverConfiguration& config)
148148
}
149149
prog.replace(prog.find(BEGIN_REPLACE), BEGIN_REPLACE.length(), begin_replace.str());
150150

151+
trajectory_interface_.reset(new control::TrajectoryPointInterface(config.trajectory_port));
152+
script_command_interface_.reset(new control::ScriptCommandInterface(config.script_command_port));
153+
151154
if (in_headless_mode_)
152155
{
153156
full_robot_program_ = "stop program\n";
@@ -167,9 +170,6 @@ void UrDriver::init(const UrDriverConfiguration& config)
167170
URCL_LOG_DEBUG("Created script sender");
168171
}
169172

170-
trajectory_interface_.reset(new control::TrajectoryPointInterface(config.trajectory_port));
171-
script_command_interface_.reset(new control::ScriptCommandInterface(config.script_command_port));
172-
173173
if (!std::empty(config.calibration_checksum))
174174
{
175175
URCL_LOG_WARN("DEPRECATION NOTICE: Passing the calibration_checksum to the UrDriver's constructor has been "

tests/test_ur_driver.cpp

Lines changed: 25 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,17 @@ class UrDriverTest : public ::testing::Test
5959

6060
void SetUp()
6161
{
62-
ASSERT_TRUE(g_my_robot->isHealthy());
62+
if (!g_my_robot->isHealthy())
63+
{
64+
ASSERT_TRUE(g_my_robot->resendRobotProgram());
65+
ASSERT_TRUE(g_my_robot->waitForProgramRunning(500));
66+
}
67+
}
68+
69+
void TearDown()
70+
{
71+
g_my_robot->ur_driver_->stopControl();
72+
g_my_robot->waitForProgramNotRunning(1000);
6373
}
6474
};
6575

@@ -71,21 +81,24 @@ TEST_F(UrDriverTest, read_non_existing_script_file)
7181

7282
TEST_F(UrDriverTest, read_existing_script_file)
7383
{
84+
int fd = 0;
85+
char existing_script_file[] = "urscript.XXXXXX";
7486
#ifdef _WIN32
7587
# define mkstemp _mktemp_s
7688
#endif
77-
char existing_script_file[] = "urscript.XXXXXX";
78-
int fd = mkstemp(existing_script_file);
79-
if (fd == -1)
89+
mkstemp(existing_script_file);
90+
91+
std::ofstream ofs(existing_script_file);
92+
if (ofs.bad())
8093
{
8194
std::cout << "Failed to create temporary files" << std::endl;
8295
GTEST_FAIL();
8396
}
8497
EXPECT_NO_THROW(UrDriver::readScriptFile(existing_script_file));
8598

8699
// clean up
87-
close(fd);
88-
unlink(existing_script_file);
100+
ofs.close();
101+
std::remove(existing_script_file);
89102
}
90103

91104
TEST_F(UrDriverTest, robot_receive_timeout)
@@ -224,13 +237,16 @@ TEST_F(UrDriverTest, send_robot_program_retry_on_failure)
224237
{
225238
// Check that sendRobotProgram is robust to the secondary stream being disconnected. This is what happens when
226239
// switching from Remote to Local and back to Remote mode for example.
227-
g_my_robot->ur_driver_->closeSecondaryStream();
228240

229-
std::this_thread::sleep_for(std::chrono::milliseconds(100));
241+
// To be able to re-send the robot program we'll have to make sure it isn't running
242+
g_my_robot->ur_driver_->stopControl();
243+
g_my_robot->waitForProgramNotRunning();
244+
245+
g_my_robot->ur_driver_->closeSecondaryStream();
230246

231247
EXPECT_TRUE(g_my_robot->resendRobotProgram());
232248

233-
EXPECT_TRUE(g_my_robot->waitForProgramRunning());
249+
EXPECT_TRUE(g_my_robot->waitForProgramRunning(1000));
234250
}
235251

236252
TEST_F(UrDriverTest, reset_rtde_client)

0 commit comments

Comments
 (0)