Provides a subscription to arbitrary ROS topics.
More...
#include <px4_ros2/utils/subscription.hpp>
|
| Subscription (Context &context, const std::string &topic) |
|
void | onUpdate (const UpdateCallback &callback) |
| Add a callback to execute when receiving a new message. More...
|
|
const RosMessageType & | last () const |
| Get the last-received message. More...
|
|
const rclcpp::Time & | lastTime () const |
| Get the receive-time of the last message. More...
|
|
template<typename DurationT = std::milli> |
bool | lastValid (const std::chrono::duration< int64_t, DurationT > max_delay=500ms) const |
| Check whether the last message is still valid. To be valid, the message must have been received within a given time of the current time. More...
|
|
template<typename RosMessageType>
class px4_ros2::Subscription< RosMessageType >
Provides a subscription to arbitrary ROS topics.
◆ last()
template<typename RosMessageType >
Get the last-received message.
- Returns
- the last-received ROS message
- Exceptions
-
std::runtime_error | when no messages have been received |
◆ lastTime()
template<typename RosMessageType >
Get the receive-time of the last message.
- Returns
- the time at which the last ROS message was received
◆ lastValid()
template<typename RosMessageType >
template<typename DurationT = std::milli>
bool px4_ros2::Subscription< RosMessageType >::lastValid |
( |
const std::chrono::duration< int64_t, DurationT > |
max_delay = 500ms | ) |
const |
|
inline |
Check whether the last message is still valid. To be valid, the message must have been received within a given time of the current time.
- Parameters
-
max_delay | the maximum delay between the current time and when the message was received |
- Returns
- true if the last message was received within the maximum delay
◆ onUpdate()
template<typename RosMessageType >
Add a callback to execute when receiving a new message.
- Parameters
-
callback | the callback function |
The documentation for this class was generated from the following file: