pub struct Publisher<T>where
T: Message,{ /* private fields */ }
Expand description
Struct for sending messages of type T
.
Multiple publishers can be created for the same topic, in different nodes or the same node.
The underlying RMW will decide on the concrete delivery mechanism (network stack, shared memory, or intraprocess).
Sending messages does not require the node’s executor to spin.
Implementations§
Source§impl<T> Publisher<T>where
T: Message,
impl<T> Publisher<T>where
T: Message,
Sourcepub fn topic_name(&self) -> String
pub fn topic_name(&self) -> String
Returns the topic name of the publisher.
This returns the topic name after remapping, so it is not necessarily the topic name which was used when creating the publisher.
Sourcepub fn get_subscription_count(&self) -> Result<usize, RclrsError>
pub fn get_subscription_count(&self) -> Result<usize, RclrsError>
Returns the number of subscriptions of the publisher.
Sourcepub fn publish<'a, M: MessageCow<'a, T>>(
&self,
message: M,
) -> Result<(), RclrsError>
pub fn publish<'a, M: MessageCow<'a, T>>( &self, message: M, ) -> Result<(), RclrsError>
Publishes a message.
The MessageCow
trait is implemented by any
[Message
] as well as any reference to a Message
.
The reason for allowing owned messages is that publishing owned messages can be more efficient in the case of idiomatic messages1.
Hence, when a message will not be needed anymore after publishing, pass it by value. When a message will be needed again after publishing, pass it by reference, instead of cloning and passing by value.
Calling publish()
is a potentially blocking call, see this issue for details.
See the [
Message
] trait for an explanation of “idiomatic”. ↩
Source§impl<T> Publisher<T>where
T: RmwMessage,
impl<T> Publisher<T>where
T: RmwMessage,
Sourcepub fn borrow_loaned_message(&self) -> Result<LoanedMessage<'_, T>, RclrsError>
pub fn borrow_loaned_message(&self) -> Result<LoanedMessage<'_, T>, RclrsError>
Obtains a writable handle to a message owned by the middleware.
This lets the middleware control how and where to allocate memory for the
message.
The purpose of this is typically to achieve zero-copy communication between publishers and
subscriptions on the same machine: the message is placed directly in a shared memory region,
and a reference to the same memory is returned by Subscription::take_loaned_message()
.
No copying or serialization/deserialization takes place, which is much more efficient,
especially as the message size grows.
§Conditions for zero-copy communication
- A middleware with support for shared memory is used, e.g.
CycloneDDS
withiceoryx
- Shared memory transport is enabled in the middleware configuration
- Publishers and subscriptions are on the same machine
- The message is a “plain old data” type containing no variable-size members, whether bounded or unbounded
- The publisher’s QOS settings are compatible with zero-copy, e.g. the default QOS
Publisher::borrow_loaned_message()
is used and the subscription uses a callback taking aReadOnlyLoanedMessage
This function is only implemented for [RmwMessage
]s since the “idiomatic” message type
does not have a typesupport library.
Sourcepub fn can_loan_messages(&self) -> bool
pub fn can_loan_messages(&self) -> bool
Returns true if message loans are possible, false otherwise.