Skip to content

Commit

Permalink
fix namespaces in test_roscpp
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Dec 28, 2012
1 parent 2d4520b commit 2ba3120
Show file tree
Hide file tree
Showing 42 changed files with 217 additions and 217 deletions.
4 changes: 2 additions & 2 deletions test/test_roscpp/perf/src/intra.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
*/

#include "perf_roscpp/intra.h"
#include "roscpp/ThroughputMessage.h"
#include "roscpp/LatencyMessage.h"
#include "test_roscpp/ThroughputMessage.h"
#include "test_roscpp/LatencyMessage.h"

#include <ros/ros.h>
#include <ros/callback_queue.h>
Expand Down
6 changes: 3 additions & 3 deletions test/test_roscpp/perf_serialization/pointcloud_serdes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "roscpp/PointCloud.h"
#include "test_roscpp/PointCloud.h"
#include <cstdlib>
#include <cstdio>

Expand All @@ -52,7 +52,7 @@ inline double toc()

int main(int, char **)
{
roscpp::PointCloud pc;
test_roscpp::PointCloud pc;

const int NUM_ITER = 100;
const int NUM_PTS = 1000000;
Expand All @@ -77,7 +77,7 @@ int main(int, char **)
tic();
for (int i = 0; i < NUM_ITER; i++)
{
roscpp::PointCloud pc2;
test_roscpp::PointCloud pc2;
deserializeMessage(m, pc2);
}
printf("avg deserization time %.6f sec\n", toc() / (double)NUM_ITER);
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/src/get_master_information.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include <stdlib.h>

#include "ros/ros.h"
#include "roscpp/TestEmpty.h"
#include "test_roscpp/TestEmpty.h"

TEST(masterInfo, getPublishedTopics)
{
Expand All @@ -68,7 +68,7 @@ TEST(masterInfo, getPublishedTopics)
for ( ; adv_it != adv_end; ++adv_it )
{
const std::string& topic = *adv_it;
pubs.push_back(nh.advertise<roscpp::TestEmpty>( topic, 0 ));
pubs.push_back(nh.advertise<test_roscpp::TestEmpty>( topic, 0 ));
}

ros::master::V_TopicInfo master_topics;
Expand Down
40 changes: 20 additions & 20 deletions test/test_roscpp/test/src/handles.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,13 @@

#include "ros/ros.h"
#include "ros/callback_queue.h"
#include <roscpp/TestArray.h>
#include <roscpp/TestStringString.h>
#include <test_roscpp/TestArray.h>
#include <test_roscpp/TestStringString.h>

#include <boost/thread.hpp>

using namespace ros;
using namespace roscpp;
using namespace test_roscpp;

TEST(RoscppHandles, nodeHandleConstructionDestruction)
{
Expand Down Expand Up @@ -122,7 +122,7 @@ TEST(RoscppHandles, nodeHandleParentWithRemappings)
}

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

void callback(const roscpp::TestArray::ConstPtr& msg)
void callback(const test_roscpp::TestArray::ConstPtr& msg)
{
++recv_count_;
}
Expand All @@ -156,8 +156,8 @@ TEST(RoscppHandles, subscriberValidity)
TEST(RoscppHandles, subscriberDestructionMultipleCallbacks)
{
ros::NodeHandle n;
ros::Publisher pub = n.advertise<roscpp::TestArray>("test", 0);
roscpp::TestArray msg;
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("test", 0);
test_roscpp::TestArray msg;

{
SubscribeHelper helper;
Expand Down Expand Up @@ -204,8 +204,8 @@ TEST(RoscppHandles, subscriberDestructionMultipleCallbacks)
TEST(RoscppHandles, subscriberSpinAfterSubscriberShutdown)
{
ros::NodeHandle n;
ros::Publisher pub = n.advertise<roscpp::TestArray>("test", 0);
roscpp::TestArray msg;
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("test", 0);
test_roscpp::TestArray msg;

int32_t last_fn_count = g_recv_count;

Expand All @@ -229,7 +229,7 @@ TEST(RoscppHandles, subscriberSpinAfterSubscriberShutdown)
TEST(RoscppHandles, subscriberGetNumPublishers)
{
ros::NodeHandle n;
ros::Publisher pub = n.advertise<roscpp::TestArray>("test", 0);
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("test", 0);

ros::Subscriber sub = n.subscribe("test", 0, subscriberCallback);

Expand Down Expand Up @@ -289,7 +289,7 @@ TEST(RoscppHandles, publisherCopy)
g_recv_count = 0;

{
ros::Publisher pub1 = n.advertise<roscpp::TestArray>("/test", 0);
ros::Publisher pub1 = n.advertise<test_roscpp::TestArray>("/test", 0);

{
ros::Publisher pub2 = pub1;
Expand Down Expand Up @@ -328,10 +328,10 @@ TEST(RoscppHandles, publisherMultiple)
g_recv_count = 0;

{
ros::Publisher pub1 = n.advertise<roscpp::TestArray>("/test", 0);
ros::Publisher pub1 = n.advertise<test_roscpp::TestArray>("/test", 0);

{
ros::Publisher pub2 = n.advertise<roscpp::TestArray>("/test", 0);
ros::Publisher pub2 = n.advertise<test_roscpp::TestArray>("/test", 0);

ASSERT_TRUE(pub1 != pub2);

Expand Down Expand Up @@ -444,7 +444,7 @@ TEST(RoscppHandles, trackedObjectWithAdvertiseSubscriberCallback)

boost::shared_ptr<char> tracked(new char);

ros::Publisher pub = n.advertise<roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback(), tracked);
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback(), tracked);

g_recv_count = 0;
g_sub_count = 0;
Expand Down Expand Up @@ -476,7 +476,7 @@ TEST(RoscppHandles, trackedObjectWithAdvertiseSubscriberCallback)
TEST(RoscppHandles, spinAfterHandleShutdownWithAdvertiseSubscriberCallback)
{
ros::NodeHandle n;
ros::Publisher pub = n.advertise<roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());

g_sub_count = 0;
ros::Subscriber sub = n.subscribe("/test", 0, subscriberCallback);
Expand All @@ -496,7 +496,7 @@ TEST(RoscppHandles, spinAfterHandleShutdownWithAdvertiseSubscriberCallback)
TEST(RoscppHandles, multiplePublishersWithSubscriberConnectCallback)
{
ros::NodeHandle n;
ros::Publisher pub = n.advertise<roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());

g_sub_count = 0;
ros::Subscriber sub = n.subscribe("/test", 0, subscriberCallback);
Expand All @@ -510,7 +510,7 @@ TEST(RoscppHandles, multiplePublishersWithSubscriberConnectCallback)
ASSERT_EQ(g_sub_count, 1);
g_sub_count = 0;

ros::Publisher pub2 = n.advertise<roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());
ros::Publisher pub2 = n.advertise<test_roscpp::TestArray>("/test", 0, connectedCallback, SubscriberStatusCallback());
ros::spinOnce();

ASSERT_EQ(g_sub_count, 1);
Expand Down Expand Up @@ -556,9 +556,9 @@ TEST(RoscppHandles, trackedObjectWithSubscriptionCallback)
g_recv_count = 0;
ros::Subscriber sub = n.subscribe("/test", 0, &SubscribeHelper::callback, tracked);

ros::Publisher pub = n.advertise<roscpp::TestArray>("/test", 0);
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0);

roscpp::TestArray msg;
test_roscpp::TestArray msg;
Duration d(0.01);
while (tracked->recv_count_ == 0)
{
Expand Down Expand Up @@ -614,7 +614,7 @@ TEST(RoscppHandles, nodeHandleShutdown)
ros::NodeHandle n;

ros::Subscriber sub = n.subscribe("/test", 0, subscriberCallback);
ros::Publisher pub = n.advertise<roscpp::TestArray>("/test", 0);
ros::Publisher pub = n.advertise<test_roscpp::TestArray>("/test", 0);
ros::ServiceServer srv = n.advertiseService("/test_srv", serviceCallback);

n.shutdown();
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/src/incrementing_sequence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@
#include <stdlib.h>

#include "ros/ros.h"
#include <roscpp/TestWithHeader.h>
#include <test_roscpp/TestWithHeader.h>

using namespace ros;
using namespace roscpp;
using namespace test_roscpp;

uint32_t g_recv_count = 0;
uint32_t g_sequence = 0;
Expand Down
12 changes: 6 additions & 6 deletions test/test_roscpp/test/src/inspection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@

#include <ros/ros.h>
#include <ros/names.h>
#include <roscpp/TestArray.h>
#include <roscpp/TestStringInt.h>
#include <roscpp/TestEmpty.h>
#include <test_roscpp/TestArray.h>
#include <test_roscpp/TestStringInt.h>
#include <test_roscpp/TestEmpty.h>

const char* g_node_name = "inspection_test";

Expand All @@ -61,9 +61,9 @@ TEST(Inspection, getAdvertisedTopics)
ASSERT_EQ(topics[0], "/rosout");

{
ros::Publisher pub1 = nh.advertise<roscpp::TestArray>("topic",1);
ros::Publisher pub2 = nh.advertise<roscpp::TestArray>("ns/topic",1);
ros::Publisher pub3 = nh.advertise<roscpp::TestArray>("/global/topic",1);
ros::Publisher pub1 = nh.advertise<test_roscpp::TestArray>("topic",1);
ros::Publisher pub2 = nh.advertise<test_roscpp::TestArray>("ns/topic",1);
ros::Publisher pub3 = nh.advertise<test_roscpp::TestArray>("/global/topic",1);

topics.clear();
ros::this_node::getAdvertisedTopics(topics);
Expand Down
4 changes: 2 additions & 2 deletions test/test_roscpp/test/src/latching_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@
#include <stdlib.h>

#include "ros/ros.h"
#include <roscpp/TestArray.h>
#include <test_roscpp/TestArray.h>

using namespace ros;
using namespace roscpp;
using namespace test_roscpp;

std::string g_node_name = "test_latching_publisher";

Expand Down
6 changes: 3 additions & 3 deletions test/test_roscpp/test/src/loads_of_publishers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,11 @@
#include <ros/ros.h>
#include <ros/callback_queue.h>

#include "roscpp/TestArray.h"
#include "test_roscpp/TestArray.h"

uint32_t g_pub_count = 0;

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

}
Expand All @@ -59,7 +59,7 @@ TEST(LoadsOfPublishers, waitForAll)

struct Helper
{
void callback(const roscpp::TestArrayConstPtr& msg)
void callback(const test_roscpp::TestArrayConstPtr& msg)
{
alive[(*msg->__connection_header)["callerid"]] = true;
}
Expand Down
6 changes: 3 additions & 3 deletions test/test_roscpp/test/src/multiple_init_fini.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,12 @@
#include <stdlib.h>

#include "ros/ros.h"
#include <roscpp/TestArray.h>
#include <test_roscpp/TestArray.h>

int g_argc;
char** g_argv;

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

Expand All @@ -66,7 +66,7 @@ TEST(roscpp, multipleInitAndFini)
ros::Subscriber sub = nh.subscribe("test", 1, callback);
ASSERT_TRUE(sub);

ros::Publisher pub = nh.advertise<roscpp::TestArray>( "test2", 1 );
ros::Publisher pub = nh.advertise<test_roscpp::TestArray>( "test2", 1 );
ASSERT_TRUE(pub);

ros::shutdown();
Expand Down
22 changes: 11 additions & 11 deletions test/test_roscpp/test/src/multiple_subscriptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
#include <time.h>
#include <stdlib.h>
#include "ros/ros.h"
#include <roscpp/TestArray.h>
#include <roscpp/TestEmpty.h>
#include <test_roscpp/TestArray.h>
#include <test_roscpp/TestEmpty.h>

int g_argc;
char** g_argv;
Expand All @@ -53,11 +53,11 @@ class Subscriptions : public testing::Test
bool test_ready;
int n_test;

void cb0(const roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[0] = true; }
void cb1(const roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[1] = true; }
void cb2(const roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[2] = true; }
void cb3(const roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[3] = true; }
void cb_verify(const roscpp::TestArrayConstPtr&)
void cb0(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[0] = true; }
void cb1(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[1] = true; }
void cb2(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[2] = true; }
void cb3(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[3] = true; }
void cb_verify(const test_roscpp::TestArrayConstPtr&)
{
if (!test_ready)
return;
Expand All @@ -69,7 +69,7 @@ class Subscriptions : public testing::Test
(should_have_it[3] ? got_it[3] : true)));
*/
}
void cb_reset(const roscpp::TestArrayConstPtr&)
void cb_reset(const test_roscpp::TestArrayConstPtr&)
{
got_it[0] = got_it[1] = got_it[2] = got_it[3] = false; test_ready = true;
}
Expand All @@ -78,7 +78,7 @@ class Subscriptions : public testing::Test
bool sub(int cb_num)
{
ROS_INFO("Subscribing %d", cb_num);
boost::function<void(const roscpp::TestArrayConstPtr&)> funcs[4] =
boost::function<void(const test_roscpp::TestArrayConstPtr&)> funcs[4] =
{
boost::bind(&Subscriptions::cb0, this, _1),
boost::bind(&Subscriptions::cb1, this, _1),
Expand Down Expand Up @@ -153,12 +153,12 @@ TEST_F(Subscriptions, multipleSubscriptions)
SUCCEED();
}

void callback1(const roscpp::TestArrayConstPtr&)
void callback1(const test_roscpp::TestArrayConstPtr&)
{

}

void callback2(const roscpp::TestEmptyConstPtr&)
void callback2(const test_roscpp::TestEmptyConstPtr&)
{

}
Expand Down
Loading

0 comments on commit 2ba3120

Please sign in to comment.