We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Required Info:
Use this program. The commented lines are used by me to trace the problem, using https://github.com/fmrico/yaets
#include <fstream> // #include "yaets/tracing.hpp" #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/int32.hpp" using namespace std::chrono_literals; using std::placeholders::_1; // yaets::TraceSession session("session1.log"); class ProducerNode : public rclcpp::Node { public: ProducerNode() : Node("producer_node") { pub_1_ = create_publisher<std_msgs::msg::Int32>("topic_1", 100); pub_2_ = create_publisher<std_msgs::msg::Int32>("topic_2", 100); timer_ = create_wall_timer(1ms, std::bind(&ProducerNode::timer_callback, this)); } void timer_callback() { // TRACE_EVENT(session); message_.data += 1; pub_1_->publish(message_); message_.data += 1; pub_2_->publish(message_); } private: rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr pub_1_, pub_2_; rclcpp::TimerBase::SharedPtr timer_; std_msgs::msg::Int32 message_; }; class ConsumerNode : public rclcpp::Node { public: ConsumerNode() : Node("consumer_node") { sub_2_ = create_subscription<std_msgs::msg::Int32>( "topic_2", 100, std::bind(&ConsumerNode::cb_2, this, _1)); sub_1_ = create_subscription<std_msgs::msg::Int32>( "topic_1", 100, std::bind(&ConsumerNode::cb_1, this, _1)); timer_ = create_wall_timer(10ms, std::bind(&ConsumerNode::timer_callback, this)); } void cb_1(const std_msgs::msg::Int32::SharedPtr msg) { // TRACE_EVENT(session); waste_time(500us); } void cb_2(const std_msgs::msg::Int32::SharedPtr msg) { // TRACE_EVENT(session); waste_time(500us); } void timer_callback() { // TRACE_EVENT(session); waste_time(5ms); } void waste_time(const rclcpp::Duration & duration) { auto start = now(); while (now() - start < duration); } private: rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr sub_1_; rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr sub_2_; rclcpp::TimerBase::SharedPtr timer_; }; int main(int argc, char * argv[]) { rclcpp::init(argc, argv); auto node_pub = std::make_shared<ProducerNode>(); auto node_sub = std::make_shared<ConsumerNode>(); // rclcpp::executors::SingleThreadedExecutor executor; rclcpp::executors::MultiThreadedExecutor executor(rclcpp::ExecutorOptions(), 8); executor.add_node(node_pub); executor.add_node(node_sub); executor.spin(); rclcpp::shutdown(); return 0; }
The behavior expected is more or less what happens with SingleThreadedExecution:
Callback for /topic2 (cb2) suffers starvation because most of the time timer and cb1 has event and messages to process
The text was updated successfully, but these errors were encountered:
No branches or pull requests
Bug report
Required Info:
Steps to reproduce issue
Use this program. The commented lines are used by me to trace the problem, using https://github.com/fmrico/yaets
Expected behavior
The behavior expected is more or less what happens with SingleThreadedExecution:
Actual behavior
Callback for /topic2 (cb2) suffers starvation because most of the time timer and cb1 has event and messages to process
The text was updated successfully, but these errors were encountered: