Skip to content

Commit 881adb0

Browse files
Tcp socket improvements (#222)
Couple of improvements related to TCP communication: 1. the error handling in `tcp_server::readData` seems wrong since the error case should be when the number of bytes received is strictly negative and not equal to 0 2. added early disconnection in `tcp_socket::read` in case of permanent failure in order to ease failure detection 3. added robustness to `UrDriver::sendScript`: the program sending is now retried once after closing and reconnecting the secondary stream. This is the workaround described in UniversalRobots/Universal_Robots_ROS_Driver#459. It helps mitigate program sending issues when working with the UR ROS2 driver in headless mode. New tests added for 2 and 3. For 1 the debug output of `TCPServerTest::client_connections` seems to confirm the behaviour makes sense. We now see `client from FD <xx> sent a connection reset package` which is what I'd expect given the client willingly terminates connection.
1 parent 85fbc55 commit 881adb0

File tree

6 files changed

+87
-8
lines changed

6 files changed

+87
-8
lines changed

include/ur_client_library/ur/ur_driver.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -489,6 +489,14 @@ class UrDriver
489489

490490
private:
491491
static std::string readScriptFile(const std::string& filename);
492+
/*!
493+
* \brief Reconnects the secondary stream used to send program to the robot.
494+
*
495+
* Only for use in headless mode, as it replaces the use of the URCaps program.
496+
*
497+
* \returns true of on successful reconnection, false otherwise
498+
*/
499+
bool reconnectSecondaryStream();
492500

493501
int rtde_frequency_;
494502
comm::INotifier notifier_;

src/comm/tcp_server.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -296,12 +296,13 @@ void TCPServer::readData(const int fd)
296296
}
297297
else
298298
{
299-
if (0 < nbytesrecv)
299+
if (nbytesrecv < 0)
300300
{
301301
if (errno == ECONNRESET) // if connection gets reset by client, we want to suppress this output
302302
{
303-
URCL_LOG_DEBUG("client from FD %s sent a connection reset package.", fd);
303+
URCL_LOG_DEBUG("client from FD %d sent a connection reset package.", fd);
304304
}
305+
else
305306
{
306307
URCL_LOG_ERROR("recv() on FD %d failed.", fd);
307308
}

src/comm/tcp_socket.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,14 @@ bool TCPSocket::read(uint8_t* buf, const size_t buf_len, size_t& read)
187187
return false;
188188
}
189189
else if (res < 0)
190+
{
191+
if (!(errno == EAGAIN || errno == EWOULDBLOCK))
192+
{
193+
// any permanent error should be detected early
194+
state_ = SocketState::Disconnected;
195+
}
190196
return false;
197+
}
191198

192199
read = static_cast<size_t>(res);
193200
return true;

src/ur/ur_driver.cpp

Lines changed: 34 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -542,9 +542,8 @@ bool UrDriver::sendScript(const std::string& program)
542542
{
543543
if (secondary_stream_ == nullptr)
544544
{
545-
throw std::runtime_error("Sending script to robot requested while there is no primary interface established. "
546-
"This "
547-
"should not happen.");
545+
throw std::runtime_error("Sending script to robot requested while there is no secondary interface established. "
546+
"This should not happen.");
548547
}
549548

550549
// urscripts (snippets) must end with a newline, or otherwise the controller's runtime will
@@ -556,12 +555,28 @@ bool UrDriver::sendScript(const std::string& program)
556555
const uint8_t* data = reinterpret_cast<const uint8_t*>(program_with_newline.c_str());
557556
size_t written;
558557

559-
if (secondary_stream_->write(data, len, written))
558+
const auto send_script_contents = [this, program_with_newline, data, len,
559+
&written](const std::string&& description) -> bool {
560+
if (secondary_stream_->write(data, len, written))
561+
{
562+
URCL_LOG_DEBUG("Sent program to robot:\n%s", program_with_newline.c_str());
563+
return true;
564+
}
565+
const std::string error_message = "Could not send program to robot: " + description;
566+
URCL_LOG_ERROR(error_message.c_str());
567+
return false;
568+
};
569+
570+
if (send_script_contents("initial attempt"))
560571
{
561-
URCL_LOG_DEBUG("Sent program to robot:\n%s", program_with_newline.c_str());
562572
return true;
563573
}
564-
URCL_LOG_ERROR("Could not send program to robot");
574+
575+
if (reconnectSecondaryStream())
576+
{
577+
return send_script_contents("after reconnecting secondary stream");
578+
}
579+
565580
return false;
566581
}
567582

@@ -578,6 +593,19 @@ bool UrDriver::sendRobotProgram()
578593
}
579594
}
580595

596+
bool UrDriver::reconnectSecondaryStream()
597+
{
598+
URCL_LOG_DEBUG("Closing secondary stream...");
599+
secondary_stream_->close();
600+
if (secondary_stream_->connect())
601+
{
602+
URCL_LOG_DEBUG("Secondary stream connected");
603+
return true;
604+
}
605+
URCL_LOG_ERROR("Failed to reconnect secondary stream!");
606+
return false;
607+
}
608+
581609
std::vector<std::string> UrDriver::getRTDEOutputRecipe()
582610
{
583611
return rtde_client_->getOutputRecipe();

tests/test_tcp_socket.cpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -360,6 +360,28 @@ TEST_F(TCPSocketTest, test_deprecated_reconnection_time_interface)
360360
EXPECT_TRUE(client_->setup(2));
361361
}
362362

363+
TEST_F(TCPSocketTest, test_read_on_socket_abruptly_closed)
364+
{
365+
client_->setup();
366+
367+
// Make sure the client has connected to the server, before writing to the client
368+
EXPECT_TRUE(waitForConnectionCallback());
369+
370+
std::string send_message = "test message";
371+
size_t len = send_message.size();
372+
const uint8_t* data = reinterpret_cast<const uint8_t*>(send_message.c_str());
373+
size_t written;
374+
server_->write(client_fd_, data, len, written);
375+
376+
// Simulate socket failure
377+
close(client_->getSocketFD());
378+
379+
char characters;
380+
size_t read_chars = 0;
381+
EXPECT_FALSE(client_->read((uint8_t*)&characters, 1, read_chars));
382+
EXPECT_EQ(client_->getState(), comm::SocketState::Disconnected);
383+
}
384+
363385
int main(int argc, char* argv[])
364386
{
365387
::testing::InitGoogleTest(&argc, argv);

tests/test_ur_driver.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -359,6 +359,19 @@ TEST_F(UrDriverTest, target_outside_limits_pose)
359359
waitForProgramNotRunning(1000);
360360
}
361361

362+
TEST_F(UrDriverTest, send_robot_program_retry_on_failure)
363+
{
364+
// Start robot program
365+
g_ur_driver_->sendRobotProgram();
366+
EXPECT_TRUE(waitForProgramRunning(1000));
367+
368+
// Check that sendRobotProgram is robust to the secondary stream being disconnected. This is what happens when
369+
// switching from Remote to Local and back to Remote mode for example.
370+
g_ur_driver_->secondary_stream_->close();
371+
372+
EXPECT_TRUE(g_ur_driver_->sendRobotProgram());
373+
}
374+
362375
// TODO we should add more tests for the UrDriver class.
363376

364377
int main(int argc, char* argv[])

0 commit comments

Comments
 (0)