Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 2 additions & 3 deletions rclcpp/resource/logging.hpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -151,10 +151,9 @@ def get_rclcpp_suffix_from_features(features):
@[ end if]@
logger.get_name(), \
@[ if 'stream' not in feature_combination]@
rclcpp::get_c_string(RCLCPP_FIRST_ARG(__VA_ARGS__, "")), \
RCLCPP_ALL_BUT_FIRST_ARGS(__VA_ARGS__,"")); \
__VA_ARGS__); \
@[ else]@
"%s", rclcpp::get_c_string(ss.str())); \
"%s", ss.str().c_str()); \
@[ end if]@
} while (0)

Expand Down
4 changes: 3 additions & 1 deletion rclcpp/src/rclcpp/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,9 @@ get_node_logger(const rcl_node_t * node)
const char * logger_name = rcl_node_get_logger_name(node);
if (nullptr == logger_name) {
auto logger = rclcpp::get_logger("rclcpp");
RCLCPP_ERROR(logger, "failed to get logger name from node at address %p", node);
RCLCPP_ERROR(
logger, "failed to get logger name from node at address %p",
static_cast<void *>(const_cast<rcl_node_t *>(node)));
return logger;
}
return rclcpp::get_logger(logger_name);
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/signal_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ SignalHandler::deferred_signal_handler()
get_logger(),
"deferred_signal_handler(): "
"shutting down rclcpp::Context @ %p, because it had shutdown_on_sigint == true",
context_ptr.get());
static_cast<void *>(context_ptr.get()));
context_ptr->shutdown("signal handler");
}
}
Expand Down
42 changes: 22 additions & 20 deletions rclcpp/test/rclcpp/test_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,75 +80,77 @@ TEST(TestLogger, set_level) {
rcutils_logging_set_output_handler(rcutils_logging_console_output_handler);

// default
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
RCLCPP_DEBUG(logger, "message %s", "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
RCLCPP_INFO(logger, "message %s", "info");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message info", g_last_log_event.message);

// unset
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Unset);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
RCLCPP_DEBUG(logger, "message");
RCLCPP_DEBUG(logger, "message %s", "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
RCLCPP_INFO(logger, "message");
RCLCPP_INFO(logger, "message %s", "info");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message info", g_last_log_event.message);

// debug
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Debug);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
RCLCPP_DEBUG(logger, "message %s", "debug");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message debug", g_last_log_event.message);
RCLCPP_INFO(logger, std::string("message %s"), "info");
RCLCPP_INFO(logger, "message %s", "info");
EXPECT_EQ("message info", g_last_log_event.message);

// info
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Info);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
RCLCPP_DEBUG(logger, "message %s", "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
RCLCPP_INFO(logger, "message %s", "info");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message info", g_last_log_event.message);

// warn
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Warn);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
RCLCPP_DEBUG(logger, "message %s", "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
RCLCPP_INFO(logger, "message %s", "info");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_WARN(logger, std::string("message %s"), "warn");
RCLCPP_WARN(logger, "message %s", "warn");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message warn", g_last_log_event.message);

// error
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Error);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
RCLCPP_DEBUG(logger, "message %s", "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
RCLCPP_INFO(logger, "message %s", "info");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_WARN(logger, std::string("message %s"), "warn");
RCLCPP_WARN(logger, "message %s", "warn");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_ERROR(logger, std::string("message %s"), "error");
RCLCPP_ERROR(logger, "message %s", "error");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message error", g_last_log_event.message);

// fatal
g_last_log_event.console_output_handler_called = false;
logger.set_level(rclcpp::Logger::Level::Fatal);
RCLCPP_DEBUG(logger, std::string("message %s"), "debug");
RCLCPP_DEBUG(logger, "message %s", "debug");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_INFO(logger, std::string("message %s"), "info");
RCLCPP_INFO(logger, "message %s", "info");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_WARN(logger, std::string("message %s"), "warn");
RCLCPP_WARN(logger, "message %s", "warn");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_ERROR(logger, std::string("message %s"), "error");
RCLCPP_ERROR(logger, "message %s", "error");
EXPECT_FALSE(g_last_log_event.console_output_handler_called);
RCLCPP_FATAL(logger, std::string("message %s"), "fatal");
RCLCPP_FATAL(logger, "message %s", "fatal");
EXPECT_TRUE(g_last_log_event.console_output_handler_called);
EXPECT_EQ("message fatal", g_last_log_event.message);

Expand Down
20 changes: 0 additions & 20 deletions rclcpp/test/rclcpp/test_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,26 +110,6 @@ TEST_F(TestLoggingMacros, test_logging_named) {
EXPECT_EQ("message 3", g_last_log_event.message);
}

TEST_F(TestLoggingMacros, test_logging_string) {
for (std::string i : {"one", "two", "three"}) {
RCLCPP_DEBUG(g_logger, "message " + i);
}
EXPECT_EQ(3u, g_log_calls);
EXPECT_EQ("message three", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, "message " "four");
EXPECT_EQ("message four", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, std::string("message " "five"));
EXPECT_EQ("message five", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, std::string("message %s"), "six");
EXPECT_EQ("message six", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, "message seven");
EXPECT_EQ("message seven", g_last_log_event.message);
}

TEST_F(TestLoggingMacros, test_logging_stream) {
for (std::string i : {"one", "two", "three"}) {
RCLCPP_DEBUG_STREAM(g_logger, "message " << i);
Expand Down
5 changes: 4 additions & 1 deletion rclcpp_components/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,10 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual)
add_compile_options(
-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual
-Wformat=2 -Wconversion -Wshadow -Wsign-conversion -Wold-style-cast -Wcast-qual
)
endif()

find_package(ament_cmake_ros REQUIRED)
Expand Down
4 changes: 2 additions & 2 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ ComponentManager::OnLoadNode(
response->error_message = "Failed to find class with the requested plugin name.";
response->success = false;
} catch (const ComponentManagerException & ex) {
RCLCPP_ERROR(get_logger(), ex.what());
RCLCPP_ERROR(get_logger(), "%s", ex.what());
response->error_message = ex.what();
response->success = false;
}
Expand All @@ -244,7 +244,7 @@ ComponentManager::OnUnloadNode(
std::stringstream ss;
ss << "No node found with unique_id: " << request->unique_id;
response->error_message = ss.str();
RCLCPP_WARN(get_logger(), ss.str());
RCLCPP_WARN(get_logger(), "%s", ss.str().c_str());
} else {
if (auto exec = executor_.lock()) {
exec->remove_node(wrapper->second.get_node_base_interface());
Expand Down
4 changes: 2 additions & 2 deletions rclcpp_components/test/test_component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,8 @@ TEST_F(TestComponentManager, create_component_factory_invalid)
rclcpp_components::ComponentManagerException);

// Test valid library with invalid class
auto resources = manager->get_component_resources("rclcpp_components");
auto factory = manager->create_component_factory({"foo_class", resources[0].second});
auto component_resources = manager->get_component_resources("rclcpp_components");
auto factory = manager->create_component_factory({"foo_class", component_resources[0].second});
EXPECT_EQ(nullptr, factory);

// Test improperly formed resources file
Expand Down
86 changes: 43 additions & 43 deletions rclcpp_components/test/test_component_manager_api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,10 @@ TEST_F(TestComponentManager, components_api)
exec->add_node(manager);
exec->add_node(node);

auto client = node->create_client<composition_interfaces::srv::LoadNode>(
auto composition_client = node->create_client<composition_interfaces::srv::LoadNode>(
"/ComponentManager/_container/load_node");

if (!client->wait_for_service(20s)) {
if (!composition_client->wait_for_service(20s)) {
ASSERT_TRUE(false) << "service not available after waiting";
}

Expand All @@ -57,7 +57,7 @@ TEST_F(TestComponentManager, components_api)
request->package_name = "rclcpp_components";
request->plugin_name = "test_rclcpp_components::TestComponentFoo";

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, true);
Expand All @@ -71,7 +71,7 @@ TEST_F(TestComponentManager, components_api)
request->package_name = "rclcpp_components";
request->plugin_name = "test_rclcpp_components::TestComponentBar";

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, true);
Expand All @@ -87,7 +87,7 @@ TEST_F(TestComponentManager, components_api)
request->plugin_name = "test_rclcpp_components::TestComponentFoo";
request->node_name = "test_component_baz";

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, true);
Expand All @@ -104,7 +104,7 @@ TEST_F(TestComponentManager, components_api)
request->node_namespace = "/ns";
request->node_name = "test_component_bing";

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, true);
Expand All @@ -119,7 +119,7 @@ TEST_F(TestComponentManager, components_api)
request->package_name = "rclcpp_components";
request->plugin_name = "test_rclcpp_components::TestComponent";

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, false);
Expand All @@ -134,7 +134,7 @@ TEST_F(TestComponentManager, components_api)
request->package_name = "rclcpp_components_foo";
request->plugin_name = "test_rclcpp_components::TestComponentFoo";

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, false);
Expand All @@ -151,7 +151,7 @@ TEST_F(TestComponentManager, components_api)
request->node_name = "test_component_remap";
request->remap_rules.push_back("alice:=bob");

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, true);
Expand All @@ -170,7 +170,7 @@ TEST_F(TestComponentManager, components_api)
rclcpp::ParameterValue(true));
request->extra_arguments.push_back(use_intraprocess_comms.to_parameter_msg());

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, true);
Expand All @@ -191,7 +191,7 @@ TEST_F(TestComponentManager, components_api)
rclcpp::ParameterValue("hello"));
request->extra_arguments.push_back(use_intraprocess_comms.to_parameter_msg());

auto result = client->async_send_request(request);
auto result = composition_client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
EXPECT_EQ(result.get()->success, false);
Expand Down Expand Up @@ -226,23 +226,23 @@ TEST_F(TestComponentManager, components_api)
auto result = client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
auto node_names = result.get()->full_node_names;
auto unique_ids = result.get()->unique_ids;

EXPECT_EQ(node_names.size(), 6u);
EXPECT_EQ(node_names[0], "/test_component_foo");
EXPECT_EQ(node_names[1], "/test_component_bar");
EXPECT_EQ(node_names[2], "/test_component_baz");
EXPECT_EQ(node_names[3], "/ns/test_component_bing");
EXPECT_EQ(node_names[4], "/test_component_remap");
EXPECT_EQ(node_names[5], "/test_component_intra_process");
EXPECT_EQ(unique_ids.size(), 6u);
EXPECT_EQ(unique_ids[0], 1u);
EXPECT_EQ(unique_ids[1], 2u);
EXPECT_EQ(unique_ids[2], 3u);
EXPECT_EQ(unique_ids[3], 4u);
EXPECT_EQ(unique_ids[4], 5u);
EXPECT_EQ(unique_ids[5], 6u);
auto result_node_names = result.get()->full_node_names;
auto result_unique_ids = result.get()->unique_ids;

EXPECT_EQ(result_node_names.size(), 6u);
EXPECT_EQ(result_node_names[0], "/test_component_foo");
EXPECT_EQ(result_node_names[1], "/test_component_bar");
EXPECT_EQ(result_node_names[2], "/test_component_baz");
EXPECT_EQ(result_node_names[3], "/ns/test_component_bing");
EXPECT_EQ(result_node_names[4], "/test_component_remap");
EXPECT_EQ(result_node_names[5], "/test_component_intra_process");
EXPECT_EQ(result_unique_ids.size(), 6u);
EXPECT_EQ(result_unique_ids[0], 1u);
EXPECT_EQ(result_unique_ids[1], 2u);
EXPECT_EQ(result_unique_ids[2], 3u);
EXPECT_EQ(result_unique_ids[3], 4u);
EXPECT_EQ(result_unique_ids[4], 5u);
EXPECT_EQ(result_unique_ids[5], 6u);
}
}

Expand Down Expand Up @@ -290,21 +290,21 @@ TEST_F(TestComponentManager, components_api)
auto result = client->async_send_request(request);
auto ret = exec->spin_until_future_complete(result, 5s); // Wait for the result.
EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
auto node_names = result.get()->full_node_names;
auto unique_ids = result.get()->unique_ids;

EXPECT_EQ(node_names.size(), 5u);
EXPECT_EQ(node_names[0], "/test_component_bar");
EXPECT_EQ(node_names[1], "/test_component_baz");
EXPECT_EQ(node_names[2], "/ns/test_component_bing");
EXPECT_EQ(node_names[3], "/test_component_remap");
EXPECT_EQ(node_names[4], "/test_component_intra_process");
EXPECT_EQ(unique_ids.size(), 5u);
EXPECT_EQ(unique_ids[0], 2u);
EXPECT_EQ(unique_ids[1], 3u);
EXPECT_EQ(unique_ids[2], 4u);
EXPECT_EQ(unique_ids[3], 5u);
EXPECT_EQ(unique_ids[4], 6u);
auto result_node_names = result.get()->full_node_names;
auto result_unique_ids = result.get()->unique_ids;

EXPECT_EQ(result_node_names.size(), 5u);
EXPECT_EQ(result_node_names[0], "/test_component_bar");
EXPECT_EQ(result_node_names[1], "/test_component_baz");
EXPECT_EQ(result_node_names[2], "/ns/test_component_bing");
EXPECT_EQ(result_node_names[3], "/test_component_remap");
EXPECT_EQ(result_node_names[4], "/test_component_intra_process");
EXPECT_EQ(result_unique_ids.size(), 5u);
EXPECT_EQ(result_unique_ids[0], 2u);
EXPECT_EQ(result_unique_ids[1], 3u);
EXPECT_EQ(result_unique_ids[2], 4u);
EXPECT_EQ(result_unique_ids[3], 5u);
EXPECT_EQ(result_unique_ids[4], 6u);
}
}
}