Template Class RealtimeServerGoalHandle
Defined in File realtime_server_goal_handle.hpp
Class Documentation
-
template<class Action>
class RealtimeServerGoalHandle Public Functions
Set feedback to be published by runNonRealtime().
This method uses a non-blocking lock acquisition with try_to_lock() and is safe to call from real-time context without causing thread blocking or priority inversion. If the lock cannot be acquired (because runNonRealtime() is holding it), the update is silently skipped to avoid blocking the real-time thread.
The feedback pointer is stored and the non-RT thread will publish it on the next runNonRealtime() call, provided the goal handle is in executing state.
See also
runNonRealtime() for the counterpart that publishes the feedback.
See also
preallocated_feedback_ for recommended pre-allocated feedback usage.
Note
If the mutex lock cannot be acquired, the feedback update is dropped without notification. This is intentional to preserve real-time guarantees. Check the return value if you need to know whether the update succeeded.
Note
Feedback is only published if the goal is currently executing. If feedback is set after the goal transitions out of executing state, it will be discarded.
- Parameters:
feedback – Shared pointer to feedback message. Can be nullptr to clear pending feedback. If a valid pointer is provided, the caller must ensure the feedback object remains valid until runNonRealtime() processes it. Using a preallocated feedback message (stored in preallocated_feedback_) is recommended to avoid dynamic allocations in the real-time thread.
- Returns:
true if the lock was acquired and feedback was successfully set, false if the lock could not be acquired (feedback update was dropped).
-
inline void execute()
-
inline bool valid()
-
inline void runNonRealtime()