add get_actual_qos() feature to subscriptions (#754)
Signed-off-by: Miaofei <miaofei@amazon.com>
This commit is contained in:
parent
91198ef917
commit
0ae3da49e7
2 changed files with 26 additions and 0 deletions
|
@ -98,6 +98,20 @@ public:
|
|||
const std::vector<std::shared_ptr<rclcpp::QOSEventHandlerBase>> &
|
||||
get_event_handlers() const;
|
||||
|
||||
/// Get the actual QoS settings, after the defaults have been determined.
|
||||
/**
|
||||
* The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT
|
||||
* can only be resolved after the creation of the publisher, and it
|
||||
* depends on the underlying rmw implementation.
|
||||
* If the underlying setting in use can't be represented in ROS terms,
|
||||
* it will be set to RMW_QOS_POLICY_*_UNKNOWN.
|
||||
* May throw runtime_error when an unexpected error occurs.
|
||||
* \return The actual qos settings.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
rmw_qos_profile_t
|
||||
get_actual_qos() const;
|
||||
|
||||
/// Borrow a new message.
|
||||
/** \return Shared pointer to the fresh message. */
|
||||
virtual std::shared_ptr<void>
|
||||
|
|
|
@ -128,6 +128,18 @@ SubscriptionBase::get_event_handlers() const
|
|||
return event_handlers_;
|
||||
}
|
||||
|
||||
rmw_qos_profile_t
|
||||
SubscriptionBase::get_actual_qos() const
|
||||
{
|
||||
const rmw_qos_profile_t * qos = rcl_subscription_get_actual_qos(subscription_handle_.get());
|
||||
if (!qos) {
|
||||
auto msg = std::string("failed to get qos settings: ") + rcl_get_error_string().str;
|
||||
rcl_reset_error();
|
||||
throw std::runtime_error(msg);
|
||||
}
|
||||
return *qos;
|
||||
}
|
||||
|
||||
const rosidl_message_type_support_t &
|
||||
SubscriptionBase::get_message_type_support_handle() const
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue