Skip to content

Commit

Permalink
Make some changes for newer versions of uncrustify. (ros2#1578)
Browse files Browse the repository at this point in the history
Uncrustify 0.78 is the new version in Ubuntu 24.04.
It has some small differences in indentation compared
to Uncrustify 0.72, which is what is in Ubuntu 22.04.

In this PR, we make the changes to match what Uncrustify
0.78 wants.  In most cases, I think this is a "better"
indentation.

We also add in strategic use of "*INDENT-OFF*" comments,
which instructs Uncrustify to not indent this particular
section of code.  That is so that this will still pass
the linters on Uncrustify 0.72 while Rolling is still
on that version.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Feb 29, 2024
1 parent 1564687 commit 86fc3e4
Show file tree
Hide file tree
Showing 11 changed files with 130 additions and 95 deletions.
28 changes: 16 additions & 12 deletions rosbag2_compression/src/rosbag2_compression/logging.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,40 +22,44 @@

#define ROSBAG2_COMPRESSION_PACKAGE_NAME "rosbag2_compression"

// *INDENT-OFF*

#define ROSBAG2_COMPRESSION_LOG_INFO(...) \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_LOG_INFO_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_COMPRESSION_LOG_ERROR(...) \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_LOG_ERROR_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_COMPRESSION_LOG_WARN(...) \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_LOG_WARN_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_COMPRESSION_LOG_DEBUG(...) \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_LOG_DEBUG_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_COMPRESSION_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

// *INDENT-ON*

#endif // ROSBAG2_COMPRESSION__LOGGING_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -118,13 +118,15 @@ void SequentialCompressionWriter::compression_thread_fn()
std::string file;
{
std::unique_lock<std::mutex> lock(compressor_queue_mutex_);
// *INDENT-OFF*
compressor_condition_.wait(
lock,
[&] {
return !compression_is_running_ ||
!compressor_message_queue_.empty() ||
!compressor_file_queue_.empty();
!compressor_message_queue_.empty() ||
!compressor_file_queue_.empty();
});
// *INDENT-ON*

if (!compressor_message_queue_.empty()) {
message = compressor_message_queue_.front();
Expand Down Expand Up @@ -388,12 +390,14 @@ void SequentialCompressionWriter::write(
if (compression_options_.compression_queue_size == 0u &&
compressor_message_queue_.size() > compression_options_.compression_threads)
{
// *INDENT-OFF*
compressor_condition_.wait(
lock,
[&] {
return !compression_is_running_ ||
compressor_message_queue_.size() <= compression_options_.compression_threads;
compressor_message_queue_.size() <= compression_options_.compression_threads;
});
// *INDENT-ON*
}

compressor_message_queue_.push(message);
Expand Down
28 changes: 16 additions & 12 deletions rosbag2_compression_zstd/src/rosbag2_compression_zstd/logging.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,40 +22,44 @@

#define ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME "rosbag2_compression_zstd"

// *INDENT-OFF*

#define ROSBAG2_COMPRESSION_ZSTD_LOG_INFO(...) \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_ZSTD_LOG_INFO_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_COMPRESSION_ZSTD_LOG_ERROR(...) \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_ZSTD_LOG_ERROR_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_COMPRESSION_ZSTD_LOG_WARN(...) \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_ZSTD_LOG_WARN_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_COMPRESSION_ZSTD_LOG_DEBUG(...) \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_COMPRESSION_ZSTD_LOG_DEBUG_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_COMPRESSION_ZSTD_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

// *INDENT-ON*

#endif // ROSBAG2_COMPRESSION_ZSTD__LOGGING_HPP_
28 changes: 16 additions & 12 deletions rosbag2_cpp/include/rosbag2_cpp/logging.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,40 +22,44 @@

#define ROSBAG2_CPP_PACKAGE_NAME "rosbag2_cpp"

// *INDENT-OFF*

#define ROSBAG2_CPP_LOG_INFO(...) \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_CPP_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_CPP_LOG_INFO_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_CPP_LOG_ERROR(...) \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_CPP_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_CPP_LOG_ERROR_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_CPP_LOG_WARN(...) \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_CPP_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_CPP_LOG_WARN_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_CPP_LOG_DEBUG(...) \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_CPP_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_CPP_LOG_DEBUG_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_CPP_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

// *INDENT-ON*

#endif // ROSBAG2_CPP__LOGGING_HPP_
11 changes: 5 additions & 6 deletions rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -369,12 +369,11 @@ TEST_F(
fake_storage_size_ = 0;
size_t written_messages = 0;

ON_CALL(
*storage_,
write(An<const std::vector<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>> &>())).
WillByDefault(
[this, &written_messages]
(const std::vector<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>> & msgs)
using VectorSharedBagMessages =
std::vector<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>>;

ON_CALL(*storage_, write(An<const VectorSharedBagMessages &>())).WillByDefault(
[this, &written_messages](const VectorSharedBagMessages & msgs)
{
written_messages += msgs.size();
fake_storage_size_.fetch_add(static_cast<uint32_t>(msgs.size()));
Expand Down
28 changes: 16 additions & 12 deletions rosbag2_storage/include/rosbag2_storage/logging.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,40 +22,44 @@

#define ROSBAG2_STORAGE_PACKAGE_NAME "rosbag2_storage"

// *INDENT-OFF*

#define ROSBAG2_STORAGE_LOG_INFO(...) \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_LOG_INFO_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_STORAGE_LOG_ERROR(...) \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_LOG_ERROR_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_STORAGE_LOG_WARN(...) \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_LOG_WARN_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_STORAGE_LOG_DEBUG(...) \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_LOG_DEBUG_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_STORAGE_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

// *INDENT-ON*

#endif // ROSBAG2_STORAGE__LOGGING_HPP_
36 changes: 20 additions & 16 deletions rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/logging.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,44 +22,48 @@

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME "rosbag2_storage"

// *INDENT-OFF*

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_INFO(...) \
RCUTILS_LOG_INFO_NAMED(ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_INFO_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_INFO_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_ERROR(...) \
RCUTILS_LOG_ERROR_NAMED(ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_ERROR_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_ERROR_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_WARN(...) \
RCUTILS_LOG_WARN_NAMED(ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_WARN_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_WARN_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_DEBUG(...) \
RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, __VA_ARGS__)

#define ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_DEBUG_STREAM(args) do { \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
std::stringstream __ss; \
__ss << args; \
RCUTILS_LOG_DEBUG_NAMED( \
ROSBAG2_STORAGE_DEFAULT_PLUGINS_PACKAGE_NAME, "%s", __ss.str().c_str()); \
} while (0)

// *INDENT-ON*

#endif // ROSBAG2_STORAGE_SQLITE3__LOGGING_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ class ClientManager : public rclcpp::Node
enable_service_event_contents_(service_event_contents),
enable_client_event_contents_(client_event_contents)
{
// *INDENT-OFF*
auto do_nothing_srv_callback =
[this](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<typename ServiceT::Request> request,
Expand All @@ -53,6 +54,7 @@ class ClientManager : public rclcpp::Node
(void)request;
(void)response;
};
// *INDENT-ON*

service_ = create_service<ServiceT>(service_name_, do_nothing_srv_callback);

Expand Down
10 changes: 6 additions & 4 deletions rosbag2_tests/test/rosbag2_tests/test_reindexer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,11 +149,13 @@ TEST_P(ReindexTestFixture, test_multiple_files) {
target_metadata.topics_with_message_count.begin(),
target_metadata.topics_with_message_count.end(),
[&gen_topic](rosbag2_storage::TopicInformation & t) {
// *INDENT-OFF*
return (t.topic_metadata.name == gen_topic.topic_metadata.name) &&
(t.message_count == gen_topic.message_count) &&
(t.topic_metadata.offered_qos_profiles ==
gen_topic.topic_metadata.offered_qos_profiles) &&
(t.topic_metadata.type == gen_topic.topic_metadata.type);
(t.message_count == gen_topic.message_count) &&
(t.topic_metadata.offered_qos_profiles ==
gen_topic.topic_metadata.offered_qos_profiles) &&
(t.topic_metadata.type == gen_topic.topic_metadata.type);
// *INDENT-ON*
}
) != target_metadata.topics_with_message_count.end()
);
Expand Down
Loading

0 comments on commit 86fc3e4

Please sign in to comment.