Skip to content

Commit

Permalink
Fix isLatched behaviour, add tests.
Browse files Browse the repository at this point in the history
  • Loading branch information
mikepurvis committed Jul 11, 2020
1 parent 0676095 commit 8eec231
Show file tree
Hide file tree
Showing 3 changed files with 55 additions and 3 deletions.
2 changes: 1 addition & 1 deletion clients/roscpp/include/ros/publication.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class ROSCPP_DECL Publication
const std::string& _md5sum,
const std::string& message_definition,
size_t max_queue,
bool latch,
bool /* unused */,
bool has_header);

~Publication();
Expand Down
27 changes: 25 additions & 2 deletions clients/roscpp/src/libros/publication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ Publication::Publication(const std::string &name,
const std::string &_md5sum,
const std::string& message_definition,
size_t max_queue,
bool latch,
bool /* unused */,
bool has_header)
: name_(name),
datatype_(datatype),
Expand All @@ -87,7 +87,7 @@ Publication::Publication(const std::string &name,
max_queue_(max_queue),
seq_(0),
dropped_(false),
latch_(latch),
latch_(false),
has_header_(has_header),
intraprocess_subscriber_count_(0)
{
Expand Down Expand Up @@ -117,6 +117,13 @@ void Publication::addCallbacks(const SubscriberCallbacksPtr& callbacks)
callbacks->callback_queue_->addCallback(cb, (uint64_t)callbacks.get());
}
}

// Mark the publication as having one or more latched messages if any of the callbacks associated with
// it have a handler defined to push them out.
if (callbacks->push_latched_message_)
{
latch_ = true;
}
}

void Publication::removeCallbacks(const SubscriberCallbacksPtr& callbacks)
Expand All @@ -133,6 +140,22 @@ void Publication::removeCallbacks(const SubscriberCallbacksPtr& callbacks)
}
callbacks_.erase(it);
}

// IF the callbacks we're removing were latched, check the remainder of the list
// to see if any latched callbacks remain. If not, clear the latch status on the singleton.
if (callbacks->push_latched_message_)
{
V_Callback::iterator it = callbacks_.begin();
V_Callback::iterator end = callbacks_.end();
for (; it != end; ++it)
{
if ((*it)->push_latched_message_)
{
return;
}
}
latch_ = false;
}
}

void Publication::drop()
Expand Down
29 changes: 29 additions & 0 deletions test/test_roscpp/test/src/multiple_latched_publishers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

#include <gtest/gtest.h>
#include "ros/ros.h"
#include "ros/topic_manager.h"
#include <std_msgs/builtin_bool.h>


Expand Down Expand Up @@ -79,6 +80,34 @@ TEST(MultipleLatchedPublishers, LatchedPublisherReceiveMultiple)
EXPECT_EQ(latched_publishers.size(), msg_count);
}

TEST(MultipleLatchedPublishers, TopicManagerIsLatched)
{
ros::NodeHandle nh;
std::vector<ros::Publisher> publishers_bar = {
nh.advertise<bool>("bar", 10, false),
nh.advertise<bool>("bar", 10, true),
nh.advertise<bool>("bar", 10, false),
};
EXPECT_TRUE(ros::TopicManager::instance()->isLatched("/bar"));

std::vector<ros::Publisher> publishers_baz = {
nh.advertise<bool>("baz", 10, false),
nh.advertise<bool>("baz", 10, false),
};
EXPECT_FALSE(ros::TopicManager::instance()->isLatched("/baz"));
}

TEST(MultipleLatchedPublishers, TopicManagerLatchShutdown)
{
ros::NodeHandle nh;
ros::Publisher qux_latched = nh.advertise<bool>("qux", 10, true);
ros::Publisher qux_unlatched = nh.advertise<bool>("qux", 10, false);
EXPECT_TRUE(ros::TopicManager::instance()->isLatched("/qux"));

qux_latched.shutdown();
EXPECT_FALSE(ros::TopicManager::instance()->isLatched("/qux"));
}

int main(int argc, char **argv) {
::testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "test_multiple_latched_publishers");
Expand Down

0 comments on commit 8eec231

Please sign in to comment.