Skip to content

Commit

Permalink
remove mutex lock from constructors.
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Nov 16, 2021
1 parent 1644625 commit 3a3d395
Showing 1 changed file with 14 additions and 20 deletions.
34 changes: 14 additions & 20 deletions rclcpp_lifecycle/src/state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,22 +44,19 @@ State::State(
throw std::runtime_error("Lifecycle State cannot have an empty label.");
}

{
std::lock_guard<std::recursive_mutex> lock(state_handle_mutex_);
state_handle_ = static_cast<rcl_lifecycle_state_t *>(
allocator_.allocate(sizeof(rcl_lifecycle_state_t), allocator_.state));
if (!state_handle_) {
throw std::runtime_error("failed to allocate memory for rcl_lifecycle_state_t");
}
// zero initialize
state_handle_->id = 0;
state_handle_->label = nullptr;

auto ret = rcl_lifecycle_state_init(state_handle_, id, label.c_str(), &allocator_);
if (ret != RCL_RET_OK) {
reset();
rclcpp::exceptions::throw_from_rcl_error(ret);
}
state_handle_ = static_cast<rcl_lifecycle_state_t *>(
allocator_.allocate(sizeof(rcl_lifecycle_state_t), allocator_.state));
if (!state_handle_) {
throw std::runtime_error("failed to allocate memory for rcl_lifecycle_state_t");
}
// zero initialize
state_handle_->id = 0;
state_handle_->label = nullptr;

auto ret = rcl_lifecycle_state_init(state_handle_, id, label.c_str(), &allocator_);
if (ret != RCL_RET_OK) {
reset();
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}

Expand All @@ -74,10 +71,7 @@ State::State(
throw std::runtime_error("rcl_lifecycle_state_handle is null");
}

{
std::lock_guard<std::recursive_mutex> lock(state_handle_mutex_);
state_handle_ = const_cast<rcl_lifecycle_state_t *>(rcl_lifecycle_state_handle);
}
state_handle_ = const_cast<rcl_lifecycle_state_t *>(rcl_lifecycle_state_handle);
}

State::State(const State & rhs)
Expand Down

0 comments on commit 3a3d395

Please sign in to comment.