Skip to content

Commit

Permalink
print warning if event callback is not supported instead of passing e…
Browse files Browse the repository at this point in the history
…xception. (#2648)

Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya authored Oct 9, 2024
1 parent c50f0c9 commit 41d3a27
Show file tree
Hide file tree
Showing 2 changed files with 83 additions and 34 deletions.
52 changes: 36 additions & 16 deletions rclcpp/src/rclcpp/publisher_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,15 +135,28 @@ void
PublisherBase::bind_event_callbacks(
const PublisherEventCallbacks & event_callbacks, bool use_default_callbacks)
{
if (event_callbacks.deadline_callback) {
this->add_event_handler(
event_callbacks.deadline_callback,
RCL_PUBLISHER_OFFERED_DEADLINE_MISSED);
try {
if (event_callbacks.deadline_callback) {
this->add_event_handler(
event_callbacks.deadline_callback,
RCL_PUBLISHER_OFFERED_DEADLINE_MISSED);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for deadline; not supported");
}
if (event_callbacks.liveliness_callback) {
this->add_event_handler(
event_callbacks.liveliness_callback,
RCL_PUBLISHER_LIVELINESS_LOST);

try {
if (event_callbacks.liveliness_callback) {
this->add_event_handler(
event_callbacks.liveliness_callback,
RCL_PUBLISHER_LIVELINESS_LOST);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for liveliness; not supported");
}

QOSOfferedIncompatibleQoSCallbackType incompatible_qos_cb;
Expand All @@ -160,9 +173,9 @@ PublisherBase::bind_event_callbacks(
this->add_event_handler(incompatible_qos_cb, RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_DEBUG(
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for incompatible qos; wrong callback type");
"Failed to add event handler for incompatible qos; not supported");
}

IncompatibleTypeCallbackType incompatible_type_cb;
Expand All @@ -179,14 +192,21 @@ PublisherBase::bind_event_callbacks(
this->add_event_handler(incompatible_type_cb, RCL_PUBLISHER_INCOMPATIBLE_TYPE);
}
} catch (UnsupportedEventTypeException & /*exc*/) {
RCLCPP_DEBUG(
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for incompatible type; wrong callback type");
"Failed to add event handler for incompatible type; not supported");
}
if (event_callbacks.matched_callback) {
this->add_event_handler(
event_callbacks.matched_callback,
RCL_PUBLISHER_MATCHED);

try {
if (event_callbacks.matched_callback) {
this->add_event_handler(
event_callbacks.matched_callback,
RCL_PUBLISHER_MATCHED);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for matched; not supported");
}
}

Expand Down
65 changes: 47 additions & 18 deletions rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,16 +112,28 @@ void
SubscriptionBase::bind_event_callbacks(
const SubscriptionEventCallbacks & event_callbacks, bool use_default_callbacks)
{
if (event_callbacks.deadline_callback) {
this->add_event_handler(
event_callbacks.deadline_callback,
RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED);
try {
if (event_callbacks.deadline_callback) {
this->add_event_handler(
event_callbacks.deadline_callback,
RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for deadline; not supported");
}

if (event_callbacks.liveliness_callback) {
this->add_event_handler(
event_callbacks.liveliness_callback,
RCL_SUBSCRIPTION_LIVELINESS_CHANGED);
try {
if (event_callbacks.liveliness_callback) {
this->add_event_handler(
event_callbacks.liveliness_callback,
RCL_SUBSCRIPTION_LIVELINESS_CHANGED);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for liveliness; not supported");
}

QOSRequestedIncompatibleQoSCallbackType incompatible_qos_cb;
Expand All @@ -139,7 +151,9 @@ SubscriptionBase::bind_event_callbacks(
this->add_event_handler(incompatible_qos_cb, RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
// pass
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for incompatible qos; not supported");
}

IncompatibleTypeCallbackType incompatible_type_cb;
Expand All @@ -156,18 +170,33 @@ SubscriptionBase::bind_event_callbacks(
this->add_event_handler(incompatible_type_cb, RCL_SUBSCRIPTION_INCOMPATIBLE_TYPE);
}
} catch (UnsupportedEventTypeException & /*exc*/) {
// pass
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for incompatible type; not supported");
}

if (event_callbacks.message_lost_callback) {
this->add_event_handler(
event_callbacks.message_lost_callback,
RCL_SUBSCRIPTION_MESSAGE_LOST);
try {
if (event_callbacks.message_lost_callback) {
this->add_event_handler(
event_callbacks.message_lost_callback,
RCL_SUBSCRIPTION_MESSAGE_LOST);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for message lost; not supported");
}
if (event_callbacks.matched_callback) {
this->add_event_handler(
event_callbacks.matched_callback,
RCL_SUBSCRIPTION_MATCHED);

try {
if (event_callbacks.matched_callback) {
this->add_event_handler(
event_callbacks.matched_callback,
RCL_SUBSCRIPTION_MATCHED);
}
} catch (const UnsupportedEventTypeException & /*exc*/) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Failed to add event handler for matched; not supported");
}
}

Expand Down

0 comments on commit 41d3a27

Please sign in to comment.