Skip to content

Commit e5e258e

Browse files
YoshiRipre-commit-ci[bot]
authored andcommitted
feat(autoware_test_utils): add qos handler in pub/sub (autowarefoundation#7856)
* feat: add qos handler in pub/sub Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * style(pre-commit): autofix * feat: update test_pub_msg function to not use setpublisher function Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> --------- Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: xtk8532704 <1041084556@qq.com>
1 parent 91e3463 commit e5e258e

File tree

1 file changed

+34
-12
lines changed

1 file changed

+34
-12
lines changed

common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp

+34-12
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@
4848

4949
#include <limits>
5050
#include <memory>
51+
#include <optional>
5152
#include <string>
5253
#include <unordered_map>
5354
#include <vector>
@@ -402,6 +403,7 @@ void createPublisherWithQoS(
402403
rclcpp::Node::SharedPtr test_node, std::string topic_name,
403404
std::shared_ptr<rclcpp::Publisher<T>> & publisher)
404405
{
406+
// override QoS settings for specific message types
405407
if constexpr (
406408
std::is_same_v<T, LaneletRoute> || std::is_same_v<T, LaneletMapBin> ||
407409
std::is_same_v<T, OperationModeState>) {
@@ -443,18 +445,23 @@ void setPublisher(
443445
* @param topic_name The name of the topic to subscribe to.
444446
* @param callback The callback function to call when a message is received.
445447
* @param subscriber A reference to the subscription to be created.
448+
* @param qos The QoS settings for the subscription (optional).
446449
*/
447450
template <typename T>
448451
void createSubscription(
449-
rclcpp::Node::SharedPtr test_node, std::string topic_name,
452+
rclcpp::Node::SharedPtr test_node, const std::string & topic_name,
450453
std::function<void(const typename T::ConstSharedPtr)> callback,
451-
std::shared_ptr<rclcpp::Subscription<T>> & subscriber)
454+
std::shared_ptr<rclcpp::Subscription<T>> & subscriber,
455+
std::optional<rclcpp::QoS> qos = std::nullopt)
452456
{
453-
if constexpr (std::is_same_v<T, Trajectory>) {
454-
subscriber = test_node->create_subscription<T>(topic_name, rclcpp::QoS{1}, callback);
455-
} else {
456-
subscriber = test_node->create_subscription<T>(topic_name, 10, callback);
457+
if (!qos.has_value()) {
458+
if constexpr (std::is_same_v<T, Trajectory>) {
459+
qos = rclcpp::QoS{1};
460+
} else {
461+
qos = rclcpp::QoS{10};
462+
}
457463
}
464+
subscriber = test_node->create_subscription<T>(topic_name, *qos, callback);
458465
}
459466

460467
/**
@@ -467,14 +474,17 @@ void createSubscription(
467474
* @param topic_name The name of the topic to subscribe to.
468475
* @param subscriber A reference to the subscription to be set.
469476
* @param count A reference to a counter that increments on message receipt.
477+
* @param qos The QoS settings for the subscription (optional).
470478
*/
471479
template <typename T>
472480
void setSubscriber(
473481
rclcpp::Node::SharedPtr test_node, std::string topic_name,
474-
std::shared_ptr<rclcpp::Subscription<T>> & subscriber, size_t & count)
482+
std::shared_ptr<rclcpp::Subscription<T>> & subscriber, size_t & count,
483+
std::optional<rclcpp::QoS> qos = std::nullopt)
475484
{
476485
createSubscription(
477-
test_node, topic_name, [&count](const typename T::ConstSharedPtr) { count++; }, subscriber);
486+
test_node, topic_name, [&count](const typename T::ConstSharedPtr) { count++; }, subscriber,
487+
qos);
478488
}
479489

480490
/**
@@ -534,28 +544,40 @@ class AutowareTestManager
534544
template <typename MessageType>
535545
void test_pub_msg(
536546
rclcpp::Node::SharedPtr target_node, const std::string & topic_name, MessageType & msg)
547+
{
548+
rclcpp::QoS qos(rclcpp::KeepLast(10));
549+
test_pub_msg(target_node, topic_name, msg, qos);
550+
}
551+
552+
template <typename MessageType>
553+
void test_pub_msg(
554+
rclcpp::Node::SharedPtr target_node, const std::string & topic_name, MessageType & msg,
555+
rclcpp::QoS qos)
537556
{
538557
if (publishers_.find(topic_name) == publishers_.end()) {
539-
auto publisher = test_node_->create_publisher<MessageType>(topic_name, 10);
558+
auto publisher = test_node_->create_publisher<MessageType>(topic_name, qos);
540559
publishers_[topic_name] = std::static_pointer_cast<rclcpp::PublisherBase>(publisher);
541560
}
542561

543562
auto publisher =
544563
std::dynamic_pointer_cast<rclcpp::Publisher<MessageType>>(publishers_[topic_name]);
545564

546-
autoware::test_utils::publishToTargetNode(test_node_, target_node, topic_name, publisher, msg);
565+
publisher->publish(msg);
566+
const int repeat_count = 3;
567+
autoware::test_utils::spinSomeNodes(test_node_, target_node, repeat_count);
547568
RCLCPP_INFO(test_node_->get_logger(), "Published message on topic '%s'", topic_name.c_str());
548569
}
549570

550571
template <typename MessageType>
551572
void set_subscriber(
552573
const std::string & topic_name,
553-
std::function<void(const typename MessageType::ConstSharedPtr)> callback)
574+
std::function<void(const typename MessageType::ConstSharedPtr)> callback,
575+
std::optional<rclcpp::QoS> qos = std::nullopt)
554576
{
555577
if (subscribers_.find(topic_name) == subscribers_.end()) {
556578
std::shared_ptr<rclcpp::Subscription<MessageType>> subscriber;
557579
autoware::test_utils::createSubscription<MessageType>(
558-
test_node_, topic_name, callback, subscriber);
580+
test_node_, topic_name, callback, subscriber, qos);
559581
subscribers_[topic_name] = std::static_pointer_cast<rclcpp::SubscriptionBase>(subscriber);
560582
} else {
561583
RCLCPP_WARN(test_node_->get_logger(), "Subscriber %s already set.", topic_name.c_str());

0 commit comments

Comments
 (0)