Template Class RealtimePublisher
Defined in File realtime_publisher.hpp
Class Documentation
-
template<class MessageT>
class RealtimePublisher Public Types
-
using PublisherType = rclcpp::Publisher<MessageT>
Provide various typedefs to resemble the rclcpp::Publisher type.
Public Functions
Constructor for the realtime publisher.
Starts a dedicated thread for message publishing. The publishing thread runs the publishingLoop() function to handle message delivery in a non-realtime context.
- Parameters:
publisher – the ROS publisher to wrap
-
inline ~RealtimePublisher()
Destructor.
-
inline void stop()
Stop the realtime publisher.
Signals the publishing thread to exit by setting keep_running_ to false and notifying the condition variable. This allows the publishing loop to break out of its wait state and exit cleanly.
-
inline bool trylock()
Try to acquire the data lock for non-realtime message publishing.
It first checks if the current state allows non-realtime message publishing (turn_ == REALTIME) and then attempts to lock
- Returns:
true if the lock was successfully acquired, false otherwise
-
inline bool can_publish() const
Check if the realtime publisher is in a state to publish messages.
Note
The msg_ variable can be safely accessed if this function returns true
- Returns:
true if the publisher is in a state to publish messages
-
inline bool try_publish(const MessageT &msg)
Try to publish the given message.
This method attempts to publish the given message if the publisher is in a state to do so. It uses a try_lock to avoid blocking if the mutex is already held by another thread.
- Parameters:
msg – [in] The message to publish
- Returns:
true if the message was successfully published, false otherwise
-
inline bool tryPublish(const MessageT &msg)
Try to publish the given message (deprecated)
- Deprecated:
This method is deprecated and should be replaced with try_publish()
This method is deprecated and should be replaced with try_publish(). It attempts to publish the given message if the publisher is in a state to do so. It uses a try_lock to avoid blocking if the mutex is already held by another thread.
- Parameters:
msg – [in] The message to publish
- Returns:
true if the message was successfully published, false otherwise
-
inline void unlockAndPublish()
Unlock the msg_ variable for the non-realtime thread to start publishing.
After a successful trylock and after the data is written to the mgs_ variable, the lock has to be released for the message to get published on the specified topic.
-
inline void lock()
Acquire the data lock.
This blocking call acquires exclusive access to the msg_ variable. Use trylock() for non-blocking attempts to acquire the lock.
-
inline void unlock()
Unlocks the data without publishing anything.
-
inline std::thread &get_thread()
-
inline const std::thread &get_thread() const
-
inline std::mutex &get_mutex()
-
inline const std::mutex &get_mutex() const
-
using PublisherType = rclcpp::Publisher<MessageT>