Skip to content

Commit

Permalink
reconsider mutex lock scope.
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 Oct 26, 2021
1 parent de7ec73 commit 453bfa8
Show file tree
Hide file tree
Showing 2 changed files with 39 additions and 54 deletions.
60 changes: 23 additions & 37 deletions rclcpp_lifecycle/src/lifecycle_node_interface_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,20 +114,18 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
}

if (enable_communication_interface) {
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
{ // change_state
auto cb = std::bind(
&LifecycleNodeInterfaceImpl::on_change_state, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);
rclcpp::AnyServiceCallback<ChangeStateSrv> any_cb;
any_cb.set(std::move(cb));

{
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
srv_change_state_ = std::make_shared<rclcpp::Service<ChangeStateSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_change_state,
any_cb);
}
srv_change_state_ = std::make_shared<rclcpp::Service<ChangeStateSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_change_state,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_change_state_),
nullptr);
Expand All @@ -140,13 +138,10 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
rclcpp::AnyServiceCallback<GetStateSrv> any_cb;
any_cb.set(std::move(cb));

{
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
srv_get_state_ = std::make_shared<rclcpp::Service<GetStateSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_state,
any_cb);
}
srv_get_state_ = std::make_shared<rclcpp::Service<GetStateSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_state,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_get_state_),
nullptr);
Expand All @@ -159,13 +154,10 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
rclcpp::AnyServiceCallback<GetAvailableStatesSrv> any_cb;
any_cb.set(std::move(cb));

{
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
srv_get_available_states_ = std::make_shared<rclcpp::Service<GetAvailableStatesSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_available_states,
any_cb);
}
srv_get_available_states_ = std::make_shared<rclcpp::Service<GetAvailableStatesSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_available_states,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_get_available_states_),
nullptr);
Expand All @@ -178,14 +170,11 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
rclcpp::AnyServiceCallback<GetAvailableTransitionsSrv> any_cb;
any_cb.set(std::move(cb));

{
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
srv_get_available_transitions_ =
std::make_shared<rclcpp::Service<GetAvailableTransitionsSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_available_transitions,
any_cb);
}
srv_get_available_transitions_ =
std::make_shared<rclcpp::Service<GetAvailableTransitionsSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_available_transitions,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_get_available_transitions_),
nullptr);
Expand All @@ -198,14 +187,11 @@ class LifecycleNode::LifecycleNodeInterfaceImpl
rclcpp::AnyServiceCallback<GetAvailableTransitionsSrv> any_cb;
any_cb.set(std::move(cb));

{
std::lock_guard<std::recursive_mutex> lock(state_machine_mutex_);
srv_get_transition_graph_ =
std::make_shared<rclcpp::Service<GetAvailableTransitionsSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_transition_graph,
any_cb);
}
srv_get_transition_graph_ =
std::make_shared<rclcpp::Service<GetAvailableTransitionsSrv>>(
node_base_interface_->get_shared_rcl_node_handle(),
&state_machine_.com_interface.srv_get_transition_graph,
any_cb);
node_services_interface_->add_service(
std::dynamic_pointer_cast<rclcpp::ServiceBase>(srv_get_transition_graph_),
nullptr);
Expand Down
33 changes: 16 additions & 17 deletions rclcpp_lifecycle/src/state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,9 @@ State::operator=(const State & rhs)
return *this;
}

// hold the lock until state_handle_ is reconstructed
std::lock_guard<std::recursive_mutex> lock(state_handle_mutex_);

// reset all currently used resources
reset();

Expand All @@ -108,29 +111,25 @@ State::operator=(const State & rhs)

// we don't own the handle, so we can return straight ahead
if (!owns_rcl_state_handle_) {
std::lock_guard<std::recursive_mutex> lock(state_handle_mutex_);
state_handle_ = rhs.state_handle_;
return *this;
}

// we own the handle, so we have to deep-copy the rhs object
{
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;
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_, rhs.id(), rhs.label().c_str(), &allocator_);
if (ret != RCL_RET_OK) {
reset();
throw std::runtime_error("failed to duplicate label for rcl_lifecycle_state_t");
}
auto ret = rcl_lifecycle_state_init(
state_handle_, rhs.id(), rhs.label().c_str(), &allocator_);
if (ret != RCL_RET_OK) {
reset();
throw std::runtime_error("failed to duplicate label for rcl_lifecycle_state_t");
}

return *this;
Expand Down

0 comments on commit 453bfa8

Please sign in to comment.