Skip to content

Commit

Permalink
fix uses of newly deprecated functions
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Mar 27, 2024
1 parent 7d9b19b commit d4906d6
Show file tree
Hide file tree
Showing 36 changed files with 215 additions and 135 deletions.
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/event_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,12 +117,12 @@ class EventHandlerBase : public Waitable
/// Add the Waitable to a wait set.
RCLCPP_PUBLIC
void
add_to_wait_set(rcl_wait_set_t * wait_set) override;
add_to_wait_set(rcl_wait_set_t & wait_set) override;

/// Check if the Waitable is ready.
RCLCPP_PUBLIC
bool
is_ready(rcl_wait_set_t * wait_set) override;
is_ready(const rcl_wait_set_t & wait_set) override;

/// Set a callback to be called when each new event instance occurs.
/**
Expand Down Expand Up @@ -294,7 +294,7 @@ class EventHandler : public EventHandlerBase

/// Execute any entities of the Waitable that are ready.
void
execute(std::shared_ptr<void> & data) override
execute(const std::shared_ptr<void> & data) override
{
if (!data) {
throw std::runtime_error("'data' is empty");
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
*/
RCLCPP_PUBLIC
void
add_to_wait_set(rcl_wait_set_t * wait_set) override;
add_to_wait_set(rcl_wait_set_t & wait_set) override;

/// Check conditions against the wait set
/**
Expand All @@ -69,7 +69,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
*/
RCLCPP_PUBLIC
bool
is_ready(rcl_wait_set_t * wait_set) override;
is_ready(const rcl_wait_set_t & wait_set) override;

/// Perform work associated with the waitable.
/**
Expand All @@ -78,7 +78,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
*/
RCLCPP_PUBLIC
void
execute(std::shared_ptr<void> & data) override;
execute(const std::shared_ptr<void> & data) override;

/// Retrieve data to be used in the next execute call.
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class StaticExecutorEntitiesCollector final
/// Execute the waitable.
RCLCPP_PUBLIC
void
execute(std::shared_ptr<void> & data) override;
execute(const std::shared_ptr<void> & data) override;

/// Take the data so that it can be consumed with `execute`.
/**
Expand All @@ -103,7 +103,7 @@ class StaticExecutorEntitiesCollector final
*/
RCLCPP_PUBLIC
void
add_to_wait_set(rcl_wait_set_t * wait_set) override;
add_to_wait_set(rcl_wait_set_t & wait_set) override;

RCLCPP_PUBLIC
size_t
Expand Down Expand Up @@ -196,7 +196,7 @@ class StaticExecutorEntitiesCollector final
*/
RCLCPP_PUBLIC
bool
is_ready(rcl_wait_set_t * wait_set) override;
is_ready(const rcl_wait_set_t & wait_set) override;

/// Return number of timers
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,23 +132,22 @@ class SubscriptionIntraProcess
);
}

void execute(std::shared_ptr<void> & data) override
void execute(const std::shared_ptr<void> & data) override
{
execute_impl<SubscribedType>(data);
}

protected:
template<typename T>
typename std::enable_if<std::is_same<T, rcl_serialized_message_t>::value, void>::type
execute_impl(std::shared_ptr<void> & data)
execute_impl(const std::shared_ptr<void> &)
{
(void)data;
throw std::runtime_error("Subscription intra-process can't handle serialized messages");
}

template<class T>
typename std::enable_if<!std::is_same<T, rcl_serialized_message_t>::value, void>::type
execute_impl(std::shared_ptr<void> & data)
execute_impl(const std::shared_ptr<void> & data)
{
if (!data) {
return;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable

RCLCPP_PUBLIC
void
add_to_wait_set(rcl_wait_set_t * wait_set) override;
add_to_wait_set(rcl_wait_set_t & wait_set) override;

RCLCPP_PUBLIC
virtual
Expand All @@ -72,7 +72,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
is_durability_transient_local() const;

bool
is_ready(rcl_wait_set_t * wait_set) override = 0;
is_ready(const rcl_wait_set_t & wait_set) override = 0;

std::shared_ptr<void>
take_data() override = 0;
Expand All @@ -85,7 +85,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
}

void
execute(std::shared_ptr<void> & data) override = 0;
execute(const std::shared_ptr<void> & data) override = 0;

virtual
bool
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class SubscriptionIntraProcessBuffer : public SubscriptionROSMsgIntraProcessBuff
}

bool
is_ready(rcl_wait_set_t * wait_set) override
is_ready(const rcl_wait_set_t & wait_set) override
{
(void) wait_set;
return buffer_->has_data();
Expand Down
6 changes: 4 additions & 2 deletions rclcpp/include/rclcpp/guard_condition.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class GuardCondition
*/
RCLCPP_PUBLIC
void
add_to_wait_set(rcl_wait_set_t * wait_set);
add_to_wait_set(rcl_wait_set_t & wait_set);

/// Set a callback to be called whenever the guard condition is triggered.
/**
Expand Down Expand Up @@ -128,7 +128,9 @@ class GuardCondition
std::recursive_mutex reentrant_mutex_;
std::function<void(size_t)> on_trigger_callback_{nullptr};
size_t unread_count_{0};
rcl_wait_set_t * wait_set_{nullptr};
// the type of wait_set_ is actually rcl_wait_set_t *, but it's never
// dereferenced, only compared to, so make it void * to avoid accidental use
void * wait_set_{nullptr};
};

} // namespace rclcpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
}
}
for (size_t i = 0; i < waitable_handles_.size(); ++i) {
if (waitable_handles_[i]->is_ready(wait_set)) {
if (waitable_handles_[i]->is_ready(*wait_set)) {
waitable_triggered_handles_.emplace_back(std::move(waitable_handles_[i]));
}
}
Expand Down Expand Up @@ -235,7 +235,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
}

for (const std::shared_ptr<Waitable> & waitable : waitable_handles_) {
waitable->add_to_wait_set(wait_set);
waitable->add_to_wait_set(*wait_set);
}
return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ class StoragePolicyCommon
continue;
}
rclcpp::Waitable & waitable = *waitable_ptr_pair.second;
waitable.add_to_wait_set(&rcl_wait_set_);
waitable.add_to_wait_set(rcl_wait_set_);
}
}

Expand Down
33 changes: 27 additions & 6 deletions rclcpp/include/rclcpp/waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,10 @@ class Waitable
size_t
get_number_of_ready_guard_conditions();

#ifdef __GNUC__
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
#endif
/// Deprecated.
/**
* \sa add_to_wait_set(rcl_wait_set_t &)
Expand All @@ -109,7 +113,10 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
add_to_wait_set(rcl_wait_set_t * wait_set) = 0;
add_to_wait_set(rcl_wait_set_t * wait_set);
#ifdef __GNUC__
#pragma GCC diagnostic pop
#endif

/// Add the Waitable to a wait set.
/**
Expand All @@ -119,8 +126,12 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
add_to_wait_set(rcl_wait_set_t & wait_set) = 0;
add_to_wait_set(rcl_wait_set_t & wait_set);

#ifdef __GNUC__
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
#endif
/// Deprecated.
/**
* \sa is_ready(const rcl_wait_set_t &)
Expand All @@ -129,7 +140,10 @@ class Waitable
RCLCPP_PUBLIC
virtual
bool
is_ready(rcl_wait_set_t * wait_set) = 0;
is_ready(rcl_wait_set_t * wait_set);
#ifdef __GNUC__
#pragma GCC diagnostic pop
#endif

/// Check if the Waitable is ready.
/**
Expand All @@ -144,7 +158,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
bool
is_ready(const rcl_wait_set_t & wait_set) = 0;
is_ready(const rcl_wait_set_t & wait_set);

/// Take the data so that it can be consumed with `execute`.
/**
Expand Down Expand Up @@ -198,6 +212,10 @@ class Waitable
std::shared_ptr<void>
take_data_by_entity_id(size_t id);

#ifdef __GNUC__
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
#endif
/// Deprecated.
/**
* \sa execute(const std::shared_ptr<void> &)
Expand All @@ -206,7 +224,10 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
execute(std::shared_ptr<void> & data) = 0;
execute(std::shared_ptr<void> & data);
#ifdef __GNUC__
#pragma GCC diagnostic pop
#endif

/// Execute data that is passed in.
/**
Expand All @@ -233,7 +254,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
execute(const std::shared_ptr<void> & data) = 0;
execute(const std::shared_ptr<void> & data);

/// Exchange the "in use by wait set" state for this timer.
/**
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/src/rclcpp/event_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,19 +56,19 @@ EventHandlerBase::get_number_of_ready_events()

/// Add the Waitable to a wait set.
void
EventHandlerBase::add_to_wait_set(rcl_wait_set_t * wait_set)
EventHandlerBase::add_to_wait_set(rcl_wait_set_t & wait_set)
{
rcl_ret_t ret = rcl_wait_set_add_event(wait_set, &event_handle_, &wait_set_event_index_);
rcl_ret_t ret = rcl_wait_set_add_event(&wait_set, &event_handle_, &wait_set_event_index_);
if (RCL_RET_OK != ret) {
exceptions::throw_from_rcl_error(ret, "Couldn't add event to wait set");
}
}

/// Check if the Waitable is ready.
bool
EventHandlerBase::is_ready(rcl_wait_set_t * wait_set)
EventHandlerBase::is_ready(const rcl_wait_set_t & wait_set)
{
return wait_set->events[wait_set_event_index_] == &event_handle_;
return wait_set.events[wait_set_event_index_] == &event_handle_;
}

void
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -560,7 +560,8 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
execute_client(any_exec.client);
}
if (any_exec.waitable) {
any_exec.waitable->execute(any_exec.data);
const std::shared_ptr<void> & const_data = any_exec.data;
any_exec.waitable->execute(const_data);
}
// Reset the callback_group, regardless of type
any_exec.callback_group->can_be_taken_from().store(true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ ready_executables(
if (!waitable) {
continue;
}
if (!waitable->is_ready(&rcl_wait_set)) {
if (!waitable->is_ready(rcl_wait_set)) {
continue;
}
auto group_info = group_cache(entry.callback_group);
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ ExecutorNotifyWaitable & ExecutorNotifyWaitable::operator=(const ExecutorNotifyW
}

void
ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t & wait_set)
{
std::lock_guard<std::mutex> lock(guard_condition_mutex_);

Expand All @@ -53,7 +53,7 @@ ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
auto rcl_guard_condition = &guard_condition->get_rcl_guard_condition();

rcl_ret_t ret = rcl_wait_set_add_guard_condition(
wait_set,
&wait_set,
rcl_guard_condition, NULL);

if (RCL_RET_OK != ret) {
Expand All @@ -65,13 +65,13 @@ ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
}

bool
ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
ExecutorNotifyWaitable::is_ready(const rcl_wait_set_t & wait_set)
{
std::lock_guard<std::mutex> lock(guard_condition_mutex_);

bool any_ready = false;
for (size_t ii = 0; ii < wait_set->size_of_guard_conditions; ++ii) {
auto rcl_guard_condition = wait_set->guard_conditions[ii];
for (size_t ii = 0; ii < wait_set.size_of_guard_conditions; ++ii) {
auto rcl_guard_condition = wait_set.guard_conditions[ii];

if (nullptr == rcl_guard_condition) {
continue;
Expand All @@ -87,7 +87,7 @@ ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
}

void
ExecutorNotifyWaitable::execute(std::shared_ptr<void> & data)
ExecutorNotifyWaitable::execute(const std::shared_ptr<void> & data)
{
(void) data;
this->execute_callback_();
Expand Down
Loading

0 comments on commit d4906d6

Please sign in to comment.