--- Begin Message ---
- To: Debian Bug Tracking System <submit@bugs.debian.org>
- Subject: buster-pu: package ros-ros-comm/1.14.3+ds1-5+deb10u1
- From: Jochen Sprickerhof <jspricke@debian.org>
- Date: Fri, 16 Oct 2020 18:46:27 +0200
- Message-id: <160286678786.48870.8281193100441066711.reportbug@fenchel>
Package: release.debian.org
Severity: normal
Tags: buster
User: release.debian.org@packages.debian.org
Usertags: pu
[ Reason ]
CVE-2020-16124 was published with a number of integer overflow in the
XML RPC layer of ros-ros-comm.
[ Impact ]
The impact is rather low as the ROS middleware has no authentication nor
security features implemented and should only be used behind a firewall.
Still would be good to get it fixed in stable.
[ Tests ]
The patch adds a unit test and I ran manual tests using the relay
command from the topic-tools package.
[ Risks ]
I see the code as rather trivial, and the risk as low.
[ Checklist ]
[X] *all* changes are documented in the d/changelog
[X] I reviewed all changes and I approve them
[X] attach debdiff against the package in (old)stable
[X] the issue is verified as fixed in unstable
[ Changes ]
The patch adds size checks and unit tests.
[ Other info ]
I left the patches as they where merged upstream but can squash them if
that would be easier for you.
diff --git a/debian/changelog b/debian/changelog
index 2f80bb1..420c997 100644
--- a/debian/changelog
+++ b/debian/changelog
@@ -1,3 +1,9 @@
+ros-ros-comm (1.14.3+ds1-5+deb10u2) buster; urgency=high
+
+ * Add https://github.com/ros/ros_comm/pull/2065 (Fix CVE-2020-16124)
+
+ -- Jochen Sprickerhof <jspricke@debian.org> Fri, 16 Oct 2020 17:48:57 +0200
+
ros-ros-comm (1.14.3+ds1-5+deb10u1) stable; urgency=high
* Add https://github.com/ros/ros_comm/pull/1771 (Fix CVE-2019-13566, CVE-2019-13465)
diff --git a/debian/patches/0007-Build-Python-3-version-of-roslz4.patch b/debian/patches/0007-Build-Python-3-version-of-roslz4.patch
index 9487775..ab177c6 100644
--- a/debian/patches/0007-Build-Python-3-version-of-roslz4.patch
+++ b/debian/patches/0007-Build-Python-3-version-of-roslz4.patch
@@ -6,6 +6,8 @@ Subject: Build Python 3 version of roslz4
CMakeLists.txt | 9 +++++++++
1 file changed, 9 insertions(+)
+diff --git a/CMakeLists.txt b/CMakeLists.txt
+index 169420f..eb45865 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -20,3 +20,12 @@ add_subdirectory(tools/rosout)
diff --git a/debian/patches/0010-Trap-for-overly-large-input-to-XmlRPCPP-which-could-.patch b/debian/patches/0010-Trap-for-overly-large-input-to-XmlRPCPP-which-could-.patch
new file mode 100644
index 0000000..e26a0d1
--- /dev/null
+++ b/debian/patches/0010-Trap-for-overly-large-input-to-XmlRPCPP-which-could-.patch
@@ -0,0 +1,351 @@
+From: Sid Faber <sid.faber@canonical.com>
+Date: Tue, 15 Sep 2020 19:48:40 +0000
+Subject: Trap for overly large input to XmlRPCPP which could cause problems
+ with int <-> size_t conversions.
+
+ - In XmlRpcClient, XmlRpcServerConnection and XmlRpcSocket, recognize when incoming or outgoing data is too large, generate an error and discard the data when practical.
+ - Use the safe strtol() rather than atoi() to decode an incoming content-length header, and generate an error if the length is invalid or too large.
+ - In XmlRpcUtil, prevent attempts to parse overly large XML input.
+ - Add tests where they can reasonably be inserted into existing test routines.
+
+Although this fix could be cleaner the update is written to make the update ABI compatible.
+
+This fix addresses CVE-2020-16124 / Integer overflow in ros_comm.
+
+Signed-off-by: Sid Faber <sid.faber@canonical.com>
+---
+ utilities/xmlrpcpp/src/XmlRpcClient.cpp | 25 +++++++--
+ utilities/xmlrpcpp/src/XmlRpcServerConnection.cpp | 28 ++++++++--
+ utilities/xmlrpcpp/src/XmlRpcSocket.cpp | 13 +++++
+ utilities/xmlrpcpp/src/XmlRpcUtil.cpp | 5 ++
+ utilities/xmlrpcpp/test/TestValues.cpp | 27 +++++++++-
+ utilities/xmlrpcpp/test/test_client.cpp | 65 +++++++++++++++++++++++
+ 6 files changed, 153 insertions(+), 10 deletions(-)
+
+diff --git a/utilities/xmlrpcpp/src/XmlRpcClient.cpp b/utilities/xmlrpcpp/src/XmlRpcClient.cpp
+index 2d42bb8..d53214e 100644
+--- a/utilities/xmlrpcpp/src/XmlRpcClient.cpp
++++ b/utilities/xmlrpcpp/src/XmlRpcClient.cpp
+@@ -312,6 +312,13 @@ XmlRpcClient::generateRequest(const char* methodName, XmlRpcValue const& params)
+ header.length(), body.length());
+
+ _request = header + body;
++ // Limit the size of the request to avoid integer overruns
++ if (_request.length() > size_t(__INT_MAX__)) {
++ XmlRpcUtil::error("XmlRpcClient::generateRequest: request length (%u) exceeds maximum allowed size (%u).",
++ _request.length(), __INT_MAX__);
++ _request.clear();
++ return false;
++ }
+ return true;
+ }
+
+@@ -431,13 +438,16 @@ XmlRpcClient::readHeader()
+ return false; // We could try to figure it out by parsing as we read, but for now...
+ }
+
+- _contentLength = atoi(lp);
+- if (_contentLength <= 0) {
+- XmlRpcUtil::error("Error in XmlRpcClient::readHeader: Invalid Content-length specified (%d).", _contentLength);
++ // avoid overly large or improperly formatted content-length
++ long int clength = 0;
++ clength = strtol(lp, nullptr, 10);
++ if ((clength <= 0) || (clength > __INT_MAX__)) {
++ XmlRpcUtil::error("Error in XmlRpcClient::readHeader: Invalid Content-length specified.");
+ // Close the socket because we can't make further use of it.
+ close();
+ return false;
+ }
++ _contentLength = int(clength);
+
+ XmlRpcUtil::log(4, "client read content length: %d", _contentLength);
+
+@@ -448,7 +458,6 @@ XmlRpcClient::readHeader()
+ return true; // Continue monitoring this source
+ }
+
+-
+ bool
+ XmlRpcClient::readResponse()
+ {
+@@ -464,6 +473,14 @@ XmlRpcClient::readResponse()
+ }
+ _response += buff;
+
++ // Avoid an overly large response
++ if (_response.length() > size_t(__INT_MAX__)) {
++ XmlRpcUtil::error("XmlRpcClient::readResponse: response length (%u) exceeds the maximum allowed size (%u).",
++ _response.length(), __INT_MAX__);
++ _response.clear();
++ close();
++ return false;
++ }
+ // If we haven't gotten the entire _response yet, return (keep reading)
+ if (int(_response.length()) < _contentLength) {
+ if (_eof) {
+diff --git a/utilities/xmlrpcpp/src/XmlRpcServerConnection.cpp b/utilities/xmlrpcpp/src/XmlRpcServerConnection.cpp
+index 26c997f..1aeba70 100644
+--- a/utilities/xmlrpcpp/src/XmlRpcServerConnection.cpp
++++ b/utilities/xmlrpcpp/src/XmlRpcServerConnection.cpp
+@@ -119,11 +119,14 @@ XmlRpcServerConnection::readHeader()
+ return false; // We could try to figure it out by parsing as we read, but for now...
+ }
+
+- _contentLength = atoi(lp);
+- if (_contentLength <= 0) {
+- XmlRpcUtil::error("XmlRpcServerConnection::readHeader: Invalid Content-length specified (%d).", _contentLength);
++ // avoid overly large or improperly formatted content-length
++ long int clength = 0;
++ clength = strtol(lp, nullptr, 10);
++ if ((clength < 0) || (clength > __INT_MAX__)) {
++ XmlRpcUtil::error("XmlRpcServerConnection::readHeader: Invalid Content-length specified.");
+ return false;
+ }
++ _contentLength = int(clength);
+
+ XmlRpcUtil::log(3, "XmlRpcServerConnection::readHeader: specified content length is %d.", _contentLength);
+
+@@ -157,6 +160,13 @@ XmlRpcServerConnection::readRequest()
+ XmlRpcUtil::error("XmlRpcServerConnection::readRequest: read error (%s).",XmlRpcSocket::getErrorMsg().c_str());
+ return false;
+ }
++ // Avoid an overly large request
++ if (_request.length() > size_t(__INT_MAX__)) {
++ XmlRpcUtil::error("XmlRpcServerConnection::readRequest: request length (%u) exceeds the maximum allowed size (%u)",
++ _request.length(), __INT_MAX__);
++ _request.resize(__INT_MAX__);
++ return false;
++ }
+
+ // If we haven't gotten the entire request yet, return (keep reading)
+ if (int(_request.length()) < _contentLength) {
+@@ -334,8 +344,16 @@ XmlRpcServerConnection::generateResponse(std::string const& resultXml)
+ std::string body = RESPONSE_1 + resultXml + RESPONSE_2;
+ std::string header = generateHeader(body);
+
+- _response = header + body;
+- XmlRpcUtil::log(5, "XmlRpcServerConnection::generateResponse:\n%s\n", _response.c_str());
++ // Avoid an overly large response
++ if ((header.length() + body.length()) > size_t(__INT_MAX__)) {
++ XmlRpcUtil::error("XmlRpcServerConnection::generateResponse: response length (%u) exceeds the maximum allowed size (%u).",
++ _response.length(), __INT_MAX__);
++ _response = "";
++ }
++ else {
++ _response = header + body;
++ XmlRpcUtil::log(5, "XmlRpcServerConnection::generateResponse:\n%s\n", _response.c_str());
++ }
+ }
+
+ // Prepend http headers
+diff --git a/utilities/xmlrpcpp/src/XmlRpcSocket.cpp b/utilities/xmlrpcpp/src/XmlRpcSocket.cpp
+index 8c5fce0..272e3d5 100644
+--- a/utilities/xmlrpcpp/src/XmlRpcSocket.cpp
++++ b/utilities/xmlrpcpp/src/XmlRpcSocket.cpp
+@@ -313,6 +313,13 @@ XmlRpcSocket::nbRead(int fd, std::string& s, bool *eof)
+ return false; // Error
+ }
+ }
++ // Watch for integer overrun
++ if (s.length() > size_t(__INT_MAX__)) {
++ XmlRpcUtil::error("XmlRpcSocket::nbRead: text size (%u) exceeds the maximum allowed size (%s).",
++ s.length(), __INT_MAX__);
++ s.clear();
++ return false;
++ }
+ return true;
+ }
+
+@@ -321,6 +328,12 @@ XmlRpcSocket::nbRead(int fd, std::string& s, bool *eof)
+ bool
+ XmlRpcSocket::nbWrite(int fd, const std::string& s, int *bytesSoFar)
+ {
++ // Watch for integer overrun
++ if (s.length() > size_t(__INT_MAX__)) {
++ XmlRpcUtil::error("XmlRpcSocket::nbWrite: text size (%u) exceeds the maximum allowed size(%s)",
++ s.length(), __INT_MAX__);
++ return false;
++ }
+ int nToWrite = int(s.length()) - *bytesSoFar;
+ char *sp = const_cast<char*>(s.c_str()) + *bytesSoFar;
+ bool wouldBlock = false;
+diff --git a/utilities/xmlrpcpp/src/XmlRpcUtil.cpp b/utilities/xmlrpcpp/src/XmlRpcUtil.cpp
+index 901ebc8..ab0991d 100644
+--- a/utilities/xmlrpcpp/src/XmlRpcUtil.cpp
++++ b/utilities/xmlrpcpp/src/XmlRpcUtil.cpp
+@@ -108,6 +108,8 @@ void XmlRpcUtil::error(const char* fmt, ...)
+ std::string
+ XmlRpcUtil::parseTag(const char* tag, std::string const& xml, int* offset)
+ {
++ // avoid attempting to parse overly long xml input
++ if (xml.length() > size_t(__INT_MAX__)) return std::string();
+ if (*offset >= int(xml.length())) return std::string();
+ size_t istart = xml.find(tag, *offset);
+ if (istart == std::string::npos) return std::string();
+@@ -126,6 +128,7 @@ XmlRpcUtil::parseTag(const char* tag, std::string const& xml, int* offset)
+ bool
+ XmlRpcUtil::findTag(const char* tag, std::string const& xml, int* offset)
+ {
++ if (xml.length() > size_t(__INT_MAX__)) return false;
+ if (*offset >= int(xml.length())) return false;
+ size_t istart = xml.find(tag, *offset);
+ if (istart == std::string::npos)
+@@ -141,6 +144,7 @@ XmlRpcUtil::findTag(const char* tag, std::string const& xml, int* offset)
+ bool
+ XmlRpcUtil::nextTagIs(const char* tag, std::string const& xml, int* offset)
+ {
++ if (xml.length() > size_t(__INT_MAX__)) return false;
+ if (*offset >= int(xml.length())) return false;
+ const char* cp = xml.c_str() + *offset;
+ int nc = 0;
+@@ -162,6 +166,7 @@ XmlRpcUtil::nextTagIs(const char* tag, std::string const& xml, int* offset)
+ std::string
+ XmlRpcUtil::getNextTag(std::string const& xml, int* offset)
+ {
++ if (xml.length() > size_t(__INT_MAX__)) return std::string();
+ if (*offset >= int(xml.length())) return std::string();
+
+ size_t pos = *offset;
+diff --git a/utilities/xmlrpcpp/test/TestValues.cpp b/utilities/xmlrpcpp/test/TestValues.cpp
+index 842e78e..91b676a 100644
+--- a/utilities/xmlrpcpp/test/TestValues.cpp
++++ b/utilities/xmlrpcpp/test/TestValues.cpp
+@@ -27,8 +27,9 @@
+ #include <stdlib.h>
+ #include <string>
+
+-#include "xmlrpcpp/XmlRpcValue.h"
+ #include "xmlrpcpp/XmlRpcException.h"
++#include "xmlrpcpp/XmlRpcUtil.h"
++#include "xmlrpcpp/XmlRpcValue.h"
+
+ #include <gtest/gtest.h>
+
+@@ -174,6 +175,30 @@ TEST(XmlRpc, testString) {
+ EXPECT_EQ("Now is the time <&", ss.str());
+ }
+
++//Test decoding of a well-formed but overly large XML input
++TEST(XmlRpc, testOversizeString) {
++ std::string xml = "<tag><nexttag>";
++ xml += std::string(__INT_MAX__, 'a');
++ xml += "a</nextag></tag>";
++ int offset;
++
++ offset = 0;
++ EXPECT_EQ(XmlRpcUtil::parseTag("<tag>", xml, &offset), std::string());
++ EXPECT_EQ(offset, 0);
++
++ offset = 0;
++ EXPECT_FALSE(XmlRpcUtil::findTag("<tag>", xml, &offset));
++ EXPECT_EQ(offset, 0);
++
++ offset = 0;
++ EXPECT_FALSE(XmlRpcUtil::nextTagIs("<tag>", xml, &offset));
++ EXPECT_EQ(offset, 0);
++
++ offset = 0;
++ EXPECT_EQ(XmlRpcUtil::getNextTag(xml, &offset), std::string());
++ EXPECT_EQ(offset, 0);
++}
++
+ TEST(XmlRpc, testDateTime) {
+ // DateTime
+ int offset = 0;
+diff --git a/utilities/xmlrpcpp/test/test_client.cpp b/utilities/xmlrpcpp/test/test_client.cpp
+index 2318519..6c253b3 100644
+--- a/utilities/xmlrpcpp/test/test_client.cpp
++++ b/utilities/xmlrpcpp/test/test_client.cpp
+@@ -466,6 +466,11 @@ TEST(XmlRpcClient, generateRequest) {
+ "<methodCall><methodName>DoEmpty</methodName>\r\n"
+ "</methodCall>\r\n",
+ a._request);
++
++ // create a request where content fits but the message will overflow and gets truncated
++ XmlRpcValue toolarge(std::string(__INT_MAX__ - 10, 'a'));
++ EXPECT_FALSE(a.generateRequest("DoFoo", toolarge));
++ EXPECT_EQ(a._request.length(), 0);
+ }
+
+ // Test generateHeader()
+@@ -621,6 +626,11 @@ const std::string header2 = "HTTP/1.0 200 OK\r\n"
+ "Date: Mon, 30 Oct 2017 22:28:12 GMT\r\n"
+ "Content-type: text/xml\r\n"
+ "Content-length: 114\r\n\r\n";
++// Header for testing a custom Content-length value
++const std::string header3 = "HTTP/1.1 200 OK\r\n"
++ "Server: XMLRPC++ 0.7\r\n"
++ "Content-Type: text/xml\r\n"
++ "Content-length: ";
+ // Generic response XML
+ const std::string response = "<?xml version=\"1.0\"?>\r\n"
+ "<methodResponse><params><param>\r\n"
+@@ -894,6 +904,31 @@ TEST_F(MockSocketTest, readHeader_partial_err) {
+ Expect_close(8);
+ }
+
++// Test to fail when content-length is too large
++TEST_F(MockSocketTest, readHeader_oversize) {
++ XmlRpcClientForTest a("localhost", 42);
++
++ // Hack us into the correct initial state.
++ a.setfd(7);
++ a._connectionState = XmlRpcClientForTest::READ_HEADER;
++
++ // Add a large content-length to the standard header
++ std::string header_cl = header3;
++ header_cl += std::to_string(size_t(__INT_MAX__) + 1);
++ header_cl += "\r\n\r\n ";
++
++ Expect_nbRead(7, header_cl, false, true);
++ Expect_close(7);
++
++ EXPECT_FALSE(a.readHeader());
++ EXPECT_EQ(0, a._contentLength); // Content length should be reset
++
++ // Check that all expected function calls were made before destruction.
++ CheckCalls();
++}
++
++
++
+ // Test readResponse()
+ // Test read of response in a single read call
+ // Test response spread across several read calls
+@@ -1064,6 +1099,36 @@ TEST_F(MockSocketTest, readResponse_eof) {
+ CheckCalls();
+ }
+
++// Test that readResponse closes the socket and truncates the response when too
++// much data is received (even when content-length is legitimate)
++TEST_F(MockSocketTest, readResponse_oversize) {
++ XmlRpcClientForTest a("localhost", 42);
++
++ // Hack us into the correct initial state.
++ a.setfd(8);
++ a._connectionState = XmlRpcClientForTest::READ_RESPONSE;
++
++ // Create an overflow response
++ std::string response = std::string(__INT_MAX__, 'a');
++ response += "a";
++
++ // Start with a pre-populated content-length that is within bounds
++ a._contentLength = __INT_MAX__;
++
++ // Expect to read the socket
++ Expect_nbRead(8, response, true, true);
++ // Expect the socket to close
++ Expect_close(8);
++
++ // Expect readResponse to return false because the response is too long, and
++ // truncate the response.
++ EXPECT_FALSE(a.readResponse());
++ EXPECT_EQ(a._response.size(), 0);
++
++ CheckCalls();
++}
++
++
+ // Test parseResponse
+ // Test correct parsing of various response types: empty, int, double,
+ // string, bool, list, struct, date, base64, etc
diff --git a/debian/patches/0011-Trap-for-memory-allocation-error-in-tests.patch b/debian/patches/0011-Trap-for-memory-allocation-error-in-tests.patch
new file mode 100644
index 0000000..b25332f
--- /dev/null
+++ b/debian/patches/0011-Trap-for-memory-allocation-error-in-tests.patch
@@ -0,0 +1,164 @@
+From: Sid Faber <sid.faber@canonical.com>
+Date: Wed, 30 Sep 2020 15:33:48 -0400
+Subject: Trap for memory allocation error in tests
+
+Signed-off-by: Sid Faber <sid.faber@canonical.com>
+---
+ utilities/xmlrpcpp/src/XmlRpcClient.cpp | 1 +
+ utilities/xmlrpcpp/test/TestValues.cpp | 47 ++++++++++++++++--------------
+ utilities/xmlrpcpp/test/test_client.cpp | 51 +++++++++++++++++++++------------
+ 3 files changed, 60 insertions(+), 39 deletions(-)
+
+diff --git a/utilities/xmlrpcpp/src/XmlRpcClient.cpp b/utilities/xmlrpcpp/src/XmlRpcClient.cpp
+index d53214e..ad5ba96 100644
+--- a/utilities/xmlrpcpp/src/XmlRpcClient.cpp
++++ b/utilities/xmlrpcpp/src/XmlRpcClient.cpp
+@@ -458,6 +458,7 @@ XmlRpcClient::readHeader()
+ return true; // Continue monitoring this source
+ }
+
++
+ bool
+ XmlRpcClient::readResponse()
+ {
+diff --git a/utilities/xmlrpcpp/test/TestValues.cpp b/utilities/xmlrpcpp/test/TestValues.cpp
+index 91b676a..927c9a5 100644
+--- a/utilities/xmlrpcpp/test/TestValues.cpp
++++ b/utilities/xmlrpcpp/test/TestValues.cpp
+@@ -27,9 +27,9 @@
+ #include <stdlib.h>
+ #include <string>
+
++#include "xmlrpcpp/XmlRpcValue.h"
+ #include "xmlrpcpp/XmlRpcException.h"
+ #include "xmlrpcpp/XmlRpcUtil.h"
+-#include "xmlrpcpp/XmlRpcValue.h"
+
+ #include <gtest/gtest.h>
+
+@@ -177,26 +177,31 @@ TEST(XmlRpc, testString) {
+
+ //Test decoding of a well-formed but overly large XML input
+ TEST(XmlRpc, testOversizeString) {
+- std::string xml = "<tag><nexttag>";
+- xml += std::string(__INT_MAX__, 'a');
+- xml += "a</nextag></tag>";
+- int offset;
+-
+- offset = 0;
+- EXPECT_EQ(XmlRpcUtil::parseTag("<tag>", xml, &offset), std::string());
+- EXPECT_EQ(offset, 0);
+-
+- offset = 0;
+- EXPECT_FALSE(XmlRpcUtil::findTag("<tag>", xml, &offset));
+- EXPECT_EQ(offset, 0);
+-
+- offset = 0;
+- EXPECT_FALSE(XmlRpcUtil::nextTagIs("<tag>", xml, &offset));
+- EXPECT_EQ(offset, 0);
+-
+- offset = 0;
+- EXPECT_EQ(XmlRpcUtil::getNextTag(xml, &offset), std::string());
+- EXPECT_EQ(offset, 0);
++ try {
++ std::string xml = "<tag><nexttag>";
++ xml += std::string(__INT_MAX__, 'a');
++ xml += "a</nextag></tag>";
++ int offset;
++
++ offset = 0;
++ EXPECT_EQ(XmlRpcUtil::parseTag("<tag>", xml, &offset), std::string());
++ EXPECT_EQ(offset, 0);
++
++ offset = 0;
++ EXPECT_FALSE(XmlRpcUtil::findTag("<tag>", xml, &offset));
++ EXPECT_EQ(offset, 0);
++
++ offset = 0;
++ EXPECT_FALSE(XmlRpcUtil::nextTagIs("<tag>", xml, &offset));
++ EXPECT_EQ(offset, 0);
++
++ offset = 0;
++ EXPECT_EQ(XmlRpcUtil::getNextTag(xml, &offset), std::string());
++ EXPECT_EQ(offset, 0);
++ }
++ catch (std::bad_alloc& err) {
++ GTEST_SKIP() << "Unable to allocate memory for overflow tests\n";
++ }
+ }
+
+ TEST(XmlRpc, testDateTime) {
+diff --git a/utilities/xmlrpcpp/test/test_client.cpp b/utilities/xmlrpcpp/test/test_client.cpp
+index 6c253b3..1c37e51 100644
+--- a/utilities/xmlrpcpp/test/test_client.cpp
++++ b/utilities/xmlrpcpp/test/test_client.cpp
+@@ -466,11 +466,20 @@ TEST(XmlRpcClient, generateRequest) {
+ "<methodCall><methodName>DoEmpty</methodName>\r\n"
+ "</methodCall>\r\n",
+ a._request);
++}
+
+- // create a request where content fits but the message will overflow and gets truncated
+- XmlRpcValue toolarge(std::string(__INT_MAX__ - 10, 'a'));
+- EXPECT_FALSE(a.generateRequest("DoFoo", toolarge));
+- EXPECT_EQ(a._request.length(), 0);
++// create a request where content fits but the message will overflow and gets truncated
++TEST(XmlRpcClient, generateOversizeRequest) {
++ XmlRpcClientForTest a("localhost", 42);
++ // Gracefully skip this test if there's not enough memory to run it
++ try {
++ XmlRpcValue toolarge(std::string(__INT_MAX__ - 10, 'a'));
++ EXPECT_FALSE(a.generateRequest("DoFoo", toolarge));
++ EXPECT_EQ(a._request.length(), 0);
++ }
++ catch (std::bad_alloc& err) {
++ GTEST_SKIP() << "Unable to allocate memory for overflow test\n";
++ }
+ }
+
+ // Test generateHeader()
+@@ -1108,24 +1117,30 @@ TEST_F(MockSocketTest, readResponse_oversize) {
+ a.setfd(8);
+ a._connectionState = XmlRpcClientForTest::READ_RESPONSE;
+
+- // Create an overflow response
+- std::string response = std::string(__INT_MAX__, 'a');
+- response += "a";
++ try {
++ // Create an overflow response
++ std::string response = std::string(__INT_MAX__, 'a');
++ response += "a";
+
+- // Start with a pre-populated content-length that is within bounds
+- a._contentLength = __INT_MAX__;
++ // Start with a pre-populated content-length that is within bounds
++ a._contentLength = __INT_MAX__;
+
+- // Expect to read the socket
+- Expect_nbRead(8, response, true, true);
+- // Expect the socket to close
+- Expect_close(8);
++ // Expect to read the socket
++ Expect_nbRead(8, response, true, true);
++ // Expect the socket to close
++ Expect_close(8);
+
+- // Expect readResponse to return false because the response is too long, and
+- // truncate the response.
+- EXPECT_FALSE(a.readResponse());
+- EXPECT_EQ(a._response.size(), 0);
++ // Expect readResponse to return false because the response is too long, and
++ // truncate the response.
++ EXPECT_FALSE(a.readResponse());
++ EXPECT_EQ(a._response.size(), 0);
++
++ CheckCalls();
++ }
++ catch (std::bad_alloc& err) {
++ GTEST_SKIP() << "Unable to allocate memory for overflow test\n";
++ }
+
+- CheckCalls();
+ }
+
+
diff --git a/debian/patches/0012-Revert-earlier-change.patch b/debian/patches/0012-Revert-earlier-change.patch
new file mode 100644
index 0000000..36d7996
--- /dev/null
+++ b/debian/patches/0012-Revert-earlier-change.patch
@@ -0,0 +1,22 @@
+From: Sid Faber <sid.faber@canonical.com>
+Date: Wed, 30 Sep 2020 15:39:49 -0400
+Subject: Revert earlier change
+
+Signed-off-by: Sid Faber <sid.faber@canonical.com>
+---
+ utilities/xmlrpcpp/src/XmlRpcClient.cpp | 2 +-
+ 1 file changed, 1 insertion(+), 1 deletion(-)
+
+diff --git a/utilities/xmlrpcpp/src/XmlRpcClient.cpp b/utilities/xmlrpcpp/src/XmlRpcClient.cpp
+index ad5ba96..4496fab 100644
+--- a/utilities/xmlrpcpp/src/XmlRpcClient.cpp
++++ b/utilities/xmlrpcpp/src/XmlRpcClient.cpp
+@@ -458,7 +458,7 @@ XmlRpcClient::readHeader()
+ return true; // Continue monitoring this source
+ }
+
+-
++
+ bool
+ XmlRpcClient::readResponse()
+ {
diff --git a/debian/patches/0013-Update-tests.patch b/debian/patches/0013-Update-tests.patch
new file mode 100644
index 0000000..1143fff
--- /dev/null
+++ b/debian/patches/0013-Update-tests.patch
@@ -0,0 +1,101 @@
+From: Sid Faber <sid.faber@canonical.com>
+Date: Thu, 1 Oct 2020 12:19:54 -0400
+Subject: Update tests
+
+Replace call to GTEST_SKIP with output to stderr. Remove the
+redResponseOversize test since out-of-memory errors during
+testing cannot easily be handled within the existing test objects.
+
+Signed-off-by: Sid Faber <sid.faber@canonical.com>
+---
+ utilities/xmlrpcpp/test/TestValues.cpp | 2 +-
+ utilities/xmlrpcpp/test/test_client.cpp | 42 ++-------------------------------
+ 2 files changed, 3 insertions(+), 41 deletions(-)
+
+diff --git a/utilities/xmlrpcpp/test/TestValues.cpp b/utilities/xmlrpcpp/test/TestValues.cpp
+index 927c9a5..6b9d119 100644
+--- a/utilities/xmlrpcpp/test/TestValues.cpp
++++ b/utilities/xmlrpcpp/test/TestValues.cpp
+@@ -200,7 +200,7 @@ TEST(XmlRpc, testOversizeString) {
+ EXPECT_EQ(offset, 0);
+ }
+ catch (std::bad_alloc& err) {
+- GTEST_SKIP() << "Unable to allocate memory for overflow tests\n";
++ std::cerr << "[ SKIPPED ] Unable to allocate memory for test testOversizeString\n";
+ }
+ }
+
+diff --git a/utilities/xmlrpcpp/test/test_client.cpp b/utilities/xmlrpcpp/test/test_client.cpp
+index 1c37e51..bdcb53c 100644
+--- a/utilities/xmlrpcpp/test/test_client.cpp
++++ b/utilities/xmlrpcpp/test/test_client.cpp
+@@ -478,7 +478,7 @@ TEST(XmlRpcClient, generateOversizeRequest) {
+ EXPECT_EQ(a._request.length(), 0);
+ }
+ catch (std::bad_alloc& err) {
+- GTEST_SKIP() << "Unable to allocate memory for overflow test\n";
++ std::cerr << "[ SKIPPED ] Unable to allocate memory for test generateOversizeRequest\n";
+ }
+ }
+
+@@ -913,7 +913,7 @@ TEST_F(MockSocketTest, readHeader_partial_err) {
+ Expect_close(8);
+ }
+
+-// Test to fail when content-length is too large
++// Test that the read will fail when content-length is too large
+ TEST_F(MockSocketTest, readHeader_oversize) {
+ XmlRpcClientForTest a("localhost", 42);
+
+@@ -936,8 +936,6 @@ TEST_F(MockSocketTest, readHeader_oversize) {
+ CheckCalls();
+ }
+
+-
+-
+ // Test readResponse()
+ // Test read of response in a single read call
+ // Test response spread across several read calls
+@@ -1108,42 +1106,6 @@ TEST_F(MockSocketTest, readResponse_eof) {
+ CheckCalls();
+ }
+
+-// Test that readResponse closes the socket and truncates the response when too
+-// much data is received (even when content-length is legitimate)
+-TEST_F(MockSocketTest, readResponse_oversize) {
+- XmlRpcClientForTest a("localhost", 42);
+-
+- // Hack us into the correct initial state.
+- a.setfd(8);
+- a._connectionState = XmlRpcClientForTest::READ_RESPONSE;
+-
+- try {
+- // Create an overflow response
+- std::string response = std::string(__INT_MAX__, 'a');
+- response += "a";
+-
+- // Start with a pre-populated content-length that is within bounds
+- a._contentLength = __INT_MAX__;
+-
+- // Expect to read the socket
+- Expect_nbRead(8, response, true, true);
+- // Expect the socket to close
+- Expect_close(8);
+-
+- // Expect readResponse to return false because the response is too long, and
+- // truncate the response.
+- EXPECT_FALSE(a.readResponse());
+- EXPECT_EQ(a._response.size(), 0);
+-
+- CheckCalls();
+- }
+- catch (std::bad_alloc& err) {
+- GTEST_SKIP() << "Unable to allocate memory for overflow test\n";
+- }
+-
+-}
+-
+-
+ // Test parseResponse
+ // Test correct parsing of various response types: empty, int, double,
+ // string, bool, list, struct, date, base64, etc
diff --git a/debian/patches/0014-Improve-test-error-handling.patch b/debian/patches/0014-Improve-test-error-handling.patch
new file mode 100644
index 0000000..49c83a2
--- /dev/null
+++ b/debian/patches/0014-Improve-test-error-handling.patch
@@ -0,0 +1,54 @@
+From: Sid Faber <sid.faber@canonical.com>
+Date: Fri, 2 Oct 2020 10:43:43 -0400
+Subject: Improve test error handling
+
+Use GTEST_SKIP if available, otherwise print to stderr. Remove test
+that's being killed because it takes too long to handle the oversize
+test values
+---
+ utilities/xmlrpcpp/test/TestValues.cpp | 6 +++++-
+ utilities/xmlrpcpp/test/test_client.cpp | 14 --------------
+ 2 files changed, 5 insertions(+), 15 deletions(-)
+
+diff --git a/utilities/xmlrpcpp/test/TestValues.cpp b/utilities/xmlrpcpp/test/TestValues.cpp
+index 6b9d119..acd79c2 100644
+--- a/utilities/xmlrpcpp/test/TestValues.cpp
++++ b/utilities/xmlrpcpp/test/TestValues.cpp
+@@ -200,7 +200,11 @@ TEST(XmlRpc, testOversizeString) {
+ EXPECT_EQ(offset, 0);
+ }
+ catch (std::bad_alloc& err) {
+- std::cerr << "[ SKIPPED ] Unable to allocate memory for test testOversizeString\n";
++#ifdef GTEST_SKIP
++ GTEST_SKIP() << "Unable to allocate memory to run test\n";
++#else
++ std::cerr << "[ SKIPPED ] XmlRpc.testOversizeString Unable to allocate memory to run test\n";
++#endif
+ }
+ }
+
+diff --git a/utilities/xmlrpcpp/test/test_client.cpp b/utilities/xmlrpcpp/test/test_client.cpp
+index bdcb53c..9457ea5 100644
+--- a/utilities/xmlrpcpp/test/test_client.cpp
++++ b/utilities/xmlrpcpp/test/test_client.cpp
+@@ -468,20 +468,6 @@ TEST(XmlRpcClient, generateRequest) {
+ a._request);
+ }
+
+-// create a request where content fits but the message will overflow and gets truncated
+-TEST(XmlRpcClient, generateOversizeRequest) {
+- XmlRpcClientForTest a("localhost", 42);
+- // Gracefully skip this test if there's not enough memory to run it
+- try {
+- XmlRpcValue toolarge(std::string(__INT_MAX__ - 10, 'a'));
+- EXPECT_FALSE(a.generateRequest("DoFoo", toolarge));
+- EXPECT_EQ(a._request.length(), 0);
+- }
+- catch (std::bad_alloc& err) {
+- std::cerr << "[ SKIPPED ] Unable to allocate memory for test generateOversizeRequest\n";
+- }
+-}
+-
+ // Test generateHeader()
+ // Correct header is generated for various sizes and content of request body.
+ TEST(XmlRpcClient, generateHeader) {
diff --git a/debian/patches/series b/debian/patches/series
index daf961c..70ba75d 100644
--- a/debian/patches/series
+++ b/debian/patches/series
@@ -7,3 +7,8 @@
0007-Build-Python-3-version-of-roslz4.patch
0008-fixing-string-check.patch
1741.patch
+0010-Trap-for-overly-large-input-to-XmlRPCPP-which-could-.patch
+0011-Trap-for-memory-allocation-error-in-tests.patch
+0012-Revert-earlier-change.patch
+0013-Update-tests.patch
+0014-Improve-test-error-handling.patch
--- End Message ---