Skip to content

Commit

Permalink
fix compiler warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Mar 14, 2016
1 parent 8480181 commit 69b4610
Show file tree
Hide file tree
Showing 32 changed files with 80 additions and 74 deletions.
10 changes: 5 additions & 5 deletions test/test_roscpp/test/src/handles.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ TEST(RoscppHandles, nodeHandleParentWithRemappings)
}

int32_t g_recv_count = 0;
void subscriberCallback(const test_roscpp::TestArray::ConstPtr& msg)
void subscriberCallback(const test_roscpp::TestArray::ConstPtr&)
{
++g_recv_count;
}
Expand All @@ -134,7 +134,7 @@ class SubscribeHelper
: recv_count_(0)
{}

void callback(const test_roscpp::TestArray::ConstPtr& msg)
void callback(const test_roscpp::TestArray::ConstPtr&)
{
++recv_count_;
}
Expand Down Expand Up @@ -350,7 +350,7 @@ TEST(RoscppHandles, publisherMultiple)
ASSERT_TRUE(std::find(topics.begin(), topics.end(), "/test") == topics.end());
}

bool serviceCallback(TestStringString::Request& req, TestStringString::Response& res)
bool serviceCallback(TestStringString::Request&, TestStringString::Response&)
{
return true;
}
Expand Down Expand Up @@ -433,7 +433,7 @@ TEST(RoscppHandles, serviceAdvMultiple)
}

int32_t g_sub_count = 0;
void connectedCallback(const ros::SingleSubscriberPublisher& pub)
void connectedCallback(const ros::SingleSubscriberPublisher&)
{
++g_sub_count;
}
Expand Down Expand Up @@ -519,7 +519,7 @@ TEST(RoscppHandles, multiplePublishersWithSubscriberConnectCallback)
class ServiceClass
{
public:
bool serviceCallback(TestStringString::Request& req, TestStringString::Response& res)
bool serviceCallback(TestStringString::Request&, TestStringString::Response&)
{
return true;
}
Expand Down
12 changes: 6 additions & 6 deletions test/test_roscpp/test/src/intraprocess_subscriptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,18 +90,18 @@ template<>
struct Serializer<Msg>
{
template<typename Stream>
inline static void write(Stream& stream, const Msg& v)
inline static void write(Stream&, const Msg& v)
{
v.serialized = true;
}

template<typename Stream>
inline static void read(Stream& stream, Msg& v)
inline static void read(Stream&, Msg& v)
{
v.deserialized = true;
}

inline static uint32_t serializedLength(const Msg& v)
inline static uint32_t serializedLength(const Msg&)
{
return 0;
}
Expand Down Expand Up @@ -157,18 +157,18 @@ template<>
struct Serializer<Msg2>
{
template<typename Stream>
inline static void write(Stream& stream, const Msg2& v)
inline static void write(Stream&, const Msg2& v)
{
v.serialized = true;
}

template<typename Stream>
inline static void read(Stream& stream, Msg2& v)
inline static void read(Stream&, Msg2& v)
{
v.deserialized = true;
}

inline static uint32_t serializedLength(const Msg2& v)
inline static uint32_t serializedLength(const Msg2&)
{
return 0;
}
Expand Down
3 changes: 1 addition & 2 deletions test/test_roscpp/test/src/loads_of_publishers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,8 @@

uint32_t g_pub_count = 0;

void callback(const test_roscpp::TestArrayConstPtr& msg)
void callback(const test_roscpp::TestArrayConstPtr&)
{

}

TEST(LoadsOfPublishers, waitForAll)
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/multiple_init_fini.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
int g_argc;
char** g_argv;

void callback(const test_roscpp::TestArrayConstPtr& msg)
void callback(const test_roscpp::TestArrayConstPtr&)
{
}

Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/service_adv_a.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <sys/wait.h>
#include <cstdlib>

bool srvCallback(test_roscpp::TestStringString::Request &req,
bool srvCallback(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &res)
{
res.str = "A";
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/src/service_adv_multiple.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@
#include "ros/service.h"
#include <test_roscpp/TestStringString.h>

bool srvCallback(test_roscpp::TestStringString::Request &req,
test_roscpp::TestStringString::Response &res)
bool srvCallback(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &)
{
return true;
}
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/src/service_adv_unadv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ class ServiceAdvertiser : public testing::Test
bool advertised_;
bool failure_;

bool srvCallback(test_roscpp::TestStringString::Request &req,
test_roscpp::TestStringString::Response &res)
bool srvCallback(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &)
{
ROS_INFO("in callback");
if(!advertised_)
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/service_adv_zombie.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

#include <stdlib.h>

bool srvCallback(test_roscpp::TestStringString::Request &req,
bool srvCallback(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &res)
{
res.str = "B";
Expand Down
16 changes: 8 additions & 8 deletions test/test_roscpp/test/src/service_callback_types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,36 +40,36 @@

#include <vector>

bool add(test_roscpp::TestStringString::Request &req,
test_roscpp::TestStringString::Response &res )
bool add(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &)
{
return true;
}

bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event)
bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&)
{
return true;
}

bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event, const std::string& bound)
bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&, const std::string&)
{
return true;
}

struct A
{
bool add(test_roscpp::TestStringString::Request &req,
test_roscpp::TestStringString::Response &res )
bool add(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &)
{
return true;
}

bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event)
bool add2(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&)
{
return true;
}

bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>& event, const std::string& bound)
bool add3(ros::ServiceEvent<test_roscpp::TestStringString::Request, test_roscpp::TestStringString::Response>&, const std::string&)
{
return true;
}
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 @@ -6,7 +6,7 @@
#include <ros/console.h>
#include <ros/poll_manager.h>

bool dummyService(std_srvs::Empty::Request &req,std_srvs::Empty::Request &res)
bool dummyService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
{
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/service_exception.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ typedef log4cxx::helpers::ObjectPtrT<ListAppender> ListAppenderPtr;

static const char EXCEPTION[] = "custom exception message";

bool throwingService(std_srvs::Empty::Request& req, std_srvs::Empty::Request& res)
bool throwingService(std_srvs::Empty::Request&, std_srvs::Empty::Request&)
{
throw std::runtime_error(EXCEPTION);
return true;
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/service_wait_a_adv_b.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#include "ros/ros.h"
#include <test_roscpp/TestStringString.h>

bool srvCallback(test_roscpp::TestStringString::Request &req,
bool srvCallback(test_roscpp::TestStringString::Request &,
test_roscpp::TestStringString::Response &res)
{
res.str = "B";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#include <test_roscpp/TestWithHeader.h>

void callback(const test_roscpp::TestWithHeaderConstPtr& msg)
void callback(const test_roscpp::TestWithHeaderConstPtr&)
{
// No operation needed here
}
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/subscribe_empty.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class Subscriptions : public testing::Test
int msg_i;
ros::Duration dt;

void messageCallback(const test_roscpp::TestEmptyConstPtr& msg)
void messageCallback(const test_roscpp::TestEmptyConstPtr&)
{
if(failure || success)
return;
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/src/subscribe_retry_tcp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include "roscpp/Empty.h"

int32_t g_count = 0;
void callback(const test_roscpp::TestArrayConstPtr& msg)
void callback(const test_roscpp::TestArrayConstPtr&)
{
++g_count;
}
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/src/subscribe_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ template<>
struct Serializer<AnyMessage>
{
template<typename Stream, typename T>
static void allInOne(Stream s, T t)
static void allInOne(Stream, T)
{
}

Expand All @@ -95,7 +95,7 @@ struct AnyHelper
{
}

void cb(const AnyMessageConstPtr& msg)
void cb(const AnyMessageConstPtr&)
{
++count;
}
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/src/subscribe_unsubscribe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class Subscriptions : public testing::Test
ros::NodeHandle nh_;
ros::Subscriber sub_;

void messageCallback(const test_roscpp::TestArrayConstPtr& msg)
void messageCallback(const test_roscpp::TestArrayConstPtr&)
{
ROS_INFO("in callback");

Expand All @@ -65,7 +65,7 @@ class Subscriptions : public testing::Test
}
}

void autoUnsubscribeCallback(const test_roscpp::TestArrayConstPtr& msg)
void autoUnsubscribeCallback(const test_roscpp::TestArrayConstPtr&)
{
ROS_INFO("in autounsub callback");
sub_.shutdown();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#include "ros/ros.h"
#include <test_roscpp/TestArray.h>

void callback(const test_roscpp::TestArrayConstPtr& msg)
void callback(const test_roscpp::TestArrayConstPtr&)
{
}

Expand Down
6 changes: 3 additions & 3 deletions test/test_roscpp/test/src/timer_callbacks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -333,7 +333,7 @@ TEST(RoscppTimerCallbacks, stopWallTimer)
}

int32_t g_count = 0;
void timerCallback(const ros::WallTimerEvent& evt)
void timerCallback(const ros::WallTimerEvent&)
{
++g_count;
}
Expand Down Expand Up @@ -387,7 +387,7 @@ class TimerHelper
timer_ = n.createTimer(r, &TimerHelper::callback, this, oneshot);
}

void callback(const TimerEvent& e)
void callback(const TimerEvent&)
{
++total_calls_;
}
Expand Down Expand Up @@ -594,7 +594,7 @@ class Tracked
g_count = 0;
}

void callback(const TimerEvent& e)
void callback(const TimerEvent&)
{
++g_count;
}
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/test_spinners.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ using namespace ros;
int argc_;
char** argv_;

void fire_shutdown(const ros::WallTimerEvent& event) {
void fire_shutdown(const ros::WallTimerEvent&) {
ROS_INFO("Asking for shutdown");
ros::shutdown();
}
Expand Down
3 changes: 2 additions & 1 deletion test/test_roscpp/test/test_subscription_queue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class FakeMessage
virtual const std::string __getMD5Sum() const { return ""; }
virtual const std::string __getMessageDefinition() const { return ""; }
virtual uint32_t serializationLength() const { return 0; }
virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const { return write_ptr; }
virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const { (void)seq; return write_ptr; }
virtual uint8_t *deserialize(uint8_t *read_ptr) { return read_ptr; }
};

Expand All @@ -74,6 +74,7 @@ class FakeSubHelper : public SubscriptionCallbackHelper

virtual void call(SubscriptionCallbackHelperCallParams& params)
{
(void)params;
{
boost::mutex::scoped_lock lock(mutex_);
++calls_;
Expand Down
7 changes: 5 additions & 2 deletions test/test_roscpp/test_serialization/src/helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ class Allocator
template<class U>
Allocator(const Allocator<U>& u) throw ()
{
(void)u;
}

~Allocator() throw ()
Expand All @@ -115,10 +116,12 @@ class Allocator
}
pointer allocate(size_type n, Allocator<void>::const_pointer hint = 0)
{
(void)hint;
return reinterpret_cast<pointer> (malloc(n * sizeof(T)));
}
void deallocate(pointer p, size_type n)
{
(void)n;
free(p);
}

Expand All @@ -133,13 +136,13 @@ class Allocator
};

template<class T1, class T2>
inline bool operator==(const Allocator<T1>& a1, const Allocator<T2>& a2) throw ()
inline bool operator==(const Allocator<T1>&, const Allocator<T2>&) throw ()
{
return true;
}

template<class T1, class T2>
inline bool operator!=(const Allocator<T1>& a1, const Allocator<T2>& a2) throw ()
inline bool operator!=(const Allocator<T1>&, const Allocator<T2>&) throw ()
{
return false;
}
Expand Down
Loading

0 comments on commit 69b4610

Please sign in to comment.