Skip to content

Commit

Permalink
changed from atomic to const
Browse files Browse the repository at this point in the history
Signed-off-by: Pedro Pena <[email protected]>
  • Loading branch information
peterpena committed Aug 4, 2020
1 parent c68a82c commit 7e6c958
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 10 deletions.
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class CallbackGroup
RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup)

RCLCPP_PUBLIC
explicit CallbackGroup(CallbackGroupType group_type, bool allow_executor_to_add = true);
explicit CallbackGroup(CallbackGroupType group_type, const bool allow_executor_to_add = true);

template<typename Function>
rclcpp::SubscriptionBase::SharedPtr
Expand Down Expand Up @@ -129,8 +129,8 @@ class CallbackGroup
* add a callback group
*/
RCLCPP_PUBLIC
std::atomic_bool &
allow_executor_to_add() {return allow_executor_to_add_;}
const bool &
allow_executor_to_add() const {return allow_executor_to_add_;}

protected:
RCLCPP_DISABLE_COPY(CallbackGroup)
Expand Down Expand Up @@ -173,7 +173,7 @@ class CallbackGroup
std::vector<rclcpp::ClientBase::WeakPtr> client_ptrs_;
std::vector<rclcpp::Waitable::WeakPtr> waitable_ptrs_;
std::atomic_bool can_be_taken_from_;
std::atomic_bool allow_executor_to_add_;
const bool allow_executor_to_add_;

private:
template<typename TypeT, typename Function>
Expand Down
7 changes: 4 additions & 3 deletions rclcpp/src/rclcpp/callback_group.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,11 @@
using rclcpp::CallbackGroup;
using rclcpp::CallbackGroupType;

CallbackGroup::CallbackGroup(CallbackGroupType group_type, bool allow_executor_to_add)
CallbackGroup::CallbackGroup(CallbackGroupType group_type, const bool allow_executor_to_add)
: type_(group_type), associated_with_executor_(false),
can_be_taken_from_(true)
{allow_executor_to_add_.store(allow_executor_to_add);}
can_be_taken_from_(true),
allow_executor_to_add_(allow_executor_to_add)
{}


std::atomic_bool &
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ Executor::add_allowable_unassigned_callback_groups()
[this, node](rclcpp::CallbackGroup::WeakPtr group_ptr)
{
auto shared_group_ptr = group_ptr.lock();
if (shared_group_ptr && shared_group_ptr->allow_executor_to_add().load() &&
if (shared_group_ptr && shared_group_ptr->allow_executor_to_add() &&
!shared_group_ptr->get_associated_with_executor_atomic().load())
{
add_callback_group(shared_group_ptr, node);
Expand Down Expand Up @@ -234,7 +234,7 @@ Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_pt
for (auto & weak_group : node_ptr->get_callback_groups()) {
auto group_ptr = weak_group.lock();
if (group_ptr != nullptr && !group_ptr->get_associated_with_executor_atomic().load() &&
group_ptr->allow_executor_to_add().load())
group_ptr->allow_executor_to_add())
{
add_callback_group(group_ptr, node_ptr, notify);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,6 @@ StaticExecutorEntitiesCollector::add_callback_group(
{
rclcpp::CallbackGroup::WeakPtr weak_group_ptr = group_ptr;
auto insert_info = weak_groups_to_nodes_.insert(std::make_pair(weak_group_ptr, node_ptr));
group_ptr->allow_executor_to_add().store(false);
bool was_inserted = insert_info.second;
if (!was_inserted) {
throw std::runtime_error("Callback group was already added to executor.");
Expand Down

0 comments on commit 7e6c958

Please sign in to comment.