Skip to content

Commit 46934cc

Browse files
authored
Reduce usage of dashboard client in tests and examples (#296)
As we now have more capabilities in the primary interface, we don't need to rely on the dashboard client to initialize the robot in the example robot wrapper.
1 parent b42da6d commit 46934cc

11 files changed

+244
-49
lines changed

include/ur_client_library/example_robot_wrapper.h

+12-2
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
*
@@ -167,12 +169,20 @@ class ExampleRobotWrapper
167169

168170
bool isHealthy() const;
169171

170-
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 */
172+
//! Dashboard client to interact with the robot
173+
std::shared_ptr<urcl::DashboardClient> dashboard_client_;
174+
175+
//! primary client to interact with the robot
176+
std::shared_ptr<urcl::primary_interface::PrimaryClient> primary_client_;
177+
178+
//! UR driver to interact with the robot
179+
std::shared_ptr<urcl::UrDriver> ur_driver_;
172180

173181
private:
174182
void handleRobotProgramState(bool program_running);
175183

184+
comm::INotifier notifier_;
185+
176186
std::atomic<bool> rtde_communication_started_ = false;
177187
std::atomic<bool> consume_rtde_packages_ = false;
178188
std::mutex read_package_mutex_;

include/ur_client_library/primary/primary_client.h

+17
Original file line numberDiff line numberDiff line change
@@ -171,6 +171,23 @@ class PrimaryClient
171171
return static_cast<RobotMode>(consumer_->getRobotModeData()->robot_mode_);
172172
}
173173

174+
/*!
175+
* \brief Get the robot's software version as Major.Minor.Bugfix
176+
*
177+
* This function by default blocks until a VersionMessage has been received and returns that
178+
* version information. If there is an older version message that has been received, this is
179+
* returned directly.
180+
*
181+
* \param blocking If true, the function will block until there is a valid version information
182+
* received by the client or the timeout passed by.
183+
* \param timeout The maximum time to wait for a valid version message.
184+
*
185+
* \throws urcl::TimeoutException if no message was received until the given timeout passed by.
186+
*
187+
*/
188+
std::shared_ptr<VersionInformation>
189+
getRobotVersion(bool wait_for_message = true, const std::chrono::milliseconds timeout = std::chrono::seconds(2));
190+
174191
/*!
175192
* \brief Get the latest robot mode data.
176193
*

include/ur_client_library/primary/primary_consumer.h

+22
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,26 @@ class PrimaryConsumer : public AbstractPrimaryConsumer
196203
return robot_mode_;
197204
}
198205

206+
/*!
207+
* \brief Get the latest version information.
208+
*
209+
* The version information will be updated in the background. This will always show the latest
210+
* received version information independent of the time that has passed since receiving it. If no
211+
* version information has been received yet, this will return a nullptr.
212+
*/
213+
std::shared_ptr<VersionInformation> getVersionInformation()
214+
{
215+
std::scoped_lock lock(version_information_mutex_);
216+
return version_information_;
217+
}
218+
199219
private:
200220
std::function<void(ErrorCode&)> error_code_message_callback_;
201221
std::shared_ptr<KinematicsInfo> kinematics_info_;
202222
std::mutex robot_mode_mutex_;
203223
std::shared_ptr<RobotModeData> robot_mode_;
224+
std::mutex version_information_mutex_;
225+
std::shared_ptr<VersionInformation> version_information_;
204226
};
205227

206228
} // namespace primary_interface

include/ur_client_library/ur/ur_driver.h

+6-1
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

+81-28
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,28 @@ 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+
dashboard_client_->commandCloseSafetyPopup();
112+
}
113+
try
114+
{
115+
primary_client_->commandUnlockProtectiveStop();
116+
}
117+
catch (const TimeoutException&)
106118
{
107119
std::this_thread::sleep_for(std::chrono::seconds(5));
108-
if (!dashboard_client_->commandUnlockProtectiveStop())
120+
try
109121
{
110-
URCL_LOG_ERROR("Could not unlock protective stop");
122+
primary_client_->commandUnlockProtectiveStop();
123+
}
124+
catch (const TimeoutException&)
125+
{
126+
URCL_LOG_ERROR("Robot could not unlock the protective stop");
111127
return false;
112128
}
113129
}
@@ -157,6 +173,36 @@ bool ExampleRobotWrapper::initializeRobotWithDashboard()
157173
return true;
158174
}
159175

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

255301
bool ExampleRobotWrapper::startRobotProgram(const std::string& program_file_name)
256302
{
257-
if (!dashboard_client_->commandLoadProgram(program_file_name))
303+
if (dashboard_client_ != nullptr)
258304
{
259-
URCL_LOG_ERROR("Could not load program '%s'", program_file_name.c_str());
260-
return false;
261-
}
305+
if (!dashboard_client_->commandLoadProgram(program_file_name))
306+
{
307+
URCL_LOG_ERROR("Could not load program '%s'", program_file_name.c_str());
308+
return false;
309+
}
262310

263-
return dashboard_client_->commandPlay();
311+
return dashboard_client_->commandPlay();
312+
}
313+
URCL_LOG_ERROR("Dashboard client is not initialized. If you are running a PolyScope X robot, the dashboard server is "
314+
"not available. Loading and running polyscope programs isn't possible. Please use the headless mode "
315+
"or the teach pendant instead.");
316+
return false;
264317
}
265318
bool ExampleRobotWrapper::resendRobotProgram()
266319
{

src/primary/primary_client.cpp

+11
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

+9-1
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@
3232
#include <ur_client_library/exceptions.h>
3333
#include <chrono>
3434
#include <thread>
35+
#include "gtest/gtest.h"
36+
#include "test_utils.h"
3537
#include "ur_client_library/comm/tcp_socket.h"
3638
#include "ur_client_library/ur/version_information.h"
3739
#include <ur_client_library/ur/dashboard_client.h>
@@ -61,6 +63,12 @@ class DashboardClientTest : public ::testing::Test
6163
protected:
6264
void SetUp()
6365
{
66+
if (!robotVersionLessThan(g_ROBOT_IP, "10.0.0"))
67+
{
68+
GTEST_SKIP_("Running DashboardClient tests for PolyScope X is not supported as it doesn't have a dashboard "
69+
"server.");
70+
}
71+
6472
dashboard_client_.reset(new TestableDashboardClient(g_ROBOT_IP));
6573
// In CI we the dashboard client times out for no obvious reason. Hence we increase the timeout
6674
// here.
@@ -287,4 +295,4 @@ int main(int argc, char* argv[])
287295
}
288296

289297
return RUN_ALL_TESTS();
290-
}
298+
}

0 commit comments

Comments
 (0)