Ros2: Subscriber listens to messages while LifecycleNode is unconfigured or inactive.

asked 2018-09-02 00:44:51 -0500

Teckel gravatar image

I want a lifecycle node to receive messages only when it is on the active state. According to the Managed States page, a node executes callbacks during the active state. But in the next sample code it executes the subscriber callback during the unconfigured state.

#include <chrono>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "std_msgs/msg/bool.hpp"

using namespace std::chrono_literals;

class Subscriber : public rclcpp_lifecycle::LifecycleNode{
  rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr sub;
public:
  explicit Subscriber(const std::string & node_name, bool intra_process_comms = false)
  : rclcpp_lifecycle::LifecycleNode(node_name, "", intra_process_comms){
    sub = this->create_subscription<std_msgs::msg::Bool>(
      "bool",
      [this](std_msgs::msg::Bool::UniquePtr msg) {
      RCLCPP_INFO(this->get_logger(), "Received: '%i'", msg->data)
    });
  }
};

class Publisher : public rclcpp::Node{
  rclcpp::TimerBase::SharedPtr timer;
  rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr pub;
public:
  explicit Publisher(const std::string & node_name) : Node(node_name)
  {
    pub = this->create_publisher<std_msgs::msg::Bool>("bool");
    auto timer_callback =
      [this]() -> void {
        auto message = std_msgs::msg::Bool();
        message.data = true;
        RCLCPP_INFO(this->get_logger(), "Sent")
        this->pub->publish(message);
      };
    timer = this->create_wall_timer(1s, timer_callback);
  }
};

int main(int argc, char * argv[])
{
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);
  rclcpp::init(argc, argv);
  rclcpp::executors::SingleThreadedExecutor exec;
  auto pub = std::make_shared<Publisher>("test_pub");
  exec.add_node(pub);
  auto sub = std::make_shared<Subscriber>("test_sub");
  exec.add_node(sub->get_node_base_interface());
  exec.spin();
  rclcpp::shutdown();
  return 0;
}

Is it the expected behavior? What can i do in order to achieve it? Thanks.

edit retag flag offensive close merge delete

Comments

Were you ever able to figure this out? I've hit the same issue. The lifecycle publishers have on_activate and on_deactivate methods but that functionality doesn't seem to be present on the subscribers. I would have assumed the node would handle this automatically but it doesn't appear to.

david.hodo gravatar image david.hodo  ( 2019-01-02 14:48:47 -0500 )edit

Not really. At that time it wasn't implemented on rclcpp, I didn't ask the developers whether they planned to include that. But for the time being i used a flag that was set on the activate function and unset on deactivate, and the callback checks if the flag is set in order to process the message.

Teckel gravatar image Teckel  ( 2019-01-02 17:55:22 -0500 )edit