Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor: Introduce PublisherOptions #372

Merged
merged 3 commits into from
Feb 14, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 8 additions & 6 deletions src/agnocastlib/include/agnocast.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,32 +28,34 @@ template <typename MessageT>
typename Publisher<MessageT>::SharedPtr create_publisher(
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos)
{
return std::make_shared<Publisher<MessageT>>(node, topic_name, qos, true);
PublisherOptions options;
return std::make_shared<Publisher<MessageT>>(node, topic_name, qos, options);
}

template <typename MessageT>
typename Publisher<MessageT>::SharedPtr create_publisher(
rclcpp::Node * node, const std::string & topic_name, const size_t qos_history_depth)
{
PublisherOptions options;
return std::make_shared<Publisher<MessageT>>(
node, topic_name, rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), true);
node, topic_name, rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), options);
}

template <typename MessageT>
typename Publisher<MessageT>::SharedPtr create_publisher(
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos,
const bool do_always_ros2_publish)
const PublisherOptions & options)
{
return std::make_shared<Publisher<MessageT>>(node, topic_name, qos, do_always_ros2_publish);
return std::make_shared<Publisher<MessageT>>(node, topic_name, qos, options);
}

template <typename MessageT>
typename Publisher<MessageT>::SharedPtr create_publisher(
rclcpp::Node * node, const std::string & topic_name, const size_t qos_history_depth,
const bool do_always_ros2_publish)
const PublisherOptions & options)
{
return std::make_shared<Publisher<MessageT>>(
node, topic_name, rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), do_always_ros2_publish);
node, topic_name, rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), options);
}

template <typename MessageT>
Expand Down
17 changes: 12 additions & 5 deletions src/agnocastlib/include/agnocast_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,13 @@ void decrement_borrowed_publisher_num();
extern int agnocast_fd;
extern "C" uint32_t get_borrowed_publisher_num();

struct PublisherOptions
{
// For transient local. If true, publish() does both Agnocast publish and ROS 2 publish,
// regardless of the existence of ROS 2 subscriptions.
bool do_always_ros2_publish = true;
};

template <typename MessageT>
class Publisher
{
Expand All @@ -45,15 +52,15 @@ class Publisher
// TODO(Koichi98): The mq should be closed when a subscriber unsubscribes the topic, but this is
// not currently implemented.
std::unordered_map<std::string, mqd_t> opened_mqs_;
bool do_always_ros2_publish_; // For transient local.
PublisherOptions options_;
typename rclcpp::Publisher<MessageT>::SharedPtr ros2_publisher_;

public:
using SharedPtr = std::shared_ptr<Publisher<MessageT>>;

Publisher(
rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos,
const bool do_always_ros2_publish)
const PublisherOptions & options)
: topic_name_(node->get_node_topics_interface()->resolve_topic_name(topic_name)),
publisher_pid_(getpid()),
qos_(qos),
Expand All @@ -68,9 +75,9 @@ class Publisher
#endif

if (qos.durability() == rclcpp::DurabilityPolicy::TransientLocal) {
do_always_ros2_publish_ = do_always_ros2_publish;
options_.do_always_ros2_publish = options.do_always_ros2_publish;
} else {
do_always_ros2_publish_ = false;
options_.do_always_ros2_publish = false;
}

id_ = initialize_publisher(publisher_pid_, topic_name_);
Expand Down Expand Up @@ -102,7 +109,7 @@ class Publisher
delete release_ptr;
}

if (do_always_ros2_publish_ || ros2_publisher_->get_subscription_count() > 0) {
if (options_.do_always_ros2_publish || ros2_publisher_->get_subscription_count() > 0) {
const MessageT * raw = message.get();
ros2_publisher_->publish(*raw);
}
Expand Down