Skip to content

Commit

Permalink
enforce unique node names
Browse files Browse the repository at this point in the history
  • Loading branch information
Karsten1987 committed Feb 6, 2019
1 parent 7338210 commit 9b0e9e8
Showing 1 changed file with 11 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,21 @@ using CountFunction = std::function<size_t(const std::string &)>;
class PublisherManager
{
public:
~PublisherManager()
{
publishers_.clear();
publisher_nodes_.clear();
}

template<class T>
void add_publisher(
const std::string & topic_name, std::shared_ptr<T> message, size_t expected_messages = 0)
{
static int counter = 0;
auto publisher_node = std::make_shared<rclcpp::Node>("publisher" + std::to_string(counter++));
auto node_name = std::string("publisher") + std::to_string(counter_++);
auto publisher_node = std::make_shared<rclcpp::Node>(node_name);
auto publisher = publisher_node->create_publisher<T>(topic_name);

publisher_nodes_.push_back(publisher_node);
publishers_.push_back([publisher, topic_name, message, expected_messages](
CountFunction count_stored_messages) {
if (expected_messages != 0) {
Expand Down Expand Up @@ -72,6 +79,8 @@ class PublisherManager
}

private:
int counter_ = 1;
std::vector<std::shared_ptr<rclcpp::Node>> publisher_nodes_;
std::vector<std::function<void(CountFunction)>> publishers_;
};

Expand Down

0 comments on commit 9b0e9e8

Please sign in to comment.