Renamed tests to be more meaningful, #1746.
This commit is contained in:
parent
f8dda81a84
commit
8cb6577961
|
@ -41,7 +41,7 @@
|
|||
int g_argc;
|
||||
char** g_argv;
|
||||
|
||||
class MultiSub : public testing::Test
|
||||
class Subscriptions : public testing::Test
|
||||
{
|
||||
public:
|
||||
ros::NodeHandle nh_;
|
||||
|
@ -79,10 +79,10 @@ class MultiSub : public testing::Test
|
|||
ROS_INFO("Subscribing %d", cb_num);
|
||||
boost::function<void(const test_roscpp::TestArrayConstPtr&)> funcs[4] =
|
||||
{
|
||||
boost::bind(&MultiSub::cb0, this, _1),
|
||||
boost::bind(&MultiSub::cb1, this, _1),
|
||||
boost::bind(&MultiSub::cb2, this, _1),
|
||||
boost::bind(&MultiSub::cb3, this, _1),
|
||||
boost::bind(&Subscriptions::cb0, this, _1),
|
||||
boost::bind(&Subscriptions::cb1, this, _1),
|
||||
boost::bind(&Subscriptions::cb2, this, _1),
|
||||
boost::bind(&Subscriptions::cb3, this, _1),
|
||||
};
|
||||
|
||||
subs_[cb_num] = nh_.subscribe("test_roscpp/pubsub_test", 10, funcs[cb_num]);
|
||||
|
@ -92,8 +92,8 @@ class MultiSub : public testing::Test
|
|||
bool sub_wrappers()
|
||||
{
|
||||
ROS_INFO("sub_wrappers");
|
||||
verify_sub_ = nh_.subscribe("test_roscpp/pubsub_test", 10, &MultiSub::cb_verify, this);
|
||||
reset_sub_ = nh_.subscribe("test_roscpp/pubsub_test", 10, &MultiSub::cb_reset, this);
|
||||
verify_sub_ = nh_.subscribe("test_roscpp/pubsub_test", 10, &Subscriptions::cb_verify, this);
|
||||
reset_sub_ = nh_.subscribe("test_roscpp/pubsub_test", 10, &Subscriptions::cb_reset, this);
|
||||
return verify_sub_ && reset_sub_;
|
||||
}
|
||||
bool unsub(int cb_num)
|
||||
|
@ -112,7 +112,7 @@ class MultiSub : public testing::Test
|
|||
}
|
||||
};
|
||||
|
||||
TEST_F(MultiSub, pubSubNFast)
|
||||
TEST_F(Subscriptions, multipleSubscriptions)
|
||||
{
|
||||
test_ready = false;
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@ static char** g_argv;
|
|||
bool failure;
|
||||
bool advertised;
|
||||
|
||||
class Pub : public testing::Test
|
||||
class Publications : public testing::Test
|
||||
{
|
||||
public:
|
||||
ros::NodeHandle nh_;
|
||||
|
@ -63,7 +63,7 @@ public:
|
|||
|
||||
bool adv()
|
||||
{
|
||||
pub_ = nh_.advertise<test_roscpp::TestArray>("test_roscpp/pubsub_test", 1, boost::bind(&Pub::subscriberCallback, this, _1));
|
||||
pub_ = nh_.advertise<test_roscpp::TestArray>("test_roscpp/pubsub_test", 1, boost::bind(&Publications::subscriberCallback, this, _1));
|
||||
return pub_;
|
||||
}
|
||||
|
||||
|
@ -73,7 +73,7 @@ public:
|
|||
}
|
||||
|
||||
protected:
|
||||
Pub() {}
|
||||
Publications() {}
|
||||
void SetUp()
|
||||
{
|
||||
advertised = false;
|
||||
|
@ -86,7 +86,7 @@ protected:
|
|||
}
|
||||
};
|
||||
|
||||
TEST_F(Pub, pubUnadvertise)
|
||||
TEST_F(Publications, pubUnadvertise)
|
||||
{
|
||||
advertised = true;
|
||||
ROS_INFO("advertising");
|
||||
|
|
|
@ -48,7 +48,7 @@ int g_msg_count;
|
|||
ros::Duration g_dt;
|
||||
uint32_t g_options;
|
||||
|
||||
class SubPub : public testing::Test
|
||||
class Subscriptions : public testing::Test
|
||||
{
|
||||
public:
|
||||
bool success;
|
||||
|
@ -106,12 +106,12 @@ class SubPub : public testing::Test
|
|||
}
|
||||
};
|
||||
|
||||
TEST_F(SubPub, pubSubNFast)
|
||||
TEST_F(Subscriptions, subPub)
|
||||
{
|
||||
ros::NodeHandle nh;
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", 0, &SubPub::messageCallback, (SubPub*)this);
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", 0, &Subscriptions::messageCallback, (Subscriptions*)this);
|
||||
ASSERT_TRUE(sub);
|
||||
pub_ = nh.advertise<test_roscpp::TestArray>("test_roscpp/subpub_test", 0, boost::bind(&SubPub::subscriberCallback, this, _1));
|
||||
pub_ = nh.advertise<test_roscpp::TestArray>("test_roscpp/subpub_test", 0, boost::bind(&Subscriptions::subscriberCallback, this, _1));
|
||||
ASSERT_TRUE(pub_);
|
||||
ros::Time t1(ros::Time::now()+g_dt);
|
||||
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
int g_argc;
|
||||
char** g_argv;
|
||||
|
||||
class PubSub : public testing::Test
|
||||
class Subscriptions : public testing::Test
|
||||
{
|
||||
public:
|
||||
test_roscpp::TestEmpty msg;
|
||||
|
@ -71,7 +71,7 @@ class PubSub : public testing::Test
|
|||
}
|
||||
|
||||
protected:
|
||||
PubSub() {}
|
||||
Subscriptions() {}
|
||||
void SetUp()
|
||||
{
|
||||
success = false;
|
||||
|
@ -87,10 +87,10 @@ class PubSub : public testing::Test
|
|||
}
|
||||
};
|
||||
|
||||
TEST_F(PubSub, pubSubNFast)
|
||||
TEST_F(Subscriptions, emptyMsg)
|
||||
{
|
||||
ros::NodeHandle nh;
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", msg_count, &PubSub::messageCallback, (PubSub*)this);
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", msg_count, &Subscriptions::messageCallback, (Subscriptions*)this);
|
||||
ros::Time t1(ros::Time::now()+dt);
|
||||
|
||||
while(ros::Time::now() < t1 && !success)
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
int g_argc;
|
||||
char** g_argv;
|
||||
|
||||
class PubSub : public testing::Test
|
||||
class Subscriptions : public testing::Test
|
||||
{
|
||||
public:
|
||||
// A node is needed to make a service call
|
||||
|
@ -96,7 +96,7 @@ class PubSub : public testing::Test
|
|||
}
|
||||
|
||||
protected:
|
||||
PubSub() {}
|
||||
Subscriptions() {}
|
||||
void SetUp()
|
||||
{
|
||||
success = false;
|
||||
|
@ -122,7 +122,7 @@ class PubSub : public testing::Test
|
|||
}
|
||||
};
|
||||
|
||||
TEST_F(PubSub, pubSubNFast)
|
||||
TEST_F(Subscriptions, pubSubNFast)
|
||||
{
|
||||
ros::TransportHints hints;
|
||||
if (reliable)
|
||||
|
@ -130,7 +130,7 @@ TEST_F(PubSub, pubSubNFast)
|
|||
else
|
||||
hints.unreliable();
|
||||
|
||||
ros::Subscriber sub = n.subscribe("test_roscpp/pubsub_test", msgs_expected, &PubSub::MsgCallback, (PubSub *)this, hints);
|
||||
ros::Subscriber sub = n.subscribe("test_roscpp/pubsub_test", msgs_expected, &Subscriptions::MsgCallback, (Subscriptions *)this, hints);
|
||||
|
||||
ASSERT_TRUE(sub);
|
||||
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
int g_argc;
|
||||
char** g_argv;
|
||||
|
||||
class PubSub : public testing::Test
|
||||
class Subscriptions : public testing::Test
|
||||
{
|
||||
public:
|
||||
bool success;
|
||||
|
@ -75,7 +75,7 @@ class PubSub : public testing::Test
|
|||
}
|
||||
|
||||
protected:
|
||||
PubSub() {}
|
||||
Subscriptions() {}
|
||||
void SetUp()
|
||||
{
|
||||
success = false;
|
||||
|
@ -91,12 +91,12 @@ class PubSub : public testing::Test
|
|||
}
|
||||
};
|
||||
|
||||
TEST_F(PubSub, pubSubNFast)
|
||||
TEST_F(Subscriptions, resubscribe)
|
||||
{
|
||||
ros::NodeHandle nh;
|
||||
|
||||
{
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", 0, &PubSub::messageCallback, (PubSub*)this);
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", 0, &Subscriptions::messageCallback, (Subscriptions*)this);
|
||||
ASSERT_TRUE(sub);
|
||||
ros::Time t1(ros::Time::now()+dt);
|
||||
|
||||
|
@ -116,7 +116,7 @@ TEST_F(PubSub, pubSubNFast)
|
|||
msg_i = -1;
|
||||
|
||||
{
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test2", 0, &PubSub::messageCallback, (PubSub*)this);
|
||||
ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test2", 0, &Subscriptions::messageCallback, (Subscriptions*)this);
|
||||
ASSERT_TRUE(sub);
|
||||
ros::Time t1(ros::Time::now()+dt);
|
||||
|
||||
|
|
Loading…
Reference in New Issue