Skip to content

Commit

Permalink
update to be compatible with latest rclcpp API
Browse files Browse the repository at this point in the history
Signed-off-by: Miaofei <[email protected]>
  • Loading branch information
mm318 committed May 9, 2019
1 parent 3cec879 commit d1fc46d
Show file tree
Hide file tree
Showing 9 changed files with 55 additions and 57 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ class QosTestNode : public rclcpp::Node
public:
QosTestNode(
const std::string & name,
const std::string & topic);
const std::string & topic,
const rclcpp::QoS & qos_options);

virtual ~QosTestNode();

Expand Down Expand Up @@ -57,10 +58,13 @@ class QosTestNode : public rclcpp::Node
* \return the incremented count
*/
int increment_count();

/// name of this publisher (Node)
const std::string name_;
/// topic name to publish
const std::string topic_;
/// qos options needed for QoS settings
const rclcpp::QoS qos_options_;

private:
/// simple counter used for this node's measurements
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ class QosTestPublisher : public QosTestNode
QosTestPublisher(
const std::string & name,
const std::string & topic,
const rclcpp::QoS & qos_options,
const rclcpp::PublisherOptions & publisher_options,
const std::chrono::milliseconds & publish_period);

Expand All @@ -46,12 +47,13 @@ class QosTestPublisher : public QosTestNode
void setup_start() override;
void setup_stop() override;

/// publisher options needed for QoS settings
/// publisher options needed for QoS callbacks
const rclcpp::PublisherOptions publisher_options_;
/// publishing period
const std::chrono::milliseconds publish_period_;
/// the timer of this publisher
rclcpp::TimerBase::SharedPtr timer_;

rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ class QosTestSubscriber : public QosTestNode
QosTestSubscriber(
const std::string & name,
const std::string & topic,
const rclcpp::QoS & qos_options,
const rclcpp::SubscriptionOptions & sub_options);

virtual ~QosTestSubscriber() = default;
Expand All @@ -45,8 +46,9 @@ class QosTestSubscriber : public QosTestNode
void setup_stop() override;

private:
/// subscription options needed for QoS settings
/// subscription options needed for QoS callbacks
const rclcpp::SubscriptionOptions sub_options_;

rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};

Expand Down
4 changes: 3 additions & 1 deletion test_quality_of_service/test/qos_test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,12 @@

QosTestNode::QosTestNode(
const std::string & name,
const std::string & topic)
const std::string & topic,
const rclcpp::QoS & qos_options)
: Node(name),
name_(name),
topic_(topic),
qos_options_(qos_options),
count_(0),
started_(false)
{}
Expand Down
6 changes: 4 additions & 2 deletions test_quality_of_service/test/qos_test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,15 +20,17 @@
QosTestPublisher::QosTestPublisher(
const std::string & name,
const std::string & topic,
const rclcpp::QoS & qos_options,
const rclcpp::PublisherOptions & publisher_options,
const std::chrono::milliseconds & publish_period)
: QosTestNode(name, topic),
: QosTestNode(name, topic, qos_options),
publisher_options_(publisher_options),
publish_period_(publish_period),
timer_(nullptr)
{
RCLCPP_INFO(this->get_logger(), "created publisher %s %s\n", name.c_str(), topic.c_str());
publisher_ = this->create_publisher<std_msgs::msg::String>(topic_, 10, publisher_options_);
publisher_ = this->create_publisher<std_msgs::msg::String>(
topic_, qos_options_, publisher_options_);
}

void QosTestPublisher::publish_message()
Expand Down
5 changes: 3 additions & 2 deletions test_quality_of_service/test/qos_test_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,9 @@ using std::placeholders::_1;
QosTestSubscriber::QosTestSubscriber(
const std::string & name,
const std::string & topic,
const rclcpp::QoS & qos_options,
const rclcpp::SubscriptionOptions & sub_options)
: QosTestNode(name, topic),
: QosTestNode(name, topic, qos_options),
sub_options_(sub_options),
subscription_(nullptr)
{
Expand All @@ -48,8 +49,8 @@ void QosTestSubscriber::setup_start()
if (!subscription_) {
subscription_ = create_subscription<std_msgs::msg::String>(
topic_,
qos_options_,
std::bind(&QosTestSubscriber::listen_to_message, this, _1),
10,
sub_options_);
}
}
Expand Down
30 changes: 13 additions & 17 deletions test_quality_of_service/test/test_deadline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,19 +34,17 @@ using namespace std::chrono_literals;
TEST_F(QosRclcppTestFixture, test_deadline_no_publisher) {
const std::chrono::milliseconds deadline_duration = 1s;
const std::chrono::milliseconds test_duration = 10500ms;
const std::tuple<size_t, size_t> deadline_duration_tuple = convert_chrono_milliseconds_to_size_t(
deadline_duration);
const int expected_number_of_deadline_callbacks = test_duration / deadline_duration;

int total_number_of_subscriber_deadline_events = 0;
int last_sub_count = 0;

rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
std::tie(qos_profile.deadline.sec, qos_profile.deadline.nsec) = deadline_duration_tuple;
// define qos profile
rclcpp::QoS qos_profile(10);
qos_profile.deadline(deadline_duration);

// setup subscription options and callback
rclcpp::SubscriptionOptions subscriber_options;
subscriber_options.qos_profile = qos_profile;
subscriber_options.event_callbacks.deadline_callback =
[&last_sub_count,
&total_number_of_subscriber_deadline_events](rclcpp::QOSDeadlineRequestedInfo & event) -> void
Expand All @@ -63,9 +61,10 @@ TEST_F(QosRclcppTestFixture, test_deadline_no_publisher) {
const std::string topic("test_deadline_no_publisher");

// register a publisher for the topic but don't publish anything or use QoS options
publisher = std::make_shared<QosTestPublisher>("publisher", topic, publisher_options,
test_duration);
subscriber = std::make_shared<QosTestSubscriber>("subscriber", topic, subscriber_options);
publisher = std::make_shared<QosTestPublisher>(
"publisher", topic, qos_profile, publisher_options, test_duration);
subscriber = std::make_shared<QosTestSubscriber>(
"subscriber", topic, qos_profile, subscriber_options);

executor->add_node(subscriber);
subscriber->start();
Expand All @@ -83,8 +82,6 @@ TEST_F(QosRclcppTestFixture, test_deadline_no_publisher) {
TEST_F(QosRclcppTestFixture, test_deadline) {
int expected_number_of_events = 5;
const std::chrono::milliseconds deadline_duration = 1s;
const std::tuple<size_t, size_t> deadline_duration_tuple = convert_chrono_milliseconds_to_size_t(
deadline_duration);
const std::chrono::milliseconds max_test_length = 10s;
const std::chrono::milliseconds publish_rate = deadline_duration / expected_number_of_events;

Expand All @@ -94,12 +91,11 @@ TEST_F(QosRclcppTestFixture, test_deadline) {
int last_pub_count = 0;
int last_sub_count = 0;

rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
std::tie(qos_profile.deadline.sec, qos_profile.deadline.nsec) = deadline_duration_tuple;
rclcpp::QoS qos_profile(10);
qos_profile.deadline(deadline_duration);

// setup subscription options and callback
rclcpp::SubscriptionOptions subscriber_options;
subscriber_options.qos_profile = qos_profile;
subscriber_options.event_callbacks.deadline_callback =
[&last_sub_count,
&total_number_of_subscriber_deadline_events](rclcpp::QOSDeadlineRequestedInfo & event) -> void
Expand All @@ -113,7 +109,6 @@ TEST_F(QosRclcppTestFixture, test_deadline) {

// setup publishing options and callback
rclcpp::PublisherOptions publisher_options;
publisher_options.qos_profile = qos_profile;
publisher_options.event_callbacks.deadline_callback =
[&last_pub_count,
&total_number_of_publisher_deadline_events](rclcpp::QOSDeadlineOfferedInfo & event) -> void
Expand All @@ -127,9 +122,10 @@ TEST_F(QosRclcppTestFixture, test_deadline) {

const std::string topic("test_deadline");

publisher = std::make_shared<QosTestPublisher>("publisher", topic, publisher_options,
publish_rate);
subscriber = std::make_shared<QosTestSubscriber>("subscriber", topic, subscriber_options);
publisher = std::make_shared<QosTestPublisher>(
"publisher", topic, qos_profile, publisher_options, publish_rate);
subscriber = std::make_shared<QosTestSubscriber>(
"subscriber", topic, qos_profile, subscriber_options);

// toggle publishing on and off to force deadline events
rclcpp::TimerBase::SharedPtr toggle_publisher_timer = subscriber->create_wall_timer(
Expand Down
19 changes: 7 additions & 12 deletions test_quality_of_service/test/test_lifespan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,33 +32,28 @@ using namespace std::chrono_literals;

TEST_F(QosRclcppTestFixture, test_deadline) {
const std::chrono::milliseconds lifespan_duration = 1s;
const std::tuple<size_t, size_t> message_lifespan = convert_chrono_milliseconds_to_size_t(
lifespan_duration);
const int history = 2;
const std::chrono::milliseconds max_test_length = 11s;
const int expected_published = max_test_length / lifespan_duration * 2;
const std::chrono::milliseconds publish_period = 500ms;

// define qos profile
rmw_qos_profile_t qos_profile = rmw_qos_profile_default;

qos_profile.depth = history;
qos_profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
std::tie(qos_profile.deadline.sec, qos_profile.deadline.nsec) = message_lifespan;
rclcpp::QoS qos_profile(history);
qos_profile.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
qos_profile.lifespan(lifespan_duration);

// subscription options
rclcpp::SubscriptionOptions subscriber_options;
subscriber_options.qos_profile = qos_profile;

// publisher options
rclcpp::PublisherOptions publisher_options;
publisher_options.qos_profile = qos_profile;

std::string topic = "test_lifespan";

publisher = std::make_shared<QosTestPublisher>("publisher", topic, publisher_options,
publish_period);
subscriber = std::make_shared<QosTestSubscriber>("subscriber", topic, subscriber_options);
publisher = std::make_shared<QosTestPublisher>(
"publisher", topic, qos_profile, publisher_options, publish_period);
subscriber = std::make_shared<QosTestSubscriber>(
"subscriber", topic, qos_profile, subscriber_options);

int timer_fired_count = 0;
// toggle publishing on and off to force deadline events
Expand Down
34 changes: 14 additions & 20 deletions test_quality_of_service/test/test_liveliness.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,21 +40,17 @@ TEST_F(QosRclcppTestFixture, test_automatic_liveliness_changed) {
const std::chrono::milliseconds kill_publisher_after = 2s;
const std::chrono::milliseconds publish_period = 200ms;
int number_of_published_messages = 0;
const std::tuple<size_t, size_t> liveliness_lease_tuple =
convert_chrono_milliseconds_to_size_t(1s);
const std::chrono::milliseconds lease_duration = 1s;

int total_number_of_liveliness_events = 0;

rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
// define liveliness policy
qos_profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;

std::tie(qos_profile.deadline.sec, qos_profile.deadline.nsec) = liveliness_lease_tuple;
// define qos profile
rclcpp::QoS qos_profile(10);
qos_profile.liveliness(RMW_QOS_POLICY_LIVELINESS_AUTOMATIC);
qos_profile.liveliness_lease_duration(lease_duration);

// subscription options
rclcpp::SubscriptionOptions subscriber_options;
subscriber_options.qos_profile = qos_profile;

// subscriber Liveliness callback event
subscriber_options.event_callbacks.liveliness_callback =
[&total_number_of_liveliness_events](rclcpp::QOSLivelinessChangedInfo & event) -> void
Expand All @@ -80,20 +76,18 @@ TEST_F(QosRclcppTestFixture, test_automatic_liveliness_changed) {

// publisher options
rclcpp::PublisherOptions publisher_options;
publisher_options.qos_profile = qos_profile;

// publisher_options.event_callbacks.liveliness_callback =
// [](rclcpp::QOSLivelinessLostInfo & event) -> void
// {
// RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "=====QOSLivelinessLostInfo callback fired");
// };
publisher_options.event_callbacks.liveliness_callback =
[](rclcpp::QOSLivelinessLostInfo & /*event*/) -> void
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "=====QOSLivelinessLostInfo callback fired");
};

std::string topic("test_automatic_liveliness_changed");

publisher = std::make_shared<QosTestPublisher>("publisher", topic, publisher_options,
publish_period);

subscriber = std::make_shared<QosTestSubscriber>("subscriber", topic, subscriber_options);
publisher = std::make_shared<QosTestPublisher>(
"publisher", topic, qos_profile, publisher_options, publish_period);
subscriber = std::make_shared<QosTestSubscriber>(
"subscriber", topic, qos_profile, subscriber_options);

int timer_fired_count = 0;
// kill the publisher after a predetermined amount of time
Expand Down

0 comments on commit d1fc46d

Please sign in to comment.