Skip to content

Commit 43f0aeb

Browse files
committed
Run integration tests against PolyScopeX
1 parent 69e8185 commit 43f0aeb

File tree

11 files changed

+231
-82
lines changed

11 files changed

+231
-82
lines changed

include/ur_client_library/example_robot_wrapper.h

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,8 @@ class ExampleRobotWrapper
8585
*/
8686
bool initializeRobotWithDashboard();
8787

88+
bool initializeRobotWithPrimaryClient();
89+
8890
/**
8991
* @brief Starts RTDE communication with the robot.
9092
*
@@ -168,11 +170,15 @@ class ExampleRobotWrapper
168170
bool isHealthy() const;
169171

170172
std::shared_ptr<urcl::DashboardClient> dashboard_client_; /*!< Dashboard client to interact with the robot */
171-
std::shared_ptr<urcl::UrDriver> ur_driver_; /*!< UR driver to interact with the robot */
173+
std::shared_ptr<urcl::primary_interface::PrimaryClient> primary_client_; /*!< Dashboard client to interact with the
174+
robot */
175+
std::shared_ptr<urcl::UrDriver> ur_driver_; /*!< UR driver to interact with the robot */
172176

173177
private:
174178
void handleRobotProgramState(bool program_running);
175179

180+
comm::INotifier notifier_;
181+
176182
std::atomic<bool> rtde_communication_started_ = false;
177183
std::atomic<bool> consume_rtde_packages_ = false;
178184
std::mutex read_package_mutex_;
@@ -193,4 +199,4 @@ class ExampleRobotWrapper
193199
};
194200
} // namespace urcl
195201

196-
#endif
202+
#endif

include/ur_client_library/primary/primary_client.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -171,6 +171,9 @@ class PrimaryClient
171171
return static_cast<RobotMode>(consumer_->getRobotModeData()->robot_mode_);
172172
}
173173

174+
std::shared_ptr<VersionInformation>
175+
getRobotVersion(bool blocking = true, const std::chrono::milliseconds timeout = std::chrono::seconds(2));
176+
174177
/*!
175178
* \brief Get the latest robot mode data.
176179
*

include/ur_client_library/primary/primary_consumer.h

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
#include "ur_client_library/primary/abstract_primary_consumer.h"
3232
#include "ur_client_library/primary/robot_state/robot_mode_data.h"
3333
#include "ur_client_library/ur/datatypes.h"
34+
#include "ur_client_library/ur/version_information.h"
3435

3536
#include <functional>
3637
#include <mutex>
@@ -87,6 +88,12 @@ class PrimaryConsumer : public AbstractPrimaryConsumer
8788
*/
8889
virtual bool consume(VersionMessage& pkg) override
8990
{
91+
std::scoped_lock lock(version_information_mutex_);
92+
version_information_ = std::make_shared<VersionInformation>();
93+
version_information_->major = pkg.major_version_;
94+
version_information_->minor = pkg.minor_version_;
95+
version_information_->bugfix = pkg.svn_version_;
96+
version_information_->build = pkg.build_number_;
9097
return true;
9198
}
9299

@@ -196,11 +203,19 @@ class PrimaryConsumer : public AbstractPrimaryConsumer
196203
return robot_mode_;
197204
}
198205

206+
std::shared_ptr<VersionInformation> getVersionInformation()
207+
{
208+
std::scoped_lock lock(version_information_mutex_);
209+
return version_information_;
210+
}
211+
199212
private:
200213
std::function<void(ErrorCode&)> error_code_message_callback_;
201214
std::shared_ptr<KinematicsInfo> kinematics_info_;
202215
std::mutex robot_mode_mutex_;
203216
std::shared_ptr<RobotModeData> robot_mode_;
217+
std::mutex version_information_mutex_;
218+
std::shared_ptr<VersionInformation> version_information_;
204219
};
205220

206221
} // namespace primary_interface

include/ur_client_library/ur/ur_driver.h

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -890,6 +890,11 @@ class UrDriver
890890
return trajectory_interface_->isConnected();
891891
}
892892

893+
std::shared_ptr<urcl::primary_interface::PrimaryClient> getPrimaryClient()
894+
{
895+
return primary_client_;
896+
}
897+
893898
private:
894899
void init(const UrDriverConfiguration& config);
895900

@@ -898,7 +903,7 @@ class UrDriver
898903

899904
comm::INotifier notifier_;
900905
std::unique_ptr<rtde_interface::RTDEClient> rtde_client_;
901-
std::unique_ptr<urcl::primary_interface::PrimaryClient> primary_client_;
906+
std::shared_ptr<urcl::primary_interface::PrimaryClient> primary_client_;
902907
std::unique_ptr<control::ReverseInterface> reverse_interface_;
903908
std::unique_ptr<control::TrajectoryPointInterface> trajectory_interface_;
904909
std::unique_ptr<control::ScriptCommandInterface> script_command_interface_;

src/example_robot_wrapper.cpp

Lines changed: 77 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
#include <iostream>
3333
#include "ur_client_library/exceptions.h"
3434
#include "ur_client_library/log.h"
35+
#include "ur_client_library/ur/version_information.h"
3536

3637
namespace urcl
3738
{
@@ -40,24 +41,31 @@ ExampleRobotWrapper::ExampleRobotWrapper(const std::string& robot_ip, const std:
4041
const std::string& autostart_program, const std::string& script_file)
4142
: headless_mode_(headless_mode), autostart_program_(autostart_program)
4243
{
43-
dashboard_client_ = std::make_shared<DashboardClient>(robot_ip);
44+
primary_client_ = std::make_shared<urcl::primary_interface::PrimaryClient>(robot_ip, notifier_);
4445

45-
// Connect the robot Dashboard
46-
if (!dashboard_client_->connect())
46+
primary_client_->start();
47+
48+
auto robot_version = primary_client_->getRobotVersion();
49+
if (*robot_version < VersionInformation::fromString("10.0.0"))
4750
{
48-
URCL_LOG_ERROR("Could not connect to dashboard");
49-
}
51+
dashboard_client_ = std::make_shared<DashboardClient>(robot_ip);
52+
// Connect the robot Dashboard
53+
if (!dashboard_client_->connect())
54+
{
55+
URCL_LOG_ERROR("Could not connect to dashboard");
56+
}
5057

51-
// In CI we the dashboard client times out for no obvious reason. Hence we increase the timeout
52-
// here.
53-
timeval tv;
54-
tv.tv_sec = 10;
55-
tv.tv_usec = 0;
56-
dashboard_client_->setReceiveTimeout(tv);
58+
// In CI we the dashboard client times out for no obvious reason. Hence we increase the timeout
59+
// here.
60+
timeval tv;
61+
tv.tv_sec = 10;
62+
tv.tv_usec = 0;
63+
dashboard_client_->setReceiveTimeout(tv);
64+
}
5765

58-
if (!initializeRobotWithDashboard())
66+
if (!initializeRobotWithPrimaryClient())
5967
{
60-
throw UrException("Could not initialize robot with dashboard");
68+
throw UrException("Could not initialize robot with primary client");
6169
}
6270

6371
UrDriverConfiguration driver_config;
@@ -75,7 +83,7 @@ ExampleRobotWrapper::ExampleRobotWrapper(const std::string& robot_ip, const std:
7583
startRobotProgram(autostart_program);
7684
}
7785

78-
if (headless_mode | !std::empty(autostart_program))
86+
if (headless_mode || !std::empty(autostart_program))
7987
{
8088
if (!waitForProgramRunning(500))
8189
{
@@ -94,20 +102,27 @@ ExampleRobotWrapper::~ExampleRobotWrapper()
94102

95103
bool ExampleRobotWrapper::clearProtectiveStop()
96104
{
97-
std::string safety_status;
98-
dashboard_client_->commandSafetyStatus(safety_status);
99-
bool is_protective_stopped = safety_status.find("PROTECTIVE_STOP") != std::string::npos;
100-
if (is_protective_stopped)
105+
if (primary_client_->isRobotProtectiveStopped())
101106
{
102107
URCL_LOG_INFO("Robot is in protective stop, trying to release it");
103-
dashboard_client_->commandClosePopup();
104-
dashboard_client_->commandCloseSafetyPopup();
105-
if (!dashboard_client_->commandUnlockProtectiveStop())
108+
if (dashboard_client_ != nullptr)
109+
{
110+
dashboard_client_->commandClosePopup();
111+
}
112+
try
113+
{
114+
primary_client_->commandUnlockProtectiveStop();
115+
}
116+
catch (const TimeoutException&)
106117
{
107118
std::this_thread::sleep_for(std::chrono::seconds(5));
108-
if (!dashboard_client_->commandUnlockProtectiveStop())
119+
try
109120
{
110-
URCL_LOG_ERROR("Could not unlock protective stop");
121+
primary_client_->commandUnlockProtectiveStop();
122+
}
123+
catch (const TimeoutException&)
124+
{
125+
URCL_LOG_ERROR("Robot did not unlock the protective stop within the given timeout");
111126
return false;
112127
}
113128
}
@@ -157,6 +172,36 @@ bool ExampleRobotWrapper::initializeRobotWithDashboard()
157172
return true;
158173
}
159174

175+
bool ExampleRobotWrapper::initializeRobotWithPrimaryClient()
176+
{
177+
try
178+
{
179+
waitFor([&]() { return primary_client_->getRobotModeData() != nullptr; }, std::chrono::seconds(5));
180+
clearProtectiveStop();
181+
}
182+
catch (const std::exception& exc)
183+
{
184+
URCL_LOG_ERROR("Could not clear protective stop (%s)", exc.what());
185+
return false;
186+
}
187+
188+
try
189+
{
190+
primary_client_->commandStop();
191+
primary_client_->commandBrakeRelease();
192+
}
193+
catch (const TimeoutException& exc)
194+
{
195+
URCL_LOG_ERROR(exc.what());
196+
return false;
197+
}
198+
199+
// Now the robot is ready to receive a program
200+
URCL_LOG_INFO("Robot ready to start a program");
201+
robot_initialized_ = true;
202+
return true;
203+
}
204+
160205
void ExampleRobotWrapper::handleRobotProgramState(bool program_running)
161206
{
162207
// Print the text in green so we see it better
@@ -254,13 +299,17 @@ bool ExampleRobotWrapper::waitForProgramNotRunning(int milliseconds)
254299

255300
bool ExampleRobotWrapper::startRobotProgram(const std::string& program_file_name)
256301
{
257-
if (!dashboard_client_->commandLoadProgram(program_file_name))
302+
if (dashboard_client_ != nullptr)
258303
{
259-
URCL_LOG_ERROR("Could not load program '%s'", program_file_name.c_str());
260-
return false;
261-
}
304+
if (!dashboard_client_->commandLoadProgram(program_file_name))
305+
{
306+
URCL_LOG_ERROR("Could not load program '%s'", program_file_name.c_str());
307+
return false;
308+
}
262309

263-
return dashboard_client_->commandPlay();
310+
return dashboard_client_->commandPlay();
311+
}
312+
return false;
264313
}
265314
bool ExampleRobotWrapper::resendRobotProgram()
266315
{

src/primary/primary_client.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
#include <ur_client_library/primary/robot_state.h>
3434
#include "ur_client_library/exceptions.h"
3535
#include <ur_client_library/helpers.h>
36+
#include <chrono>
3637
namespace urcl
3738
{
3839
namespace primary_interface
@@ -267,6 +268,16 @@ void PrimaryClient::commandStop(const bool validate, const std::chrono::millisec
267268
}
268269
}
269270
}
271+
std::shared_ptr<VersionInformation> PrimaryClient::getRobotVersion(bool blocking,
272+
const std::chrono::milliseconds timeout)
273+
{
274+
if (blocking)
275+
{
276+
waitFor([this]() { return consumer_->getVersionInformation() != nullptr; }, timeout);
277+
}
278+
279+
return consumer_->getVersionInformation();
280+
}
270281

271282
} // namespace primary_interface
272283
} // namespace urcl

tests/test_dashboard_client.cpp

Lines changed: 14 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,12 @@
3131
#include <gtest/gtest.h>
3232
#include <ur_client_library/exceptions.h>
3333
#include <chrono>
34+
#include <sstream>
3435
#include <thread>
36+
#include "gtest/gtest.h"
37+
#include "test_utils.h"
3538
#include "ur_client_library/comm/tcp_socket.h"
39+
#include "ur_client_library/primary/primary_client.h"
3640
#include "ur_client_library/ur/version_information.h"
3741
#include <ur_client_library/ur/dashboard_client.h>
3842

@@ -61,6 +65,12 @@ class DashboardClientTest : public ::testing::Test
6165
protected:
6266
void SetUp()
6367
{
68+
if (!robotVersionLessThan(g_ROBOT_IP, "10.0.0"))
69+
{
70+
GTEST_SKIP_("Running DashboardClient tests for PolyScope X is not supported as it doesn't have a dashboard "
71+
"server.");
72+
}
73+
6474
dashboard_client_.reset(new TestableDashboardClient(g_ROBOT_IP));
6575
// In CI we the dashboard client times out for no obvious reason. Hence we increase the timeout
6676
// here.
@@ -80,13 +90,13 @@ class DashboardClientTest : public ::testing::Test
8090

8191
TEST_F(DashboardClientTest, connect)
8292
{
83-
EXPECT_TRUE(dashboard_client_->connect());
93+
EXPECT_TRUE(dashboard_client_->connect(3));
8494
dashboard_client_->commandCloseSafetyPopup();
8595
}
8696

8797
TEST_F(DashboardClientTest, run_program)
8898
{
89-
EXPECT_TRUE(dashboard_client_->connect());
99+
EXPECT_TRUE(dashboard_client_->connect(1));
90100
EXPECT_TRUE(dashboard_client_->commandLoadProgram("wait_program.urp"));
91101
EXPECT_TRUE(dashboard_client_->commandPowerOff());
92102
dashboard_client_->commandClosePopup(); // Necessary for CB3 test
@@ -104,7 +114,7 @@ TEST_F(DashboardClientTest, run_program)
104114

105115
TEST_F(DashboardClientTest, load_installation)
106116
{
107-
EXPECT_TRUE(dashboard_client_->connect());
117+
EXPECT_TRUE(dashboard_client_->connect(1));
108118
EXPECT_TRUE(dashboard_client_->commandLoadInstallation("default.installation"));
109119
}
110120

@@ -287,4 +297,4 @@ int main(int argc, char* argv[])
287297
}
288298

289299
return RUN_ALL_TESTS();
290-
}
300+
}

0 commit comments

Comments
 (0)