Template Class RealtimePublisher

Class Documentation

template<class MessageT>
class RealtimePublisher

Public Types

using PublisherType = rclcpp::Publisher<MessageT>

Provide various typedefs to resemble the rclcpp::Publisher type.

using PublisherSharedPtr = typename rclcpp::Publisher<MessageT>::SharedPtr
using PublishedType = typename rclcpp::TypeAdapter<MessageT>::custom_type
using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type

Public Functions

inline explicit RealtimePublisher(PublisherSharedPtr publisher)

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()
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 tryPublish(const MessageT &msg)

Try to get the data lock from realtime and publish the given message.

Tries to gain unique access to msg_ variable. If this succeeds update the msg_ variable and call unlockAndPublish

Parameters:

msg[in] The message to publish

Returns:

false in case no lock for the realtime variable is acquired. This implies the message will not be published.

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

Public Members

MessageT msg_

The msg_ variable contains the data that will get published on the ROS topic.