Skip to content

Commit

Permalink
Fixes pointed out by the clang analyzer. (#2339)
Browse files Browse the repository at this point in the history
1. Remove the default Logger copy constructor without copy
assignment (rule of three -> rule of zero).
2. Remove an unnecessary capture in a lambda.
3. Mark a variable unused.
4. Mark a method as override.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Oct 23, 2023
1 parent 5ffc963 commit c366e53
Show file tree
Hide file tree
Showing 4 changed files with 3 additions and 5 deletions.
3 changes: 0 additions & 3 deletions rclcpp/include/rclcpp/logger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,9 +126,6 @@ class Logger
std::shared_ptr<std::pair<std::string, std::string>> logger_sublogger_pairname_ = nullptr;

public:
RCLCPP_PUBLIC
Logger(const Logger &) = default;

/// Get the name of this logger.
/**
* \return the full name of the logger including any prefixes, or
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -462,7 +462,7 @@ template<Context::ShutdownType shutdown_type>
std::vector<rclcpp::Context::ShutdownCallback>
Context::get_shutdown_callback() const
{
const auto get_callback_vector = [this](auto & mutex, auto & callback_set) {
const auto get_callback_vector = [](auto & mutex, auto & callback_set) {
const std::lock_guard<std::mutex> lock(mutex);
std::vector<rclcpp::Context::ShutdownCallback> callbacks;
for (auto & callback : callback_set) {
Expand Down
1 change: 1 addition & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -644,6 +644,7 @@ TYPED_TEST(TestExecutors, testRaceConditionAddNode)
break;
}
total += k * (i + 42);
(void)total;
}
});
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_intra_process_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,7 +289,7 @@ class SubscriptionIntraProcessBuffer : public SubscriptionIntraProcessBase
}

bool
use_take_shared_method() const
use_take_shared_method() const override
{
return take_shared_method;
}
Expand Down

0 comments on commit c366e53

Please sign in to comment.