Unable to get subscriber event call backs

asked 2021-09-16 10:26:58 -0500

BhanuKiran.Chaluvadi gravatar image

updated 2021-09-17 04:06:31 -0500

Hi,

Following ros2 quality of service demo , I created an example publisher & subscriber nodes hopping to receive a event call back, when the publisher terminates (when pressing ctrl + c ). The code compiles and executes and the subscriber is able to receive the messages published by the publisher but unable to call event callbacks when the publisher dies (ctrl + c ). Here is the code snippet

Subsciber.hpp

class ExternalFTSubsciber {
 public:
  ExternalFTSubsciber();

 private:
  void handleExternalFTSensorSub(const geometry_msgs::msg::WrenchStamped::SharedPtr wrenchStamped,
                                 const rclcpp::MessageInfo& messageInfo);

  rclcpp::Subscription<geometry_msgs::msg::WrenchStamped>::SharedPtr externalFTSensorSub;
  rclcpp::SubscriptionOptions subscription_options_;
};

Subsciber.cpp

 ExternalFTSubsciber::ExternalFTSubsciber() {
  rclcpp::init(argc, argv);
  auto node = rclcpp::Node::make_shared("ft_talker");

// rclcpp::SubscriptionOptions subscription_options_;  defined in header file      
subscription_options_.event_callbacks.deadline_callback = 
        [](rclcpp::QOSDeadlineRequestedInfo& event) {
            printf("Deadline missed - total %d (delta %d)", event.total_count, event.total_count_change);
        };

  subscription_options_.event_callbacks.liveliness_callback = 
    [](rclcpp::QOSLivelinessChangedInfo& event) -> void {
        printf(
            "Liveliness changed - alive %d (delta %d),"
            " not alive %d (delta %d)",
            event.alive_count, event.alive_count_change, event.not_alive_count, event.not_alive_count_change);
  };
  std::chrono::milliseconds liveliness_lease_duration(1000);

  rclcpp::QoS qos_profile(10);
  qos_profile
    .liveliness(RMW_QOS_POLICY_LIVELINESS_AUTOMATIC)
    .liveliness_lease_duration(liveliness_lease_duration);

  externalFTSensorSub = node->createSubscription<geometry_msgs::msg::WrenchStamped>(
      "external_wrench", qos_profile, std::bind(&ExternalFTSubsciber::handleExternalFTSensorSub, this, _1, _2),
      subscription_options_);
}

Publisher.hpp

int main(int argc, char** argv) {
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);

  // Initialize ROS
  rclcpp::init(argc, argv);
  auto node = rclcpp::Node::make_shared("ft_talker");

  std::chrono::milliseconds liveliness_lease_duration(1000);
  rclcpp::QoS qos_profile(10);
  qos_profile
    .liveliness(RMW_QOS_POLICY_LIVELINESS_AUTOMATIC)
     .liveliness_lease_duration(liveliness_lease_duration);

  auto publisher = node->create_publisher<geometry_msgs::msg::WrenchStamped>("/UR5763/external_wrench", qos_profile);

  // Publish
  rclcpp::WallRate loop_rate(2ms);
  while (rclcpp::ok()) {
    auto message = std::make_unique<geometry_msgs::msg::WrenchStamped>();
    // message->header.seq = 123;
    message->header.stamp = node->get_clock()->now();
    message->header.frame_id = "tool";
try {
      publisher->publish(std::move(message));
      rclcpp::spin_some(node);
    } catch (const rclcpp::exceptions::RCLError& e) {
      RCLCPP_ERROR(node->get_logger(), "unexpectedly failed with %s", e.what());
    }
    loop_rate.sleep();
  }

  rclcpp::shutdown();
  return 0;
}

Thank you

edit retag flag offensive close merge delete

Comments

Can you clarify this statement please?

" The code compiles and executes and the subscriber is able to receive the messages published by the publisher but unable to execute callbacks when the publisher dies (ctrl + c )"

Because it sounds to me like you are expecting the subscriber to continue to process published data after the publisher is dead. In that case, who publishes data for the subscriber to process?

janindu gravatar image janindu  ( 2021-09-16 19:12:17 -0500 )edit

Hi @janindu,

When the publisher dies , I was expecting the event call back not the call back when publisher publish the messages . In my case, I expect it to print "Liveliness changed - alive...."

BhanuKiran.Chaluvadi gravatar image BhanuKiran.Chaluvadi  ( 2021-09-17 01:44:00 -0500 )edit

subscription_options_.event_callbacks.deadline_callback = { printf("Deadline missed - total %d (delta %d)", event.total_count, event.total_count_change); };

  subscription_options_.event_callbacks.liveliness_callback = 
    [](rclcpp::QOSLivelinessChangedInfo& event) -> void {
        printf(
            "Liveliness changed - alive %d (delta %d),"
            " not alive %d (delta %d)",
            event.alive_count, event.alive_count_change, event.not_alive_count, event.not_alive_count_change);
  };

I don't understand the following part of the code. I can be wrong also but please! provide a bit clearer on this.

  1. Where do you have defined subscription_options_ in cpp? it is in the header file if yes, please upload that as well.
  2. These two events are triggered with the same is this possible?
  3. Do we have to initialize() afterwards?
Ranjit Kathiriya gravatar image Ranjit Kathiriya  ( 2021-09-17 02:05:30 -0500 )edit

subscription_options_->initialize();

Thanks for helping me.

Ranjit Kathiriya gravatar image Ranjit Kathiriya  ( 2021-09-17 02:06:01 -0500 )edit

@Ranjit Kathiriya Updated with subscriber header file

BhanuKiran.Chaluvadi gravatar image BhanuKiran.Chaluvadi  ( 2021-09-17 04:07:23 -0500 )edit

Can you explain 2 and 3 points from the above question, of my commet? thanks

Ranjit Kathiriya gravatar image Ranjit Kathiriya  ( 2021-09-17 09:44:17 -0500 )edit

@Ranjit Kathiriya

  1. These two events are triggered with the same is this possible? No, they are triggered by different events.
  2. Refer demos for better understanding.
BhanuKiran.Chaluvadi gravatar image BhanuKiran.Chaluvadi  ( 2021-09-20 05:39:56 -0500 )edit