Skip to content

Commit

Permalink
fix various compiler warnings on bionic (#1325)
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas authored Feb 13, 2018
1 parent 2e6ac87 commit 24c90e4
Show file tree
Hide file tree
Showing 11 changed files with 58 additions and 49 deletions.
18 changes: 12 additions & 6 deletions test/test_rosbag/test/test_bag.cpp.in
Original file line number Diff line number Diff line change
Expand Up @@ -240,8 +240,9 @@ TEST(rosbag, read_indexed_1_2_succeeds) {

foreach(rosbag::MessageInstance const m, view) {
std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
if (imsg != NULL)
if (imsg != NULL) {
ASSERT_EQ(imsg->data, i++);
}
}

b.close();
Expand All @@ -259,8 +260,9 @@ TEST(rosbag, write_then_read_without_read_mode_fails) {
rosbag::View view(b);
foreach(rosbag::MessageInstance const m, view) {
std_msgs::String::ConstPtr s = m.instantiate<std_msgs::String>();
if (s != NULL)
if (s != NULL) {
ASSERT_EQ(s->data, std::string("foo"));
}
}
FAIL();
}
Expand Down Expand Up @@ -350,8 +352,9 @@ TEST(rosbag, topic_query_works) {
rosbag::View view(bag, rosbag::TopicQuery(t));
foreach(rosbag::MessageInstance const m, view) {
std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
if (imsg != NULL)
if (imsg != NULL) {
ASSERT_EQ(imsg->data, i++);
}
}

bag.close();
Expand Down Expand Up @@ -425,8 +428,9 @@ TEST(rosbag, multiple_bag_works) {

foreach(rosbag::MessageInstance const m, view) {
std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
if (imsg != NULL)
if (imsg != NULL) {
ASSERT_EQ(imsg->data, i++);
}
}

bag1.close();
Expand Down Expand Up @@ -474,8 +478,9 @@ TEST(rosbag, overlapping_query_works) {

foreach(rosbag::MessageInstance const m, view1) {
std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
if (imsg != NULL)
if (imsg != NULL) {
ASSERT_EQ(imsg->data, i);
}
if (i >= 250 && i < 750)
{
i += (j++ % 2);
Expand All @@ -488,8 +493,9 @@ TEST(rosbag, overlapping_query_works) {

foreach(rosbag::MessageInstance const m, view2) {
std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
if (imsg != NULL)
if (imsg != NULL) {
ASSERT_EQ(imsg->data, i++);
}
}

bag1.close();
Expand Down
6 changes: 4 additions & 2 deletions test/test_roscpp/test/src/multiple_subscriptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,8 +129,9 @@ TEST_F(Subscriptions, multipleSubscriptions)
should_have_it[3]);

for (int j = 0; j < 4; j++)
if (should_have_it[j])
if (should_have_it[j]) {
ASSERT_TRUE(sub(j));
}
ASSERT_TRUE(sub_wrappers());

ros::Time t_start = ros::Time::now();
Expand All @@ -146,8 +147,9 @@ TEST_F(Subscriptions, multipleSubscriptions)
}

for (int j = 0; j < 4; j++)
if (should_have_it[j])
if (should_have_it[j]) {
ASSERT_TRUE(unsub(j));
}
ASSERT_TRUE(unsub_wrappers());
}
SUCCEED();
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -563,7 +563,7 @@ TEST(Params, paramNodeHandleTemplateFunction)
TEST(Params, getParamNames) {
std::vector<std::string> test_params;
EXPECT_TRUE(ros::param::getParamNames(test_params));
EXPECT_LT(10, test_params.size());
EXPECT_LT(10u, test_params.size());
}

int
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/service_deadlock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ TEST(roscpp, ServiceDeadlocking)
++j;
}
ROS_INFO("Made it through %u loops in %u seconds", j, seconds);
ASSERT_GE(j, 1000);
ASSERT_GE(j, 1000u);
}

int main(int argc, char **argv)
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/string_msg_expect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ TEST(Expecter, impl)
loop_rate.sleep();
}

ASSERT_GT(nseen, 0);
ASSERT_GT(nseen, 0u);
}

int
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/test_transport_tcp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ TEST_F(Synchronous, readWhileWriting)
for (int i = 0; i < 10; ++i)
{
const uint32_t buf_size = 1024*1024;
std::auto_ptr<uint8_t> read_buf(new uint8_t[buf_size]);
boost::shared_ptr<uint8_t[]> read_buf(new uint8_t[buf_size]);

std::stringstream ss;
for (int i = 0; i < 100000; ++i)
Expand Down
8 changes: 4 additions & 4 deletions utilities/xmlrpcpp/test/TestValues.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -432,7 +432,7 @@ TEST(XmlRpc, base64) {
d = bin3;
EXPECT_EQ(XmlRpcValue::TypeBase64, bin3.getType());
EXPECT_EQ(0, bin3.size());
EXPECT_EQ(0, d.size());
EXPECT_EQ(0u, d.size());

// Copy operator
XmlRpcValue bin4;
Expand All @@ -457,7 +457,7 @@ TEST(XmpRpc, errors) {
EXPECT_FALSE(v);

// Conversions to other types should now throw an XmlRpcException.
EXPECT_THROW((int)value, XmlRpcException);
EXPECT_THROW((void)(int)value, XmlRpcException);
EXPECT_THROW(value[0], XmlRpcException);
EXPECT_THROW(value["bar"], XmlRpcException);

Expand Down Expand Up @@ -491,15 +491,15 @@ TEST(XmlRpc, int_errors) {
EXPECT_EQ(0, (int)value);

// Conversion to other types should now thrown an exception.
EXPECT_THROW((bool)value, XmlRpcException);
EXPECT_THROW((void)(bool)value, XmlRpcException);
}

TEST(XmlRpc, array_errors) {
XmlRpcValue value;
// Implicit array creation.
int v = value[0];
EXPECT_EQ(0, v);
EXPECT_THROW((bool)value, XmlRpcException);
EXPECT_THROW((void)(bool)value, XmlRpcException);
EXPECT_EQ(1, value.size());

// Access on a non-const array should implicitly create another element.
Expand Down
20 changes: 10 additions & 10 deletions utilities/xmlrpcpp/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -501,7 +501,7 @@ TEST_F(MockSocketTest, writeRequest) {
a._request = "FAKE_REQUEST";

// Check that request length is the correct size.
ASSERT_EQ(12, a._request.size());
ASSERT_EQ(12u, a._request.size());

// Expect a write; write all bytes and return success.
Expect_nbWrite(7, "FAKE_REQUEST", 12, true);
Expand All @@ -528,7 +528,7 @@ TEST_F(MockSocketTest, writeRequest_partial) {
a._request = "FAKE_REQUEST";

// Check that request length is the correct size.
ASSERT_EQ(12, a._request.size());
ASSERT_EQ(12u, a._request.size());

// Expect a write; only write 5 bytes and return success.
Expect_nbWrite(7, "FAKE_REQUEST", 5, true);
Expand Down Expand Up @@ -561,7 +561,7 @@ TEST_F(MockSocketTest, writeRequest_partial_error) {
a._request = "FAKE_REQUEST";

// Check that request length is the correct size.
ASSERT_EQ(12, a._request.size());
ASSERT_EQ(12u, a._request.size());

// Expect a write; only write 5 bytes and return success.
Expect_nbWrite(7, "FAKE_REQUEST", 5, true);
Expand Down Expand Up @@ -595,7 +595,7 @@ TEST_F(MockSocketTest, writeRequest_error) {
a._request = "FAKE_REQUEST";

// Check that request length is the correct size.
ASSERT_EQ(12, a._request.size());
ASSERT_EQ(12u, a._request.size());

// Expect a write; write no bytes and return error.
Expect_nbWrite(7, "FAKE_REQUEST", 0, false);
Expand Down Expand Up @@ -646,7 +646,7 @@ TEST_F(MockSocketTest, readHeader) {
a._connectionState = XmlRpcClient::READ_HEADER;

// Self-test that response length matches encoded values above.
ASSERT_EQ(114, response.length());
ASSERT_EQ(114u, response.length());

// Expect a read and have it return the header and the response.
Expect_nbRead(7, header + response, false, true);
Expand Down Expand Up @@ -913,7 +913,7 @@ TEST_F(MockSocketTest, readResponse_noop) {
// (verified by previous tests).
a._response = response;
a._contentLength = 114;
ASSERT_EQ(a._contentLength, a._response.length());
ASSERT_EQ(114u, a._response.length());

// Don't expect any calls. Expect readResponse to return false since we don't
// need to keep monitoring this client.
Expand Down Expand Up @@ -942,7 +942,7 @@ TEST_F(MockSocketTest, readResponse) {
// Start with empty response and pre-populated content length.
a._response = "";
a._contentLength = 114;
ASSERT_EQ(114, response.length());
ASSERT_EQ(114u, response.length());

// Expect a read, have it return the full response and success.
Expect_nbRead(7, response, false, true);
Expand Down Expand Up @@ -972,7 +972,7 @@ TEST_F(MockSocketTest, readResponse_partial) {
// Start with empty response and pre-populated content length.
a._response = "";
a._contentLength = 114;
ASSERT_EQ(114, response.length());
ASSERT_EQ(114u, response.length());

const std::string response_part1 = response.substr(0, 60);
const std::string response_part2 = response.substr(60);
Expand Down Expand Up @@ -1019,7 +1019,7 @@ TEST_F(MockSocketTest, readResponse_err) {
// Start with empty response and pre-populated content length.
a._response = "";
a._contentLength = 114;
ASSERT_EQ(114, response.length());
ASSERT_EQ(114u, response.length());

// Expect a read, have it return an error.
Expect_nbRead(7, "", false, false);
Expand Down Expand Up @@ -1047,7 +1047,7 @@ TEST_F(MockSocketTest, readResponse_eof) {
// Start with empty response and pre-populated content length.
a._response = "";
a._contentLength = 114;
ASSERT_EQ(114, response.length());
ASSERT_EQ(114u, response.length());

// Expect a read, have it return nothing and EOF.
Expect_nbRead(7, "", true, true);
Expand Down
20 changes: 10 additions & 10 deletions utilities/xmlrpcpp/test/test_dispatch.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ class MockSourceTest : public ::testing::Test {
TEST_F(MockSourceTest, ReadEvent) {
m.event_result = XmlRpcDispatch::ReadableEvent;
dispatch.addSource(&m, XmlRpcDispatch::ReadableEvent);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);

// Select returns not readable; expect no events.
fds[0].events = POLLIN;
Expand All @@ -237,7 +237,7 @@ TEST_F(MockSourceTest, WriteEvent) {
m.setKeepOpen();
m.event_result = 0;
dispatch.addSource(&m, XmlRpcDispatch::WritableEvent);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);

// Select returns writeable, expect one write event.
fds[0].events = POLLOUT;
Expand All @@ -249,7 +249,7 @@ TEST_F(MockSourceTest, WriteEvent) {
EXPECT_CLOSE_CALLS(0);
// However, even if keepOpen is set, we expect the socket to be removed from
// the sources list
EXPECT_EQ(dispatch._sources.size(), 0);
EXPECT_EQ(dispatch._sources.size(), 0u);

// Expect no more events. Since there's nothing in the dispatch list, we
// don't expect that select will be called.
Expand All @@ -261,7 +261,7 @@ TEST_F(MockSourceTest, WriteEvent) {
TEST_F(MockSourceTest, NonWriteable) {
m.event_result = XmlRpcDispatch::WritableEvent;
dispatch.addSource(&m, XmlRpcDispatch::WritableEvent);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);

// Select doesn't return writable.
fds[0].events = POLLOUT;
Expand All @@ -270,13 +270,13 @@ TEST_F(MockSourceTest, NonWriteable) {
dispatch.work(0.1);
EXPECT_EVENTS(0);
EXPECT_CLOSE_CALLS(0);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);
}

TEST_F(MockSourceTest, WriteClose) {
m.event_result = 0;
dispatch.addSource(&m, XmlRpcDispatch::WritableEvent);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);

// Socket is always writeable. Expect 1 write event since we clear the write
// event flag after we write once
Expand All @@ -290,7 +290,7 @@ TEST_F(MockSourceTest, WriteClose) {
// that the dispatch has called close() once and that the size of sources is
// now 0
EXPECT_CLOSE_CALLS(1);
EXPECT_EQ(dispatch._sources.size(), 0);
EXPECT_EQ(dispatch._sources.size(), 0u);

// Expect no more events. Since there's nothing in the dispatch list, we
// don't expect that select will be called.
Expand All @@ -302,7 +302,7 @@ TEST_F(MockSourceTest, WriteClose) {
TEST_F(MockSourceTest, Exception) {
m.event_result = XmlRpcDispatch::Exception;
dispatch.addSource(&m, XmlRpcDispatch::Exception);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);

// Select returns no exception, so expect that the handler was not called.
fds[0].events = POLLPRI;
Expand All @@ -326,7 +326,7 @@ TEST_F(MockSourceTest, LargeFd) {
m.setfd(1025);
m.event_result = XmlRpcDispatch::WritableEvent;
dispatch.addSource(&m, XmlRpcDispatch::WritableEvent);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);

// Make select return writable, expect 1 write event.
fds[0].fd = 1025;
Expand All @@ -336,7 +336,7 @@ TEST_F(MockSourceTest, LargeFd) {
dispatch.work(0.1);
EXPECT_EVENT(XmlRpcDispatch::WritableEvent);
EXPECT_CLOSE_CALLS(0);
EXPECT_EQ(dispatch._sources.size(), 1);
EXPECT_EQ(dispatch._sources.size(), 1u);
}

int main(int argc, char **argv)
Expand Down
Loading

0 comments on commit 24c90e4

Please sign in to comment.