Skip to content

Commit

Permalink
Update for rclcpp namespace removals (#255)
Browse files Browse the repository at this point in the history
* Remove subscription:: namespace

* Remove client:: namespace

* Remove service:: namespace

* Remove parameter_client:: namespace

* Remove parameter_service:: namespace

* Remove timer:: namespace

* Remove node:: namespace

* Remove event:: namespace

* Remove utilities:: namespace
  • Loading branch information
dhood committed Dec 5, 2017
1 parent 772325a commit acd4aec
Show file tree
Hide file tree
Showing 21 changed files with 60 additions and 60 deletions.
4 changes: 2 additions & 2 deletions test_communication/test/test_publisher_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void publish(
}

template<typename T>
rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
rclcpp::SubscriptionBase::SharedPtr subscribe(
rclcpp::Node::SharedPtr node,
const std::string & message_type,
std::vector<typename T::SharedPtr> & expected_messages,
Expand Down Expand Up @@ -115,7 +115,7 @@ int main(int argc, char ** argv)
std::string message = argv[1];
auto node = rclcpp::Node::make_shared(std::string("test_publisher_subscriber_") + message);

rclcpp::subscription::SubscriptionBase::SharedPtr subscriber;
rclcpp::SubscriptionBase::SharedPtr subscriber;
std::vector<bool> received_messages; // collect flags about received messages

auto messages_empty = get_messages_empty();
Expand Down
4 changes: 2 additions & 2 deletions test_communication/test/test_replier.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "test_msgs/service_fixtures.hpp"

template<typename T>
typename rclcpp::service::Service<T>::SharedPtr reply(
typename rclcpp::Service<T>::SharedPtr reply(
rclcpp::Node::SharedPtr node,
const std::string & service_type,
const std::vector<
Expand Down Expand Up @@ -74,7 +74,7 @@ int main(int argc, char ** argv)

auto services_empty = get_services_empty();
auto services_primitives = get_services_primitives();
rclcpp::service::ServiceBase::SharedPtr server;
rclcpp::ServiceBase::SharedPtr server;

if (service == "Empty") {
server = reply<test_msgs::srv::Empty>(
Expand Down
4 changes: 2 additions & 2 deletions test_communication/test/test_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@


template<typename T>
rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(
rclcpp::SubscriptionBase::SharedPtr subscribe(
rclcpp::Node::SharedPtr node,
const std::string & message_type,
std::vector<typename T::SharedPtr> & expected_messages,
Expand Down Expand Up @@ -96,7 +96,7 @@ int main(int argc, char ** argv)
auto messages_static_array_nested = get_messages_static_array_nested();
auto messages_builtins = get_messages_builtins();

rclcpp::subscription::SubscriptionBase::SharedPtr subscriber;
rclcpp::SubscriptionBase::SharedPtr subscriber;
std::vector<bool> received_messages; // collect flags about received messages
if (message == "Empty") {
subscriber = subscribe<test_msgs::msg::Empty>(
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/include/test_rclcpp/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ void wait_for_subscriber(
}
};
while (!predicate() && time_slept < duration_cast<microseconds>(timeout)) {
rclcpp::event::Event::SharedPtr graph_event = node->get_graph_event();
rclcpp::Event::SharedPtr graph_event = node->get_graph_event();
node->wait_for_graph_change(graph_event, sleep_period);
time_slept = duration_cast<std::chrono::microseconds>(steady_clock::now() - start);
}
Expand Down
8 changes: 4 additions & 4 deletions test_rclcpp/test/parameter_fixtures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
const double test_epsilon = 1e-6;

void set_test_parameters(
std::shared_ptr<rclcpp::parameter_client::SyncParametersClient> parameters_client)
std::shared_ptr<rclcpp::SyncParametersClient> parameters_client)
{
printf("Setting parameters\n");
// Set several differnet types of parameters.
Expand All @@ -52,7 +52,7 @@ void set_test_parameters(

void verify_set_parameters_async(
std::shared_ptr<rclcpp::Node> node,
std::shared_ptr<rclcpp::parameter_client::AsyncParametersClient> parameters_client)
std::shared_ptr<rclcpp::AsyncParametersClient> parameters_client)
{
printf("Setting parameters\n");
// Set several differnet types of parameters.
Expand All @@ -75,7 +75,7 @@ void verify_set_parameters_async(
}

void verify_test_parameters(
std::shared_ptr<rclcpp::parameter_client::SyncParametersClient> parameters_client)
std::shared_ptr<rclcpp::SyncParametersClient> parameters_client)
{
printf("Listing parameters with recursive depth\n");
// Test recursive depth (=0)
Expand Down Expand Up @@ -180,7 +180,7 @@ void verify_test_parameters(

void verify_get_parameters_async(
std::shared_ptr<rclcpp::Node> node,
std::shared_ptr<rclcpp::parameter_client::AsyncParametersClient> parameters_client)
std::shared_ptr<rclcpp::AsyncParametersClient> parameters_client)
{
printf("Listing parameters with recursive depth\n");
// Test recursive depth (=0)
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_client_scope_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
using namespace std::chrono_literals;

TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test) {
auto node = rclcpp::node::Node::make_shared("client_scope_regression_test");
auto node = rclcpp::Node::make_shared("client_scope_regression_test");

// Extra scope so the first client will be deleted afterwards
{
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_client_scope_consistency_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ using namespace std::chrono_literals;
// This test is concerned with the consistency of the two clients' behavior, not necessarily whether
// or not they are successful.
TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_regression_test) {
auto node = rclcpp::node::Node::make_shared("client_scope_consistency_regression_test");
auto node = rclcpp::Node::make_shared("client_scope_consistency_regression_test");

// Replicate the settings that caused https://github.com/ros2/system_tests/issues/153
rmw_qos_profile_t rmw_qos_profile =
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_client_scope_consistency_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);

auto node = rclcpp::node::Node::make_shared("client_scope_consistency_regression_test_server");
auto node = rclcpp::Node::make_shared("client_scope_consistency_regression_test_server");

// Replicate the settings that caused https://github.com/ros2/system_tests/issues/153
rmw_qos_profile_t rmw_qos_profile =
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_client_scope_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);

auto node = rclcpp::node::Node::make_shared("client_scope_server");
auto node = rclcpp::Node::make_shared("client_scope_server");

auto service = node->create_service<test_rclcpp::srv::AddTwoInts>(
"client_scope", handle_add_two_ints);
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_client_wait_for_service_shutdown.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ using namespace std::chrono_literals;
// rclcpp::shutdown() should wake up wait_for_service, even without spin.
TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) {
rclcpp::init(0, nullptr);
auto node = rclcpp::node::Node::make_shared("wait_for_service_shutdown");
auto node = rclcpp::Node::make_shared("wait_for_service_shutdown");

auto client = node->create_client<test_rclcpp::srv::AddTwoInts>("wait_for_service_shutdown");

Expand Down
28 changes: 14 additions & 14 deletions test_rclcpp/test/test_local_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) {
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous");
// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
Expand All @@ -79,8 +79,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) {
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) {
auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated");
// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
Expand All @@ -94,8 +94,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_rep
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) {
auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous"));
// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
Expand All @@ -110,7 +110,7 @@ class ParametersAsyncNode : public rclcpp::Node
: Node("test_local_parameters_async_with_callback")
{
parameters_client_ =
std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(this);
std::make_shared<rclcpp::AsyncParametersClient>(this);
}

void queue_set_parameter_request(rclcpp::executors::SingleThreadedExecutor & executor)
Expand Down Expand Up @@ -146,7 +146,7 @@ class ParametersAsyncNode : public rclcpp::Node
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_callback) {
auto node = std::make_shared<ParametersAsyncNode>();
// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
if (!node->parameters_client_->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
Expand All @@ -160,8 +160,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_call
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
Expand Down Expand Up @@ -265,8 +265,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) {
TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) {
auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
Expand Down Expand Up @@ -332,8 +332,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant

auto node = rclcpp::Node::make_shared("test_parameters_local_helpers");
// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}
Expand Down
6 changes: 3 additions & 3 deletions test_rclcpp/test/test_multiple_service_calls.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_ca
request2->b = 0;

bool second_result_received = false;
using AddTwoIntsSharedFuture = rclcpp::client::Client<test_rclcpp::srv::AddTwoInts>::SharedFuture;
using AddTwoIntsSharedFuture = rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedFuture;

auto first_response_received_callback =
[&client, &request2, &second_result_received](AddTwoIntsSharedFuture first_future) {
Expand Down Expand Up @@ -140,9 +140,9 @@ TEST(CLASSNAME(test_multiple_service_calls, RMW_IMPLEMENTATION), multiple_client
"test_multiple_clients", handle_add_two_ints);

using ClientRequestPair = std::pair<
rclcpp::client::Client<test_rclcpp::srv::AddTwoInts>::SharedPtr,
rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedPtr,
test_rclcpp::srv::AddTwoInts::Request::SharedPtr>;
using SharedFuture = rclcpp::client::Client<test_rclcpp::srv::AddTwoInts>::SharedFuture;
using SharedFuture = rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedFuture;

std::vector<ClientRequestPair> client_request_pairs;
for (uint32_t i = 0; i < n; ++i) {
Expand Down
18 changes: 9 additions & 9 deletions test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process)
// wait for delivery to occur.
const std::chrono::milliseconds sleep_per_loop(10);
while (subscriptions_size != counter.load()) {
rclcpp::utilities::sleep_for(sleep_per_loop);
rclcpp::sleep_for(sleep_per_loop);
executor.spin_some();
}
EXPECT_EQ(subscriptions_size, counter.load());
Expand All @@ -115,7 +115,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process)
std::mutex publish_mutex;
auto publish_callback = [
msg, &pub, &executor, &counter, &expected_count, &sleep_per_loop, &publish_mutex](
rclcpp::timer::TimerBase & timer) -> void
rclcpp::TimerBase & timer) -> void
{
std::lock_guard<std::mutex> lock(publish_mutex);
++msg->data;
Expand Down Expand Up @@ -168,9 +168,9 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients)
"multi_consumer_clients", callback, qos_profile, callback_group);

using ClientRequestPair = std::pair<
rclcpp::client::Client<test_rclcpp::srv::AddTwoInts>::SharedPtr,
rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedPtr,
test_rclcpp::srv::AddTwoInts::Request::SharedPtr>;
using SharedFuture = rclcpp::client::Client<test_rclcpp::srv::AddTwoInts>::SharedFuture;
using SharedFuture = rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedFuture;


std::vector<ClientRequestPair> client_request_pairs;
Expand All @@ -186,7 +186,7 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients)
int client_request_pairs_size = static_cast<int>(client_request_pairs.size());

executor.add_node(node);
rclcpp::utilities::sleep_for(5ms);
rclcpp::sleep_for(5ms);

executor.spin_some();
// No callbacks should have fired
Expand Down Expand Up @@ -251,7 +251,7 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients)
static inline void multi_access_publisher(bool intra_process)
{
// Try to access the same publisher simultaneously
auto context = std::make_shared<rclcpp::context::Context>();
auto context = std::make_shared<rclcpp::Context>();
std::string node_topic_name = "multi_access_publisher";
if (intra_process) {
node_topic_name += "_intra_process";
Expand Down Expand Up @@ -289,13 +289,13 @@ static inline void multi_access_publisher(bool intra_process)

auto timer_callback =
[&executor, &pub, &msg, &timer_counter, &subscription_counter, &num_messages](
rclcpp::timer::TimerBase & timer)
rclcpp::TimerBase & timer)
{
if (timer_counter.load() >= num_messages) {
timer.cancel();
// Wait for pending subscription callbacks to trigger.
while (subscription_counter < timer_counter) {
rclcpp::utilities::sleep_for(1ms);
rclcpp::sleep_for(1ms);
}
executor.cancel();
return;
Expand All @@ -304,7 +304,7 @@ static inline void multi_access_publisher(bool intra_process)
printf("Publishing message %u\n", timer_counter.load());
pub->publish(msg);
};
std::vector<rclcpp::timer::TimerBase::SharedPtr> timers;
std::vector<rclcpp::TimerBase::SharedPtr> timers;
// timers will fire simultaneously in each thread
for (uint32_t i = 0; i < std::min<size_t>(executor.get_number_of_threads(), 16); ++i) {
timers.push_back(node->create_wall_timer(std::chrono::milliseconds(1), timer_callback));
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_parameters_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ int main(int argc, char ** argv)
auto node = rclcpp::Node::make_shared(std::string("test_parameters_server"));

// TODO(esteve): Make the parameter service automatically start with the node.
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
auto parameter_service = std::make_shared<rclcpp::ParameterService>(node);

rclcpp::spin(node);

Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_remote_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_async) {

auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_async"));

auto parameters_client = std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(node,
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node,
test_server_name);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
Expand All @@ -56,7 +56,7 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_sync) {

auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_sync"));

auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node,
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node,
test_server_name);
if (!parameters_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_services_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) {

auto result = client->async_send_request(
request,
[](rclcpp::client::Client<test_rclcpp::srv::AddTwoInts>::SharedFutureWithRequest future) {
[](rclcpp::Client<test_rclcpp::srv::AddTwoInts>::SharedFutureWithRequest future) {
EXPECT_EQ(4, future.get().first->a);
EXPECT_EQ(5, future.get().first->b);
EXPECT_EQ(9, future.get().second->sum);
Expand Down
Loading

0 comments on commit acd4aec

Please sign in to comment.