Skip to content

Commit ddb3e8f

Browse files
committed
updated to PIMutex
Signed-off-by: Martin Mayer <[email protected]>
1 parent 3fb012e commit ddb3e8f

23 files changed

+76
-57
lines changed

rclcpp/include/rclcpp/callback_group.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,7 @@
1616
#define RCLCPP__CALLBACK_GROUP_HPP_
1717

1818
#include <atomic>
19-
#include <functional>
20-
#include <memory>
21-
#include <mutex>
19+
#include <string>
2220
#include <vector>
2321

2422
#include "rclcpp/client.hpp"
@@ -30,6 +28,7 @@
3028
#include "rclcpp/timer.hpp"
3129
#include "rclcpp/visibility_control.hpp"
3230
#include "rclcpp/waitable.hpp"
31+
#include "rcpputils/mutex.hpp"
3332

3433
namespace rclcpp
3534
{
@@ -221,7 +220,7 @@ class CallbackGroup
221220

222221
CallbackGroupType type_;
223222
// Mutex to protect the subsequent vectors of pointers.
224-
mutable std::mutex mutex_;
223+
mutable rcpputils::PIMutex mutex_;
225224
std::atomic_bool associated_with_executor_;
226225
std::vector<rclcpp::SubscriptionBase::WeakPtr> subscription_ptrs_;
227226
std::vector<rclcpp::TimerBase::WeakPtr> timer_ptrs_;

rclcpp/include/rclcpp/client.hpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,6 @@
1919
#include <future>
2020
#include <unordered_map>
2121
#include <memory>
22-
#include <mutex>
2322
#include <optional> // NOLINT, cpplint doesn't think this is a cpp std header
2423
#include <sstream>
2524
#include <string>
@@ -45,6 +44,8 @@
4544
#include "rclcpp/utilities.hpp"
4645
#include "rclcpp/visibility_control.hpp"
4746

47+
#include "rcpputils/mutex.hpp"
48+
4849
#include "rmw/error_handling.h"
4950
#include "rmw/impl/cpp/demangle.hpp"
5051
#include "rmw/rmw.h"
@@ -364,7 +365,7 @@ class ClientBase
364365

365366
std::atomic<bool> in_use_by_wait_set_{false};
366367

367-
std::recursive_mutex callback_mutex_;
368+
rcpputils::RecursivePIMutex callback_mutex_;
368369
std::function<void(size_t)> on_new_response_callback_{nullptr};
369370
};
370371

@@ -830,7 +831,7 @@ class Client : public ClientBase
830831
std::chrono::time_point<std::chrono::system_clock>,
831832
CallbackInfoVariant>>
832833
pending_requests_;
833-
std::mutex pending_requests_mutex_;
834+
rcpputils::PIMutex pending_requests_mutex_;
834835
};
835836

836837
} // namespace rclcpp

rclcpp/include/rclcpp/clock.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717

1818
#include <functional>
1919
#include <memory>
20-
#include <mutex>
2120

2221
#include "rclcpp/contexts/default_context.hpp"
2322
#include "rclcpp/macros.hpp"
@@ -27,6 +26,7 @@
2726
#include "rcl/time.h"
2827
#include "rcutils/time.h"
2928
#include "rcutils/types/rcutils_ret.h"
29+
#include "rcpputils/mutex.hpp"
3030

3131
namespace rclcpp
3232
{
@@ -204,7 +204,7 @@ class Clock
204204

205205
/// Get the clock's mutex
206206
RCLCPP_PUBLIC
207-
std::mutex &
207+
rcpputils::PIMutex &
208208
get_clock_mutex() noexcept;
209209

210210
// Add a callback to invoke if the jump threshold is exceeded.

rclcpp/include/rclcpp/context.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
#include <condition_variable>
1919
#include <functional>
2020
#include <memory>
21-
#include <mutex>
2221
#include <string>
2322
#include <typeindex>
2423
#include <typeinfo>
@@ -33,6 +32,7 @@
3332
#include "rclcpp/init_options.hpp"
3433
#include "rclcpp/macros.hpp"
3534
#include "rclcpp/visibility_control.hpp"
35+
#include "rcpputils/mutex.hpp"
3636

3737
namespace rclcpp
3838
{
@@ -377,15 +377,15 @@ class Context : public std::enable_shared_from_this<Context>
377377
std::recursive_mutex sub_contexts_mutex_;
378378

379379
std::unordered_set<std::shared_ptr<OnShutdownCallback>> on_shutdown_callbacks_;
380-
mutable std::mutex on_shutdown_callbacks_mutex_;
380+
mutable rcpputils::PIMutex on_shutdown_callbacks_mutex_;
381381

382382
std::unordered_set<std::shared_ptr<PreShutdownCallback>> pre_shutdown_callbacks_;
383-
mutable std::mutex pre_shutdown_callbacks_mutex_;
383+
mutable rcpputils::PIMutex pre_shutdown_callbacks_mutex_;
384384

385385
/// Condition variable for timed sleep (see sleep_for).
386386
std::condition_variable interrupt_condition_variable_;
387387
/// Mutex for protecting the global condition variable.
388-
std::mutex interrupt_mutex_;
388+
rcpputils::PIMutex interrupt_mutex_;
389389

390390
/// Keep shared ownership of global vector of weak contexts
391391
std::shared_ptr<WeakContextsWrapper> weak_contexts_;

rclcpp/include/rclcpp/executor.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,13 +23,13 @@
2323
#include <list>
2424
#include <map>
2525
#include <memory>
26-
#include <mutex>
2726
#include <string>
2827
#include <vector>
2928

3029
#include "rcl/guard_condition.h"
3130
#include "rcl/wait.h"
3231
#include "rcpputils/scope_exit.hpp"
32+
#include "rcpputils/mutex.hpp"
3333

3434
#include "rclcpp/context.hpp"
3535
#include "rclcpp/contexts/default_context.hpp"
@@ -545,7 +545,7 @@ class Executor
545545
rcl_wait_set_t wait_set_ = rcl_get_zero_initialized_wait_set();
546546

547547
// Mutex to protect the subsequent memory_strategy_.
548-
mutable std::mutex mutex_;
548+
mutable rcpputils::PIMutex mutex_;
549549

550550
/// The memory strategy: an interface for handling user-defined memory allocation strategies.
551551
memory_strategy::MemoryStrategy::SharedPtr

rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717

1818
#include <chrono>
1919
#include <memory>
20-
#include <mutex>
2120
#include <set>
2221
#include <thread>
2322
#include <unordered_map>
@@ -27,6 +26,8 @@
2726
#include "rclcpp/memory_strategies.hpp"
2827
#include "rclcpp/visibility_control.hpp"
2928

29+
#include "rcpputils/mutex.hpp"
30+
3031
namespace rclcpp
3132
{
3233
namespace executors
@@ -81,7 +82,7 @@ class MultiThreadedExecutor : public rclcpp::Executor
8182
private:
8283
RCLCPP_DISABLE_COPY(MultiThreadedExecutor)
8384

84-
std::mutex wait_mutex_;
85+
rcpputils::PIMutex wait_mutex_;
8586
size_t number_of_threads_;
8687
bool yield_before_execute_;
8788
std::chrono::nanoseconds next_exec_timeout_;

rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,8 @@
3030
#include "rclcpp/visibility_control.hpp"
3131
#include "rclcpp/waitable.hpp"
3232

33+
#include "rcpputils/mutex.hpp"
34+
3335
namespace rclcpp
3436
{
3537
namespace executors
@@ -338,7 +340,7 @@ class StaticExecutorEntitiesCollector final
338340
std::list<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> weak_nodes_;
339341

340342
// Mutex to protect vector of new nodes.
341-
std::mutex new_nodes_mutex_;
343+
rcpputils::PIMutex new_nodes_mutex_;
342344
std::vector<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> new_nodes_;
343345

344346
/// Wait set for managing entities that the rmw layer waits on.

rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@
1515
#ifndef RCLCPP__EXPERIMENTAL__BUFFERS__RING_BUFFER_IMPLEMENTATION_HPP_
1616
#define RCLCPP__EXPERIMENTAL__BUFFERS__RING_BUFFER_IMPLEMENTATION_HPP_
1717

18-
#include <mutex>
1918
#include <stdexcept>
2019
#include <utility>
2120
#include <vector>
@@ -26,6 +25,8 @@
2625
#include "rclcpp/macros.hpp"
2726
#include "rclcpp/visibility_control.hpp"
2827

28+
#include "rcpputils/mutex.hpp"
29+
2930
namespace rclcpp
3031
{
3132
namespace experimental
@@ -181,7 +182,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
181182
size_t read_index_;
182183
size_t size_;
183184

184-
mutable std::mutex mutex_;
185+
mutable rcpputils::PIMutex mutex_;
185186
};
186187

187188
} // namespace buffers

rclcpp/include/rclcpp/graph_listener.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717

1818
#include <atomic>
1919
#include <memory>
20-
#include <mutex>
2120
#include <thread>
2221
#include <vector>
2322

@@ -28,6 +27,7 @@
2827
#include "rclcpp/macros.hpp"
2928
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
3029
#include "rclcpp/visibility_control.hpp"
30+
#include "rcpputils/mutex.hpp"
3131

3232
namespace rclcpp
3333
{
@@ -187,10 +187,10 @@ class GraphListener : public std::enable_shared_from_this<GraphListener>
187187
std::thread listener_thread_;
188188
bool is_started_;
189189
std::atomic_bool is_shutdown_;
190-
mutable std::mutex shutdown_mutex_;
190+
mutable rcpputils::PIMutex shutdown_mutex_;
191191

192-
mutable std::mutex node_graph_interfaces_barrier_mutex_;
193-
mutable std::mutex node_graph_interfaces_mutex_;
192+
mutable rcpputils::PIMutex node_graph_interfaces_barrier_mutex_;
193+
mutable rcpputils::PIMutex node_graph_interfaces_mutex_;
194194
std::vector<rclcpp::node_interfaces::NodeGraphInterface *> node_graph_interfaces_;
195195

196196
rclcpp::GuardCondition interrupt_guard_condition_;

rclcpp/include/rclcpp/init_options.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,10 +16,10 @@
1616
#define RCLCPP__INIT_OPTIONS_HPP_
1717

1818
#include <memory>
19-
#include <mutex>
2019

2120
#include "rcl/init_options.h"
2221
#include "rclcpp/visibility_control.hpp"
22+
#include "rcpputils/mutex.hpp"
2323

2424
namespace rclcpp
2525
{
@@ -104,7 +104,7 @@ class InitOptions
104104
void
105105
finalize_init_options_impl();
106106

107-
mutable std::mutex init_options_mutex_;
107+
mutable rcpputils::PIMutex init_options_mutex_;
108108
std::unique_ptr<rcl_init_options_t> init_options_;
109109
bool initialize_logging_{true};
110110
};

0 commit comments

Comments
 (0)