Skip to content

Commit

Permalink
Lint and docs
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Mar 30, 2023
1 parent 9695eaa commit e173e5a
Show file tree
Hide file tree
Showing 5 changed files with 108 additions and 39 deletions.
81 changes: 75 additions & 6 deletions rclcpp/include/rclcpp/executors/executor_entities_collection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,16 +32,37 @@ namespace rclcpp
namespace executors
{

/// Structure to represent a single entity's entry in a collection
template<typename EntityValueType>
struct CollectionEntry
{
/// Weak pointer to entity type
using EntityWeakPtr = typename EntityValueType::WeakPtr;
/// Shared pointer to entity type
using EntitySharedPtr = typename EntityValueType::SharedPtr;

/// The entity
EntityWeakPtr entity;

/// If relevant, the entity's corresponding callback_group
rclcpp::CallbackGroup::WeakPtr callback_group;
};

/// Update a collection based on another collection
/*
* Iterates update_from and update_to to see which entities have been added/removed between
* the two collections.
*
* For each new entry (in update_from, but not in update_to),
* add the entity and fire the on_added callback
* For each removed entry (in update_to, but not in update_from),
* remove the entity and fire the on_removed callback.
*
* \param[in] update_from The collection representing the next iteration's state
* \param[inout] update_to The collection representing the current iteration's state
* \param[in] on_added Callback fired when a new entity is detected
* \param[in] on_removed Callback fired when an entity is removed
*/
template<typename CollectionType>
void update_entities(
const CollectionType & update_from,
Expand Down Expand Up @@ -71,15 +92,31 @@ void update_entities(
}
}
}

/// A collection of entities, indexed by their corresponding handles
template<typename EntityKeyType, typename EntityValueType>
class EntityCollection
: public std::unordered_map<const EntityKeyType *, CollectionEntry<EntityValueType>>
{
public:
/// Key type of the map
using Key = const EntityKeyType *;

/// Weak pointer to entity type
using EntityWeakPtr = typename EntityValueType::WeakPtr;

/// Shared pointer to entity type
using EntitySharedPtr = typename EntityValueType::SharedPtr;

/// Update this collection based on the contents of another collection
/**
* Update the internal state of this collection, firing callbacks when entities have been
* added or removed.
*
* \param[in] other Collection to compare to
* \param[in] on_added Callback for when entities have been added
* \param[in] on_removed Callback for when entities have been removed
*/
void update(
const EntityCollection<EntityKeyType, EntityValueType> & other,
std::function<void(EntitySharedPtr)> on_added,
Expand All @@ -96,40 +133,72 @@ class EntityCollection
*/
struct ExecutorEntitiesCollection
{
/// Entity entries for timers
/// Collection type for timer entities
using TimerCollection = EntityCollection<rcl_timer_t, rclcpp::TimerBase>;

/// Entity entries for subscriptions
/// Collection type for subscription entities
using SubscriptionCollection = EntityCollection<rcl_subscription_t, rclcpp::SubscriptionBase>;

/// Entity entries for clients
/// Collection type for client entities
using ClientCollection = EntityCollection<rcl_client_t, rclcpp::ClientBase>;

/// Entity entries for services
/// Collection type for service entities
using ServiceCollection = EntityCollection<rcl_service_t, rclcpp::ServiceBase>;

/// Entity entries for waitables
/// Collection type for waitable entities
using WaitableCollection = EntityCollection<rclcpp::Waitable, rclcpp::Waitable>;

/// Entity entries for guard conditions
/// Collection type for guard condition entities
using GuardConditionCollection = EntityCollection<rcl_guard_condition_t, rclcpp::GuardCondition>;

/// Collection of timers currently in use by the executor.
TimerCollection timers;

/// Collection of subscriptions currently in use by the executor.
SubscriptionCollection subscriptions;

/// Collection of clients currently in use by the executor.
ClientCollection clients;

/// Collection of services currently in use by the executor.
ServiceCollection services;

/// Collection of guard conditions currently in use by the executor.
GuardConditionCollection guard_conditions;

/// Collection of waitables currently in use by the executor.
WaitableCollection waitables;

/// Check if the entities collection is empty
/**
* \return true if all member collections are empty, false otherwise
*/
bool empty() const;

/// Clear the entities collection
void clear();
};

/// Build an entities collection from callback groups
/**
* Iterates a list of callback groups and adds entities from each valid group
*
* \param[in] callback_groups List of callback groups to check for entities
* \param[inout] colletion Entities collection to populate with found entities
*/
void
build_entities_collection(
const std::vector<rclcpp::CallbackGroup::WeakPtr> & callback_groups,
ExecutorEntitiesCollection & collection);

/// Build a queue of executables ready to be executed
/**
* Iterates a list of entities and adds them to a queue if they are ready.
*
* \param[in] collection Collection of entities corresponding to the current wait set.
* \param[in] wait_result Result of rclcpp::WaitSet::wait corresponding to the collection.
* \return A queue of executables that have been marked ready by the waitset.
*/
std::deque<rclcpp::AnyExecutable>
ready_executables(
const ExecutorEntitiesCollection & collection,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define RCLCPP__EXECUTORS__EXECUTOR_ENTITIES_COLLECTOR_HPP_

#include <list>
#include <map>
#include <memory>
#include <set>
#include <vector>
Expand Down
18 changes: 8 additions & 10 deletions rclcpp/src/rclcpp/executors/executor_entities_collection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@ namespace executors
{
bool ExecutorEntitiesCollection::empty() const
{
return (subscriptions.empty() &&
timers.empty() &&
guard_conditions.empty() &&
clients.empty() &&
services.empty() &&
waitables.empty());
return subscriptions.empty() &&
timers.empty() &&
guard_conditions.empty() &&
clients.empty() &&
services.empty() &&
waitables.empty();
}

void ExecutorEntitiesCollection::clear()
Expand All @@ -52,8 +52,7 @@ build_entities_collection(
continue;
}

if (group_ptr->can_be_taken_from().load())
{
if (group_ptr->can_be_taken_from().load()) {
group_ptr->collect_all_ptrs(
[&collection, weak_group_ptr](const rclcpp::SubscriptionBase::SharedPtr & subscription) {
collection.subscriptions.insert(
Expand Down Expand Up @@ -102,7 +101,7 @@ void check_ready(
size_t size_of_waited_entities,
typename EntityCollectionType::Key * waited_entities,
std::function<bool(rclcpp::AnyExecutable &,
typename EntityCollectionType::EntitySharedPtr &)> fill_executable)
typename EntityCollectionType::EntitySharedPtr &)> fill_executable)
{
for (size_t ii = 0; ii < size_of_waited_entities; ++ii) {
if (waited_entities[ii]) {
Expand All @@ -122,7 +121,6 @@ void check_ready(
exec.callback_group = callback_group;
if (fill_executable(exec, entity)) {
executables.push_back(exec);
} else {
}
}
}
Expand Down
25 changes: 13 additions & 12 deletions rclcpp/src/rclcpp/executors/executor_entities_collector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,16 +33,20 @@ ExecutorEntitiesCollector::~ExecutorEntitiesCollector()
{
std::lock_guard<std::mutex> guard{mutex_};

for (auto weak_node_it = weak_nodes_.begin(); weak_node_it != weak_nodes_.end();) {
for (auto weak_node_it = weak_nodes_.begin(); weak_node_it != weak_nodes_.end(); ) {
weak_node_it = remove_weak_node(weak_node_it);
}

for (auto weak_group_it = automatically_added_groups_.begin(); weak_group_it != automatically_added_groups_.end(); ) {
weak_group_it= remove_weak_callback_group(weak_group_it, automatically_added_groups_);
for (auto weak_group_it = automatically_added_groups_.begin();
weak_group_it != automatically_added_groups_.end(); )
{
weak_group_it = remove_weak_callback_group(weak_group_it, automatically_added_groups_);
}

for (auto weak_group_it = manually_added_groups_.begin(); weak_group_it != manually_added_groups_.end(); ) {
weak_group_it= remove_weak_callback_group(weak_group_it, manually_added_groups_);
for (auto weak_group_it = manually_added_groups_.begin();
weak_group_it != manually_added_groups_.end(); )
{
weak_group_it = remove_weak_callback_group(weak_group_it, manually_added_groups_);
}
}

Expand Down Expand Up @@ -86,13 +90,12 @@ ExecutorEntitiesCollector::remove_node(
}

for (auto group_it = automatically_added_groups_.begin();
group_it != automatically_added_groups_.end();)
group_it != automatically_added_groups_.end(); )
{
auto group_ptr = group_it->lock();
if (node_ptr->callback_group_in_node(group_ptr)) {
group_it = remove_weak_callback_group(group_it, automatically_added_groups_);
}
else {
} else {
++group_it;
}
}
Expand Down Expand Up @@ -168,8 +171,7 @@ ExecutorEntitiesCollector::remove_weak_node(NodeCollection::iterator weak_node)
{
// Disassociate the guard condition from the executor notify waitable
auto guard_condition_it = weak_nodes_to_guard_conditions_.find(*weak_node);
if (guard_condition_it != weak_nodes_to_guard_conditions_.end())
{
if (guard_condition_it != weak_nodes_to_guard_conditions_.end()) {
this->notify_waitable_->remove_guard_condition(guard_condition_it->second);
weak_nodes_to_guard_conditions_.erase(guard_condition_it);
}
Expand All @@ -193,8 +195,7 @@ ExecutorEntitiesCollector::remove_weak_callback_group(
{
// Disassociate the guard condition from the executor notify waitable
auto guard_condition_it = weak_groups_to_guard_conditions_.find(*weak_group_it);
if (guard_condition_it != weak_groups_to_guard_conditions_.end())
{
if (guard_condition_it != weak_groups_to_guard_conditions_.end()) {
this->notify_waitable_->remove_guard_condition(guard_condition_it->second);
weak_groups_to_guard_conditions_.erase(guard_condition_it);
}
Expand Down
22 changes: 11 additions & 11 deletions rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,23 +103,23 @@ ExecutorNotifyWaitable::get_number_of_ready_guard_conditions()
{
std::lock_guard<std::mutex> lock(guard_condition_mutex_);

for (auto add_guard_condition: to_add_)
{
auto guard_it = std::find(notify_guard_conditions_.begin(),
notify_guard_conditions_.end(),
add_guard_condition);
for (auto add_guard_condition : to_add_) {
auto guard_it = std::find(
notify_guard_conditions_.begin(),
notify_guard_conditions_.end(),
add_guard_condition);
if (guard_it == notify_guard_conditions_.end()) {
notify_guard_conditions_.push_back(add_guard_condition);
}
}
to_add_.clear();

for (auto remove_guard_condition: to_remove_)
{
auto guard_it = std::find(notify_guard_conditions_.begin(),
notify_guard_conditions_.end(),
remove_guard_condition);
if (guard_it != notify_guard_conditions_.end()){
for (auto remove_guard_condition : to_remove_) {
auto guard_it = std::find(
notify_guard_conditions_.begin(),
notify_guard_conditions_.end(),
remove_guard_condition);
if (guard_it != notify_guard_conditions_.end()) {
notify_guard_conditions_.erase(guard_it);
}
}
Expand Down

0 comments on commit e173e5a

Please sign in to comment.