Closed as not planned
Closed as not planned
Description
Bug report
Required Info:
- Operating System:
- Ubuntu 20.04.5 LTS
- Installation type:
- Binary (galactic)
- Version or commit hash:
apt-cache policy ros-galactic-rclcpp
ros-galactic-rclcpp:
Installed: 9.2.1-1focal.20220825.152106
- DDS implementation:
rmw_cyclonedds_cpp
- Client library (if applicable):
rclcpp
Steps to reproduce issue
- Publish a periodic ros topic e.g.
ros2 topic pub /foo std_msgs/String data:\ "hello"
- Build the node below and run it with
ros2 run <package> <node> /foo std_msgs/String
#include <chrono>
#include <thread>
#include <rclcpp/rclcpp.hpp>
class TestNode : public rclcpp::Node {
public:
TestNode()
: Node("test") {}
void subscribe(const std::string& topic, const std::string& dataType) {
RCLCPP_INFO(get_logger(), "Subscribing to %s (%s)", topic.c_str(), dataType.c_str());
// Create a temporary callback group. Will be destroyed when the variable gets out of scope.
// Note that this callback group is unused.
// When the following line is commented, everything works as expected.
auto cbg = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
_subscription = this->create_generic_subscription(
topic, dataType, 10, [this](std::shared_ptr<rclcpp::SerializedMessage> msg) {
RCLCPP_INFO(get_logger(), "Message with %lu bytes received", msg->size());
});
}
void unsubscribe() {
RCLCPP_INFO(get_logger(), "Unsubscribing...");
_subscription.reset();
}
bool isSubscribed() const {
return static_cast<bool>(_subscription);
}
private:
rclcpp::GenericSubscription::SharedPtr _subscription;
};
int main(int argc, char** argv) {
if (argc < 3) return -1;
const std::string topic = argv[1];
const std::string dataType = argv[2];
rclcpp::init(argc, argv);
rclcpp::executors::MultiThreadedExecutor executor;
auto node = std::make_shared<TestNode>();
executor.add_node(node);
std::thread toggleSubscriptionThread([&node, &topic, &dataType]() {
while (rclcpp::ok()) {
if (node->isSubscribed()) {
node->unsubscribe();
} else {
node->subscribe(topic, dataType);
}
std::this_thread::sleep_for(std::chrono::seconds(3));
}
});
executor.spin();
toggleSubscriptionThread.join();
rclcpp::shutdown();
}
Expected behavior
The node above effectively subscribes to a topic and unsubscribes from it after 3 seconds. This is done in an endless loop.
Expected output: Whenever the topic is subscribed, the callback should be triggered and the number of bytes of the message logged to stdout:
[INFO] [1669836475.440711860] [test]: Subscribing to /foo (std_msgs/String)
[INFO] [1669836475.971503209] [test]: Message with 16 bytes received
[INFO] [1669836476.971577131] [test]: Message with 16 bytes received
[INFO] [1669836477.971556368] [test]: Message with 16 bytes received
[INFO] [1669836478.441695409] [test]: Unsubscribing...
[INFO] [1669836481.442314768] [test]: Subscribing to /foo (std_msgs/String)
[INFO] [1669836481.971544881] [test]: Message with 16 bytes received
[INFO] [1669836482.971525189] [test]: Message with 16 bytes received
[INFO] [1669836483.971552590] [test]: Message with 16 bytes received
[INFO] [1669836484.443937982] [test]: Unsubscribing...
Actual behavior
When running the node as is, only messages of the very first subscription are logged. Following subscriptions do not log any messages anymore.
[INFO] [1669836366.327942944] [test]: Subscribing to /foo (std_msgs/String)
[INFO] [1669836366.971507995] [test]: Message with 16 bytes received
[INFO] [1669836367.971542381] [test]: Message with 16 bytes received
[INFO] [1669836368.971561775] [test]: Message with 16 bytes received
[INFO] [1669836369.328940789] [test]: Unsubscribing...
[INFO] [1669836372.329520359] [test]: Subscribing to /foo (std_msgs/String)
# !KO: No message received here!
[INFO] [1669836375.330942839] [test]: Unsubscribing...
[INFO] [1669836378.332094893] [test]: Subscribing to /foo (std_msgs/String)
# !KO: No message received here!
[INFO] [1669836381.333177594] [test]: Unsubscribing...
Additional information
The reason why it does not work is the temporary creation of a callback group. If one comments the line
auto cbg = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
the behavior is as expected
Metadata
Metadata
Assignees
Labels
No labels